Skip to content

Commit b7895c0

Browse files
mergify[bot]Felix Exner
andauthored
Remove ros2_control limit params (#168)
They have never been parsed before Jazzy and in Jazzy the URDF limits will be used unless a more strict limit is configured inside the ros2_control tags. (cherry picked from commit 410533a) Co-authored-by: Felix Exner <[email protected]>
1 parent aced9eb commit b7895c0

File tree

1 file changed

+12
-48
lines changed

1 file changed

+12
-48
lines changed

urdf/ur.ros2_control.xacro

Lines changed: 12 additions & 48 deletions
Original file line numberDiff line numberDiff line change
@@ -66,14 +66,8 @@
6666
</xacro:unless>
6767
</hardware>
6868
<joint name="${tf_prefix}shoulder_pan_joint">
69-
<command_interface name="position">
70-
<param name="min">{-2*pi}</param>
71-
<param name="max">{2*pi}</param>
72-
</command_interface>
73-
<command_interface name="velocity">
74-
<param name="min">-3.15</param>
75-
<param name="max">3.15</param>
76-
</command_interface>
69+
<command_interface name="position"/>
70+
<command_interface name="velocity"/>
7771
<state_interface name="position">
7872
<!-- initial position for the FakeSystem and simulation -->
7973
<param name="initial_value">${initial_positions['shoulder_pan_joint']}</param>
@@ -82,14 +76,8 @@
8276
<state_interface name="effort"/>
8377
</joint>
8478
<joint name="${tf_prefix}shoulder_lift_joint">
85-
<command_interface name="position">
86-
<param name="min">{-2*pi}</param>
87-
<param name="max">{2*pi}</param>
88-
</command_interface>
89-
<command_interface name="velocity">
90-
<param name="min">-3.15</param>
91-
<param name="max">3.15</param>
92-
</command_interface>
79+
<command_interface name="position"/>
80+
<command_interface name="velocity"/>
9381
<state_interface name="position">
9482
<!-- initial position for the FakeSystem and simulation -->
9583
<param name="initial_value">${initial_positions['shoulder_lift_joint']}</param>
@@ -98,14 +86,8 @@
9886
<state_interface name="effort"/>
9987
</joint>
10088
<joint name="${tf_prefix}elbow_joint">
101-
<command_interface name="position">
102-
<param name="min">{-pi}</param>
103-
<param name="max">{pi}</param>
104-
</command_interface>
105-
<command_interface name="velocity">
106-
<param name="min">-3.15</param>
107-
<param name="max">3.15</param>
108-
</command_interface>
89+
<command_interface name="position"/>
90+
<command_interface name="velocity"/>
10991
<state_interface name="position">
11092
<!-- initial position for the FakeSystem and simulation -->
11193
<param name="initial_value">${initial_positions['elbow_joint']}</param>
@@ -114,14 +96,8 @@
11496
<state_interface name="effort"/>
11597
</joint>
11698
<joint name="${tf_prefix}wrist_1_joint">
117-
<command_interface name="position">
118-
<param name="min">{-2*pi}</param>
119-
<param name="max">{2*pi}</param>
120-
</command_interface>
121-
<command_interface name="velocity">
122-
<param name="min">-3.2</param>
123-
<param name="max">3.2</param>
124-
</command_interface>
99+
<command_interface name="position"/>
100+
<command_interface name="velocity"/>
125101
<state_interface name="position">
126102
<!-- initial position for the FakeSystem and simulation -->
127103
<param name="initial_value">${initial_positions['wrist_1_joint']}</param>
@@ -130,14 +106,8 @@
130106
<state_interface name="effort"/>
131107
</joint>
132108
<joint name="${tf_prefix}wrist_2_joint">
133-
<command_interface name="position">
134-
<param name="min">{-2*pi}</param>
135-
<param name="max">{2*pi}</param>
136-
</command_interface>
137-
<command_interface name="velocity">
138-
<param name="min">-3.2</param>
139-
<param name="max">3.2</param>
140-
</command_interface>
109+
<command_interface name="position"/>
110+
<command_interface name="velocity"/>
141111
<state_interface name="position">
142112
<!-- initial position for the FakeSystem and simulation -->
143113
<param name="initial_value">${initial_positions['wrist_2_joint']}</param>
@@ -146,14 +116,8 @@
146116
<state_interface name="effort"/>
147117
</joint>
148118
<joint name="${tf_prefix}wrist_3_joint">
149-
<command_interface name="position">
150-
<param name="min">{-2*pi}</param>
151-
<param name="max">{2*pi}</param>
152-
</command_interface>
153-
<command_interface name="velocity">
154-
<param name="min">-3.2</param>
155-
<param name="max">3.2</param>
156-
</command_interface>
119+
<command_interface name="position"/>
120+
<command_interface name="velocity"/>
157121
<state_interface name="position">
158122
<!-- initial position for the FakeSystem and simulation -->
159123
<param name="initial_value">${initial_positions['wrist_3_joint']}</param>

0 commit comments

Comments
 (0)