Skip to content

Commit 6a5ef7e

Browse files
mergify[bot]urfeex
andauthored
Add effort command interface to all joints (#350)
Co-authored-by: Felix Exner <feex@universal-robots.com>
1 parent 611564e commit 6a5ef7e

File tree

1 file changed

+6
-0
lines changed

1 file changed

+6
-0
lines changed

urdf/ur.ros2_control.xacro

Lines changed: 6 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -69,6 +69,7 @@
6969
<joint name="${tf_prefix}shoulder_pan_joint">
7070
<command_interface name="position"/>
7171
<command_interface name="velocity"/>
72+
<command_interface name="effort"/>
7273
<state_interface name="position">
7374
<!-- initial position for the FakeSystem and simulation -->
7475
<param name="initial_value">${initial_positions['shoulder_pan_joint']}</param>
@@ -79,6 +80,7 @@
7980
<joint name="${tf_prefix}shoulder_lift_joint">
8081
<command_interface name="position"/>
8182
<command_interface name="velocity"/>
83+
<command_interface name="effort"/>
8284
<state_interface name="position">
8385
<!-- initial position for the FakeSystem and simulation -->
8486
<param name="initial_value">${initial_positions['shoulder_lift_joint']}</param>
@@ -89,6 +91,7 @@
8991
<joint name="${tf_prefix}elbow_joint">
9092
<command_interface name="position"/>
9193
<command_interface name="velocity"/>
94+
<command_interface name="effort"/>
9295
<state_interface name="position">
9396
<!-- initial position for the FakeSystem and simulation -->
9497
<param name="initial_value">${initial_positions['elbow_joint']}</param>
@@ -99,6 +102,7 @@
99102
<joint name="${tf_prefix}wrist_1_joint">
100103
<command_interface name="position"/>
101104
<command_interface name="velocity"/>
105+
<command_interface name="effort"/>
102106
<state_interface name="position">
103107
<!-- initial position for the FakeSystem and simulation -->
104108
<param name="initial_value">${initial_positions['wrist_1_joint']}</param>
@@ -109,6 +113,7 @@
109113
<joint name="${tf_prefix}wrist_2_joint">
110114
<command_interface name="position"/>
111115
<command_interface name="velocity"/>
116+
<command_interface name="effort"/>
112117
<state_interface name="position">
113118
<!-- initial position for the FakeSystem and simulation -->
114119
<param name="initial_value">${initial_positions['wrist_2_joint']}</param>
@@ -119,6 +124,7 @@
119124
<joint name="${tf_prefix}wrist_3_joint">
120125
<command_interface name="position"/>
121126
<command_interface name="velocity"/>
127+
<command_interface name="effort"/>
122128
<state_interface name="position">
123129
<!-- initial position for the FakeSystem and simulation -->
124130
<param name="initial_value">${initial_positions['wrist_3_joint']}</param>

0 commit comments

Comments
 (0)