Skip to content

Commit 3b0f10c

Browse files
authored
Do not add effort command interface for GZ sim (#355)
gz_ros2_control seems to not cope fine with having the effort command interface. As this is only an issue with Humble (Only tested with GZ Sim Fortress), let's deactivate it in that case.
1 parent 720e341 commit 3b0f10c

File tree

1 file changed

+18
-6
lines changed

1 file changed

+18
-6
lines changed

urdf/ur.ros2_control.xacro

Lines changed: 18 additions & 6 deletions
Original file line numberDiff line numberDiff line change
@@ -69,7 +69,9 @@
6969
<joint name="${tf_prefix}shoulder_pan_joint">
7070
<command_interface name="position"/>
7171
<command_interface name="velocity"/>
72-
<command_interface name="effort"/>
72+
<xacro:unless value="$(arg sim_ignition)">
73+
<command_interface name="effort"/>
74+
</xacro:unless>
7375
<state_interface name="position">
7476
<!-- initial position for the FakeSystem and simulation -->
7577
<param name="initial_value">${initial_positions['shoulder_pan_joint']}</param>
@@ -80,7 +82,9 @@
8082
<joint name="${tf_prefix}shoulder_lift_joint">
8183
<command_interface name="position"/>
8284
<command_interface name="velocity"/>
83-
<command_interface name="effort"/>
85+
<xacro:unless value="$(arg sim_ignition)">
86+
<command_interface name="effort"/>
87+
</xacro:unless>
8488
<state_interface name="position">
8589
<!-- initial position for the FakeSystem and simulation -->
8690
<param name="initial_value">${initial_positions['shoulder_lift_joint']}</param>
@@ -91,7 +95,9 @@
9195
<joint name="${tf_prefix}elbow_joint">
9296
<command_interface name="position"/>
9397
<command_interface name="velocity"/>
94-
<command_interface name="effort"/>
98+
<xacro:unless value="$(arg sim_ignition)">
99+
<command_interface name="effort"/>
100+
</xacro:unless>
95101
<state_interface name="position">
96102
<!-- initial position for the FakeSystem and simulation -->
97103
<param name="initial_value">${initial_positions['elbow_joint']}</param>
@@ -102,7 +108,9 @@
102108
<joint name="${tf_prefix}wrist_1_joint">
103109
<command_interface name="position"/>
104110
<command_interface name="velocity"/>
105-
<command_interface name="effort"/>
111+
<xacro:unless value="$(arg sim_ignition)">
112+
<command_interface name="effort"/>
113+
</xacro:unless>
106114
<state_interface name="position">
107115
<!-- initial position for the FakeSystem and simulation -->
108116
<param name="initial_value">${initial_positions['wrist_1_joint']}</param>
@@ -113,7 +121,9 @@
113121
<joint name="${tf_prefix}wrist_2_joint">
114122
<command_interface name="position"/>
115123
<command_interface name="velocity"/>
116-
<command_interface name="effort"/>
124+
<xacro:unless value="$(arg sim_ignition)">
125+
<command_interface name="effort"/>
126+
</xacro:unless>
117127
<state_interface name="position">
118128
<!-- initial position for the FakeSystem and simulation -->
119129
<param name="initial_value">${initial_positions['wrist_2_joint']}</param>
@@ -124,7 +134,9 @@
124134
<joint name="${tf_prefix}wrist_3_joint">
125135
<command_interface name="position"/>
126136
<command_interface name="velocity"/>
127-
<command_interface name="effort"/>
137+
<xacro:unless value="$(arg sim_ignition)">
138+
<command_interface name="effort"/>
139+
</xacro:unless>
128140
<state_interface name="position">
129141
<!-- initial position for the FakeSystem and simulation -->
130142
<param name="initial_value">${initial_positions['wrist_3_joint']}</param>

0 commit comments

Comments
 (0)