Skip to content

Commit d5df5e1

Browse files
authored
Fix ros2 control xacro (#213)
* [ur_controllers] Add exec_depend to joint_state_broadcaster Signed-off-by: Gaël Écorchard <[email protected]> * [ur_bringup, ur_controllers] Fix previous commit The dependency to `joint_state_broadcaster` should be in `ur_bringup` not `ur_controllers` as was done in previous commit. Signed-off-by: Gaël Écorchard <[email protected]> * [ur_description] Fix xacro syntax Signed-off-by: Gaël Écorchard <[email protected]> * [ur_bringup] Remove unused joint_state_publisher Remove unused dependency to `joint_state_publisher` in `package.xml`. Signed-off-by: Gaël Écorchard <[email protected]>
1 parent e454791 commit d5df5e1

File tree

2 files changed

+13
-13
lines changed

2 files changed

+13
-13
lines changed

ur_bringup/package.xml

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -21,7 +21,7 @@
2121
<buildtool_depend>ament_cmake</buildtool_depend>
2222

2323
<exec_depend>controller_manager</exec_depend>
24-
<exec_depend>joint_state_publisher</exec_depend>
24+
<exec_depend>joint_state_broadcaster</exec_depend>
2525
<exec_depend>launch</exec_depend>
2626
<exec_depend>launch_ros</exec_depend>
2727
<exec_depend>rviz2</exec_depend>

ur_description/urdf/ur.ros2_control.xacro

Lines changed: 12 additions & 12 deletions
Original file line numberDiff line numberDiff line change
@@ -42,8 +42,8 @@
4242
</hardware>
4343
<joint name="${prefix}shoulder_pan_joint">
4444
<command_interface name="position">
45-
<param name="min">{-2*pi}</param>
46-
<param name="max">{2*pi}</param>
45+
<param name="min">${-2*pi}</param>
46+
<param name="max">${2*pi}</param>
4747
</command_interface>
4848
<command_interface name="velocity">
4949
<param name="min">-3.15</param>
@@ -56,8 +56,8 @@
5656
</joint>
5757
<joint name="${prefix}shoulder_lift_joint">
5858
<command_interface name="position">
59-
<param name="min">{-2*pi}</param>
60-
<param name="max">{2*pi}</param>
59+
<param name="min">${-2*pi}</param>
60+
<param name="max">${2*pi}</param>
6161
</command_interface>
6262
<command_interface name="velocity">
6363
<param name="min">-3.15</param>
@@ -70,8 +70,8 @@
7070
</joint>
7171
<joint name="${prefix}elbow_joint">
7272
<command_interface name="position">
73-
<param name="min">{-pi}</param>
74-
<param name="max">{pi}</param>
73+
<param name="min">${-pi}</param>
74+
<param name="max">${pi}</param>
7575
</command_interface>
7676
<command_interface name="velocity">
7777
<param name="min">-3.15</param>
@@ -84,8 +84,8 @@
8484
</joint>
8585
<joint name="${prefix}wrist_1_joint">
8686
<command_interface name="position">
87-
<param name="min">{-2*pi}</param>
88-
<param name="max">{2*pi}</param>
87+
<param name="min">${-2*pi}</param>
88+
<param name="max">${2*pi}</param>
8989
</command_interface>
9090
<command_interface name="velocity">
9191
<param name="min">-3.2</param>
@@ -98,8 +98,8 @@
9898
</joint>
9999
<joint name="${prefix}wrist_2_joint">
100100
<command_interface name="position">
101-
<param name="min">{-2*pi}</param>
102-
<param name="max">{2*pi}</param>
101+
<param name="min">${-2*pi}</param>
102+
<param name="max">${2*pi}</param>
103103
</command_interface>
104104
<command_interface name="velocity">
105105
<param name="min">-3.2</param>
@@ -112,8 +112,8 @@
112112
</joint>
113113
<joint name="${prefix}wrist_3_joint">
114114
<command_interface name="position">
115-
<param name="min">{-2*pi}</param>
116-
<param name="max">{2*pi}</param>
115+
<param name="min">${-2*pi}</param>
116+
<param name="max">${2*pi}</param>
117117
</command_interface>
118118
<command_interface name="velocity">
119119
<param name="min">-3.2</param>

0 commit comments

Comments
 (0)