Skip to content
Open
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
6 changes: 6 additions & 0 deletions urdf/inc/ur_joint_control.xacro
Original file line number Diff line number Diff line change
Expand Up @@ -8,6 +8,7 @@
<joint name="${tf_prefix}shoulder_pan_joint">
<command_interface name="position"/>
<command_interface name="velocity"/>
<command_interface name="effort"/>
<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 +23,7 @@
<joint name="${tf_prefix}shoulder_lift_joint">
<command_interface name="position"/>
<command_interface name="velocity"/>
<command_interface name="effort"/>
<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 +38,7 @@
<joint name="${tf_prefix}elbow_joint">
<command_interface name="position"/>
<command_interface name="velocity"/>
<command_interface name="effort"/>
<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 +53,7 @@
<joint name="${tf_prefix}wrist_1_joint">
<command_interface name="position"/>
<command_interface name="velocity"/>
<command_interface name="effort"/>
<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 +68,7 @@
<joint name="${tf_prefix}wrist_2_joint">
<command_interface name="position"/>
<command_interface name="velocity"/>
<command_interface name="effort"/>
<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 +83,7 @@
<joint name="${tf_prefix}wrist_3_joint">
<command_interface name="position"/>
<command_interface name="velocity"/>
<command_interface name="effort"/>
<state_interface name="position">
<!-- initial position for the mock system and simulation -->
<param name="initial_value">${initial_positions['wrist_3_joint']}</param>
Expand Down
Loading