Skip to content

Commit a9767bb

Browse files
Felix ExnerVinDp
authored andcommitted
Remove limits definitions from ros2_control command interfaces
The controller manager's limit parser considers the limits from the URDF now. Removing this superfluous definitions should improve clarity. Since the CM is also actually picking up the limits from the ros2_control tags we get warnings when starting up, since the fields were missing a dollar sign for the calculations, anyway.
1 parent 462f383 commit a9767bb

File tree

1 file changed

+13
-48
lines changed

1 file changed

+13
-48
lines changed

urdf/inc/ur_joint_control.xacro

Lines changed: 13 additions & 48 deletions
Original file line numberDiff line numberDiff line change
@@ -1,18 +1,13 @@
11
<?xml version="1.0"?>
2+
23
<robot xmlns:xacro="http://wiki.ros.org/xacro">
34
<xacro:macro name="ur_joint_control_description" params="
45
tf_prefix
56
initial_positions:=${dict(shoulder_pan_joint=0.0,shoulder_lift_joint=-1.57,elbow_joint=0.0,wrist_1_joint=-1.57,wrist_2_joint=0.0,wrist_3_joint=0.0)}
67
">
78
<joint name="${tf_prefix}shoulder_pan_joint">
8-
<command_interface name="position">
9-
<param name="min">{-2*pi}</param>
10-
<param name="max">{2*pi}</param>
11-
</command_interface>
12-
<command_interface name="velocity">
13-
<param name="min">-3.15</param>
14-
<param name="max">3.15</param>
15-
</command_interface>
9+
<command_interface name="position"/>
10+
<command_interface name="velocity"/>
1611
<state_interface name="position">
1712
<!-- initial position for the mock system and simulation -->
1813
<param name="initial_value">${initial_positions['shoulder_pan_joint']}</param>
@@ -25,14 +20,8 @@
2520
</state_interface>
2621
</joint>
2722
<joint name="${tf_prefix}shoulder_lift_joint">
28-
<command_interface name="position">
29-
<param name="min">{-2*pi}</param>
30-
<param name="max">{2*pi}</param>
31-
</command_interface>
32-
<command_interface name="velocity">
33-
<param name="min">-3.15</param>
34-
<param name="max">3.15</param>
35-
</command_interface>
23+
<command_interface name="position"/>
24+
<command_interface name="velocity"/>
3625
<state_interface name="position">
3726
<!-- initial position for the mock system and simulation -->
3827
<param name="initial_value">${initial_positions['shoulder_lift_joint']}</param>
@@ -45,14 +34,8 @@
4534
</state_interface>
4635
</joint>
4736
<joint name="${tf_prefix}elbow_joint">
48-
<command_interface name="position">
49-
<param name="min">{-pi}</param>
50-
<param name="max">{pi}</param>
51-
</command_interface>
52-
<command_interface name="velocity">
53-
<param name="min">-3.15</param>
54-
<param name="max">3.15</param>
55-
</command_interface>
37+
<command_interface name="position"/>
38+
<command_interface name="velocity"/>
5639
<state_interface name="position">
5740
<!-- initial position for the mock system and simulation -->
5841
<param name="initial_value">${initial_positions['elbow_joint']}</param>
@@ -65,14 +48,8 @@
6548
</state_interface>
6649
</joint>
6750
<joint name="${tf_prefix}wrist_1_joint">
68-
<command_interface name="position">
69-
<param name="min">{-2*pi}</param>
70-
<param name="max">{2*pi}</param>
71-
</command_interface>
72-
<command_interface name="velocity">
73-
<param name="min">-3.2</param>
74-
<param name="max">3.2</param>
75-
</command_interface>
51+
<command_interface name="position"/>
52+
<command_interface name="velocity"/>
7653
<state_interface name="position">
7754
<!-- initial position for the mock system and simulation -->
7855
<param name="initial_value">${initial_positions['wrist_1_joint']}</param>
@@ -85,14 +62,8 @@
8562
</state_interface>
8663
</joint>
8764
<joint name="${tf_prefix}wrist_2_joint">
88-
<command_interface name="position">
89-
<param name="min">{-2*pi}</param>
90-
<param name="max">{2*pi}</param>
91-
</command_interface>
92-
<command_interface name="velocity">
93-
<param name="min">-3.2</param>
94-
<param name="max">3.2</param>
95-
</command_interface>
65+
<command_interface name="position"/>
66+
<command_interface name="velocity"/>
9667
<state_interface name="position">
9768
<!-- initial position for the mock system and simulation -->
9869
<param name="initial_value">${initial_positions['wrist_2_joint']}</param>
@@ -105,14 +76,8 @@
10576
</state_interface>
10677
</joint>
10778
<joint name="${tf_prefix}wrist_3_joint">
108-
<command_interface name="position">
109-
<param name="min">{-2*pi}</param>
110-
<param name="max">{2*pi}</param>
111-
</command_interface>
112-
<command_interface name="velocity">
113-
<param name="min">-3.2</param>
114-
<param name="max">3.2</param>
115-
</command_interface>
79+
<command_interface name="position"/>
80+
<command_interface name="velocity"/>
11681
<state_interface name="position">
11782
<!-- initial position for the mock system and simulation -->
11883
<param name="initial_value">${initial_positions['wrist_3_joint']}</param>

0 commit comments

Comments
 (0)