Skip to content

Commit

Permalink
Add passthrough command interfaces for joints (#204)
Browse files Browse the repository at this point in the history
  • Loading branch information
fmauch authored Oct 5, 2024
1 parent 352a35c commit 6b1a776
Showing 1 changed file with 18 additions and 0 deletions.
18 changes: 18 additions & 0 deletions urdf/inc/ur_joint_control.xacro
Original file line number Diff line number Diff line change
Expand Up @@ -8,6 +8,9 @@
<joint name="${tf_prefix}shoulder_pan_joint">
<command_interface name="position"/>
<command_interface name="velocity"/>
<command_interface name="passthrough_position"/>
<command_interface name="passthrough_velocity"/>
<command_interface name="passthrough_acceleration"/>
<state_interface name="position">
<!-- initial position for the mock system and simulation -->
<param name="initial_value">${initial_positions['shoulder_pan_joint']}</param>
Expand All @@ -22,6 +25,9 @@
<joint name="${tf_prefix}shoulder_lift_joint">
<command_interface name="position"/>
<command_interface name="velocity"/>
<command_interface name="passthrough_position"/>
<command_interface name="passthrough_velocity"/>
<command_interface name="passthrough_acceleration"/>
<state_interface name="position">
<!-- initial position for the mock system and simulation -->
<param name="initial_value">${initial_positions['shoulder_lift_joint']}</param>
Expand All @@ -36,6 +42,9 @@
<joint name="${tf_prefix}elbow_joint">
<command_interface name="position"/>
<command_interface name="velocity"/>
<command_interface name="passthrough_position"/>
<command_interface name="passthrough_velocity"/>
<command_interface name="passthrough_acceleration"/>
<state_interface name="position">
<!-- initial position for the mock system and simulation -->
<param name="initial_value">${initial_positions['elbow_joint']}</param>
Expand All @@ -50,6 +59,9 @@
<joint name="${tf_prefix}wrist_1_joint">
<command_interface name="position"/>
<command_interface name="velocity"/>
<command_interface name="passthrough_position"/>
<command_interface name="passthrough_velocity"/>
<command_interface name="passthrough_acceleration"/>
<state_interface name="position">
<!-- initial position for the mock system and simulation -->
<param name="initial_value">${initial_positions['wrist_1_joint']}</param>
Expand All @@ -64,6 +76,9 @@
<joint name="${tf_prefix}wrist_2_joint">
<command_interface name="position"/>
<command_interface name="velocity"/>
<command_interface name="passthrough_position"/>
<command_interface name="passthrough_velocity"/>
<command_interface name="passthrough_acceleration"/>
<state_interface name="position">
<!-- initial position for the mock system and simulation -->
<param name="initial_value">${initial_positions['wrist_2_joint']}</param>
Expand All @@ -78,6 +93,9 @@
<joint name="${tf_prefix}wrist_3_joint">
<command_interface name="position"/>
<command_interface name="velocity"/>
<command_interface name="passthrough_position"/>
<command_interface name="passthrough_velocity"/>
<command_interface name="passthrough_acceleration"/>
<state_interface name="position">
<!-- initial position for the mock system and simulation -->
<param name="initial_value">${initial_positions['wrist_3_joint']}</param>
Expand Down

0 comments on commit 6b1a776

Please sign in to comment.