Skip to content

Commit 3ef3aaf

Browse files
authored
Add effort command interface to all joints (backport of #302) (#351)
1 parent 309d2c6 commit 3ef3aaf

File tree

1 file changed

+6
-0
lines changed

1 file changed

+6
-0
lines changed

urdf/inc/ur_joint_control.xacro

Lines changed: 6 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -8,6 +8,7 @@
88
<joint name="${tf_prefix}shoulder_pan_joint">
99
<command_interface name="position"/>
1010
<command_interface name="velocity"/>
11+
<command_interface name="effort"/>
1112
<state_interface name="position">
1213
<!-- initial position for the mock system and simulation -->
1314
<param name="initial_value">${initial_positions['shoulder_pan_joint']}</param>
@@ -22,6 +23,7 @@
2223
<joint name="${tf_prefix}shoulder_lift_joint">
2324
<command_interface name="position"/>
2425
<command_interface name="velocity"/>
26+
<command_interface name="effort"/>
2527
<state_interface name="position">
2628
<!-- initial position for the mock system and simulation -->
2729
<param name="initial_value">${initial_positions['shoulder_lift_joint']}</param>
@@ -36,6 +38,7 @@
3638
<joint name="${tf_prefix}elbow_joint">
3739
<command_interface name="position"/>
3840
<command_interface name="velocity"/>
41+
<command_interface name="effort"/>
3942
<state_interface name="position">
4043
<!-- initial position for the mock system and simulation -->
4144
<param name="initial_value">${initial_positions['elbow_joint']}</param>
@@ -50,6 +53,7 @@
5053
<joint name="${tf_prefix}wrist_1_joint">
5154
<command_interface name="position"/>
5255
<command_interface name="velocity"/>
56+
<command_interface name="effort"/>
5357
<state_interface name="position">
5458
<!-- initial position for the mock system and simulation -->
5559
<param name="initial_value">${initial_positions['wrist_1_joint']}</param>
@@ -64,6 +68,7 @@
6468
<joint name="${tf_prefix}wrist_2_joint">
6569
<command_interface name="position"/>
6670
<command_interface name="velocity"/>
71+
<command_interface name="effort"/>
6772
<state_interface name="position">
6873
<!-- initial position for the mock system and simulation -->
6974
<param name="initial_value">${initial_positions['wrist_2_joint']}</param>
@@ -78,6 +83,7 @@
7883
<joint name="${tf_prefix}wrist_3_joint">
7984
<command_interface name="position"/>
8085
<command_interface name="velocity"/>
86+
<command_interface name="effort"/>
8187
<state_interface name="position">
8288
<!-- initial position for the mock system and simulation -->
8389
<param name="initial_value">${initial_positions['wrist_3_joint']}</param>

0 commit comments

Comments
 (0)