Skip to content

Commit 6b1a776

Browse files
author
Felix Exner (fexner)
authored
Add passthrough command interfaces for joints (#204)
1 parent 352a35c commit 6b1a776

File tree

1 file changed

+18
-0
lines changed

1 file changed

+18
-0
lines changed

urdf/inc/ur_joint_control.xacro

Lines changed: 18 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -8,6 +8,9 @@
88
<joint name="${tf_prefix}shoulder_pan_joint">
99
<command_interface name="position"/>
1010
<command_interface name="velocity"/>
11+
<command_interface name="passthrough_position"/>
12+
<command_interface name="passthrough_velocity"/>
13+
<command_interface name="passthrough_acceleration"/>
1114
<state_interface name="position">
1215
<!-- initial position for the mock system and simulation -->
1316
<param name="initial_value">${initial_positions['shoulder_pan_joint']}</param>
@@ -22,6 +25,9 @@
2225
<joint name="${tf_prefix}shoulder_lift_joint">
2326
<command_interface name="position"/>
2427
<command_interface name="velocity"/>
28+
<command_interface name="passthrough_position"/>
29+
<command_interface name="passthrough_velocity"/>
30+
<command_interface name="passthrough_acceleration"/>
2531
<state_interface name="position">
2632
<!-- initial position for the mock system and simulation -->
2733
<param name="initial_value">${initial_positions['shoulder_lift_joint']}</param>
@@ -36,6 +42,9 @@
3642
<joint name="${tf_prefix}elbow_joint">
3743
<command_interface name="position"/>
3844
<command_interface name="velocity"/>
45+
<command_interface name="passthrough_position"/>
46+
<command_interface name="passthrough_velocity"/>
47+
<command_interface name="passthrough_acceleration"/>
3948
<state_interface name="position">
4049
<!-- initial position for the mock system and simulation -->
4150
<param name="initial_value">${initial_positions['elbow_joint']}</param>
@@ -50,6 +59,9 @@
5059
<joint name="${tf_prefix}wrist_1_joint">
5160
<command_interface name="position"/>
5261
<command_interface name="velocity"/>
62+
<command_interface name="passthrough_position"/>
63+
<command_interface name="passthrough_velocity"/>
64+
<command_interface name="passthrough_acceleration"/>
5365
<state_interface name="position">
5466
<!-- initial position for the mock system and simulation -->
5567
<param name="initial_value">${initial_positions['wrist_1_joint']}</param>
@@ -64,6 +76,9 @@
6476
<joint name="${tf_prefix}wrist_2_joint">
6577
<command_interface name="position"/>
6678
<command_interface name="velocity"/>
79+
<command_interface name="passthrough_position"/>
80+
<command_interface name="passthrough_velocity"/>
81+
<command_interface name="passthrough_acceleration"/>
6782
<state_interface name="position">
6883
<!-- initial position for the mock system and simulation -->
6984
<param name="initial_value">${initial_positions['wrist_2_joint']}</param>
@@ -78,6 +93,9 @@
7893
<joint name="${tf_prefix}wrist_3_joint">
7994
<command_interface name="position"/>
8095
<command_interface name="velocity"/>
96+
<command_interface name="passthrough_position"/>
97+
<command_interface name="passthrough_velocity"/>
98+
<command_interface name="passthrough_acceleration"/>
8199
<state_interface name="position">
82100
<!-- initial position for the mock system and simulation -->
83101
<param name="initial_value">${initial_positions['wrist_3_joint']}</param>

0 commit comments

Comments
 (0)