Skip to content
This repository was archived by the owner on Mar 28, 2025. It is now read-only.

Commit 541939c

Browse files
christophfroehlichmergify[bot]
authored andcommitted
Add an example with a passive joint (#172)
Co-authored-by: Alejandro Hernández Cordero <[email protected]> (cherry picked from commit 7d5ec5d) # Conflicts: # doc/index.rst
1 parent fe829ce commit 541939c

5 files changed

+444
-4
lines changed

doc/index.rst

+55-4
Original file line numberDiff line numberDiff line change
@@ -220,7 +220,12 @@ gazebo_ros2_control_demos
220220

221221
This package contains the contents for testing gazebo_ros2_control. It is running Gazebo Classic and some other ROS 2 nodes.
222222

223-
There are some examples in the *Gazebo_ros2_control_demos* package. These examples allow to launch a cart in a 30 meter rail.
223+
There are some examples in the *Gazebo_ros2_control_demos* package.
224+
225+
Cart on rail
226+
-----------------------------------------------------------
227+
228+
These examples allow to launch a cart in a 30 meter rail.
224229

225230
.. image:: img/cart.gif
226231
:alt: Cart
@@ -232,9 +237,6 @@ You can run some of the configuration running the following commands:
232237
ros2 launch gazebo_ros2_control_demos cart_example_position.launch.py
233238
ros2 launch gazebo_ros2_control_demos cart_example_velocity.launch.py
234239
ros2 launch gazebo_ros2_control_demos cart_example_effort.launch.py
235-
ros2 launch gazebo_ros2_control_demos diff_drive.launch.py
236-
ros2 launch gazebo_ros2_control_demos tricycle_drive.launch.py
237-
238240
239241
When the Gazebo world is launched you can run some of the following commands to move the cart.
240242

@@ -243,11 +245,40 @@ When the Gazebo world is launched you can run some of the following commands to
243245
ros2 run gazebo_ros2_control_demos example_position
244246
ros2 run gazebo_ros2_control_demos example_velocity
245247
ros2 run gazebo_ros2_control_demos example_effort
248+
249+
Mobile robots
250+
-----------------------------------------------------------
251+
252+
You can run some of the mobile robots running the following commands:
253+
254+
.. code-block:: shell
255+
256+
ros2 launch gazebo_ros2_control_demos diff_drive.launch.py
257+
ros2 launch gazebo_ros2_control_demos tricycle_drive.launch.py
258+
259+
260+
When the Gazebo world is launched you can run some of the following commands to move the robots.
261+
262+
.. code-block:: shell
263+
246264
ros2 run gazebo_ros2_control_demos example_diff_drive
247265
ros2 run gazebo_ros2_control_demos example_tricycle_drive
248266
267+
<<<<<<< HEAD
249268

250269
The following example shows parallel gripper with mimic joint:
270+
=======
271+
Gripper
272+
-----------------------------------------------------------
273+
The following example shows a parallel gripper with a mimic joint:
274+
275+
.. image:: img/gripper.gif
276+
:alt: Cart
277+
278+
.. code-block:: shell
279+
280+
ros2 launch gazebo_ros2_control_demos gripper_mimic_joint_example_position.launch.py
281+
>>>>>>> 7d5ec5d (Add an example with a passive joint (#172))
251282

252283
.. image:: img/gripper.gif
253284
:alt: Cart
@@ -264,3 +295,23 @@ Send example commands:
264295
.. code-block:: shell
265296
266297
ros2 run gazebo_ros2_control_demos example_gripper
298+
299+
Pendulum with passive joints
300+
-----------------------------------------------------------
301+
302+
The following example shows a cart with a pendulum arm. This uses the effort command interface for the cart's
303+
degree of freedom on the rail, and the physics of the passive joint of the pendulum is solved correctly.
304+
305+
.. code-block:: shell
306+
307+
ros2 launch gazebo_ros2_control_demos pendulum_example_effort.launch.py
308+
ros2 run gazebo_ros2_control_demos example_effort
309+
310+
.. note::
311+
312+
If the position command interface is used instead, the motion of the pendulum is not calculated correctly and does not move at all, see this `PR <https://github.com/ros-controls/gazebo_ros2_control/issues/240>`__. This also holds true if a mimicked joint with position interface is used. To demonstrate this, run
313+
314+
.. code-block:: shell
315+
316+
ros2 launch gazebo_ros2_control_demos pendulum_example_position.launch.py
317+
ros2 run gazebo_ros2_control_demos example_position
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,86 @@
1+
# Copyright 2024 ros2_control Development Team
2+
#
3+
# Licensed under the Apache License, Version 2.0 (the "License");
4+
# you may not use this file except in compliance with the License.
5+
# You may obtain a copy of the License at
6+
#
7+
# http://www.apache.org/licenses/LICENSE-2.0
8+
#
9+
# Unless required by applicable law or agreed to in writing, software
10+
# distributed under the License is distributed on an "AS IS" BASIS,
11+
# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
12+
# See the License for the specific language governing permissions and
13+
# limitations under the License.
14+
15+
import os
16+
17+
from ament_index_python.packages import get_package_share_directory
18+
19+
20+
from launch import LaunchDescription
21+
from launch.actions import ExecuteProcess, IncludeLaunchDescription, RegisterEventHandler
22+
from launch.event_handlers import OnProcessExit
23+
from launch.launch_description_sources import PythonLaunchDescriptionSource
24+
25+
from launch_ros.actions import Node
26+
27+
import xacro
28+
29+
30+
def generate_launch_description():
31+
gazebo = IncludeLaunchDescription(
32+
PythonLaunchDescriptionSource([os.path.join(
33+
get_package_share_directory('gazebo_ros'), 'launch'), '/gazebo.launch.py']),
34+
)
35+
36+
gazebo_ros2_control_demos_path = os.path.join(
37+
get_package_share_directory('gazebo_ros2_control_demos'))
38+
39+
xacro_file = os.path.join(gazebo_ros2_control_demos_path,
40+
'urdf',
41+
'test_pendulum_effort.xacro.urdf')
42+
43+
doc = xacro.parse(open(xacro_file))
44+
xacro.process_doc(doc)
45+
params = {'robot_description': doc.toxml()}
46+
47+
node_robot_state_publisher = Node(
48+
package='robot_state_publisher',
49+
executable='robot_state_publisher',
50+
output='screen',
51+
parameters=[params]
52+
)
53+
54+
spawn_entity = Node(package='gazebo_ros', executable='spawn_entity.py',
55+
arguments=['-topic', 'robot_description',
56+
'-entity', 'cartpole'],
57+
output='screen')
58+
59+
load_joint_state_controller = ExecuteProcess(
60+
cmd=['ros2', 'control', 'load_controller', '--set-state', 'active',
61+
'joint_state_broadcaster'],
62+
output='screen'
63+
)
64+
65+
load_joint_trajectory_controller = ExecuteProcess(
66+
cmd=['ros2', 'control', 'load_controller', '--set-state', 'active', 'effort_controller'],
67+
output='screen'
68+
)
69+
70+
return LaunchDescription([
71+
RegisterEventHandler(
72+
event_handler=OnProcessExit(
73+
target_action=spawn_entity,
74+
on_exit=[load_joint_state_controller],
75+
)
76+
),
77+
RegisterEventHandler(
78+
event_handler=OnProcessExit(
79+
target_action=load_joint_state_controller,
80+
on_exit=[load_joint_trajectory_controller],
81+
)
82+
),
83+
gazebo,
84+
node_robot_state_publisher,
85+
spawn_entity,
86+
])
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,87 @@
1+
# Copyright 2024 ros2_control Development Team
2+
#
3+
# Licensed under the Apache License, Version 2.0 (the "License");
4+
# you may not use this file except in compliance with the License.
5+
# You may obtain a copy of the License at
6+
#
7+
# http://www.apache.org/licenses/LICENSE-2.0
8+
#
9+
# Unless required by applicable law or agreed to in writing, software
10+
# distributed under the License is distributed on an "AS IS" BASIS,
11+
# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
12+
# See the License for the specific language governing permissions and
13+
# limitations under the License.
14+
15+
import os
16+
17+
from ament_index_python.packages import get_package_share_directory
18+
19+
20+
from launch import LaunchDescription
21+
from launch.actions import ExecuteProcess, IncludeLaunchDescription, RegisterEventHandler
22+
from launch.event_handlers import OnProcessExit
23+
from launch.launch_description_sources import PythonLaunchDescriptionSource
24+
25+
from launch_ros.actions import Node
26+
27+
import xacro
28+
29+
30+
def generate_launch_description():
31+
gazebo = IncludeLaunchDescription(
32+
PythonLaunchDescriptionSource([os.path.join(
33+
get_package_share_directory('gazebo_ros'), 'launch'), '/gazebo.launch.py']),
34+
)
35+
36+
gazebo_ros2_control_demos_path = os.path.join(
37+
get_package_share_directory('gazebo_ros2_control_demos'))
38+
39+
xacro_file = os.path.join(gazebo_ros2_control_demos_path,
40+
'urdf',
41+
'test_pendulum_position.xacro.urdf')
42+
43+
doc = xacro.parse(open(xacro_file))
44+
xacro.process_doc(doc)
45+
params = {'robot_description': doc.toxml()}
46+
47+
node_robot_state_publisher = Node(
48+
package='robot_state_publisher',
49+
executable='robot_state_publisher',
50+
output='screen',
51+
parameters=[params]
52+
)
53+
54+
spawn_entity = Node(package='gazebo_ros', executable='spawn_entity.py',
55+
arguments=['-topic', 'robot_description',
56+
'-entity', 'cartpole'],
57+
output='screen')
58+
59+
load_joint_state_controller = ExecuteProcess(
60+
cmd=['ros2', 'control', 'load_controller', '--set-state', 'active',
61+
'joint_state_broadcaster'],
62+
output='screen'
63+
)
64+
65+
load_joint_trajectory_controller = ExecuteProcess(
66+
cmd=['ros2', 'control', 'load_controller', '--set-state', 'active',
67+
'joint_trajectory_controller'],
68+
output='screen'
69+
)
70+
71+
return LaunchDescription([
72+
RegisterEventHandler(
73+
event_handler=OnProcessExit(
74+
target_action=spawn_entity,
75+
on_exit=[load_joint_state_controller],
76+
)
77+
),
78+
RegisterEventHandler(
79+
event_handler=OnProcessExit(
80+
target_action=load_joint_state_controller,
81+
on_exit=[load_joint_trajectory_controller],
82+
)
83+
),
84+
gazebo,
85+
node_robot_state_publisher,
86+
spawn_entity,
87+
])
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,108 @@
1+
<?xml version="1.0"?>
2+
<robot xmlns:xacro="http://www.ros.org/wiki/xacro" name="pendulum on cart">
3+
4+
<xacro:macro name="quadr_block" params="mass width height name">
5+
<link name="${name}">
6+
<collision>
7+
<geometry>
8+
<box size="${width} ${width} ${height}"/>
9+
</geometry>
10+
<origin xyz="0 0 0"/>
11+
</collision>
12+
<visual>
13+
<geometry>
14+
<box size="${width} ${width} ${height}"/>
15+
</geometry>
16+
<origin xyz="0 0 ${height/2}"/>
17+
<material name="blue">
18+
<color rgba="0 0 .8 1"/>
19+
</material>
20+
</visual>
21+
<inertial>
22+
<origin xyz="0 0 ${height/2}" rpy="0 0 0"/>
23+
<mass value="${mass}"/>
24+
<inertia
25+
ixx="${mass / 12.0 * (width*width + height*height)}" ixy="0.0" ixz="0.0"
26+
iyy="${mass / 12.0 * (height*height + width*width)}" iyz="0.0"
27+
izz="${mass / 12.0 * (width*width + width*width)}"/>
28+
</inertial>
29+
</link>
30+
</xacro:macro>
31+
32+
<link name="world"/>
33+
34+
<link name="slideBar">
35+
<visual>
36+
<geometry>
37+
<box size="30 0.05 0.05"/>
38+
</geometry>
39+
<origin xyz="0 0 0"/>
40+
<material name="green">
41+
<color rgba="0 0.8 .8 1"/>
42+
</material>
43+
</visual>
44+
<inertial>
45+
<mass value="100"/>
46+
<inertia ixx="1.0" ixy="0.0" ixz="0.0" iyy="1.0" iyz="0.0" izz="1.0"/>
47+
</inertial>
48+
</link>
49+
50+
<xacro:quadr_block name="cart" mass="10" width="0.5" height="0.2"/>
51+
52+
<xacro:quadr_block name="pendulum" mass="1" width="0.2" height="1.0"/>
53+
54+
<joint name="world_to_base" type="fixed">
55+
<origin rpy="0 0 0" xyz="0 0 1"/>
56+
<parent link="world"/>
57+
<child link="slideBar"/>
58+
</joint>
59+
60+
<joint name="slider_to_cart" type="prismatic">
61+
<axis xyz="1 0 0"/>
62+
<origin xyz="0.0 0.0 0.0"/>
63+
<parent link="slideBar"/>
64+
<child link="cart"/>
65+
<limit effort="1000.0" lower="-15" upper="15" velocity="30"/>
66+
<dynamics damping="0.3" friction="0.0"/>
67+
</joint>
68+
69+
<joint name="cart_to_pendulum" type="revolute">
70+
<axis xyz="0 1 0"/>
71+
<origin xyz="0.0 0.35 0.0" rpy="0 0.1 0"/>
72+
<parent link="cart"/>
73+
<child link="pendulum"/>
74+
<limit effort="10000.0" lower="-100000" upper="100000" velocity="100000"/>
75+
<dynamics damping="0.1" friction="0.0"/>
76+
</joint>
77+
78+
<ros2_control name="GazeboSystem" type="system">
79+
<hardware>
80+
<plugin>gazebo_ros2_control/GazeboSystem</plugin>
81+
</hardware>
82+
<joint name="slider_to_cart">
83+
<command_interface name="effort">
84+
<param name="min">-1000</param>
85+
<param name="max">1000</param>
86+
</command_interface>
87+
<state_interface name="position">
88+
<param name="initial_value">1.0</param>
89+
</state_interface>
90+
<state_interface name="velocity"/>
91+
<state_interface name="effort"/>
92+
</joint>
93+
<joint name="cart_to_pendulum">
94+
<state_interface name="position">
95+
<!-- this does not work if no command interface is set -->
96+
<!-- <param name="initial_value">1.57</param> -->
97+
</state_interface>
98+
<state_interface name="velocity"/>
99+
<state_interface name="effort"/>
100+
</joint>
101+
</ros2_control>
102+
103+
<gazebo>
104+
<plugin filename="libgazebo_ros2_control.so" name="gazebo_ros2_control">
105+
<parameters>$(find gazebo_ros2_control_demos)/config/cart_controller_effort.yaml</parameters>
106+
</plugin>
107+
</gazebo>
108+
</robot>

0 commit comments

Comments
 (0)