Skip to content
Merged
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
62 changes: 62 additions & 0 deletions urdf/ur.ros2_control.xacro
Original file line number Diff line number Diff line change
Expand Up @@ -288,10 +288,72 @@
<command_interface name="zero_ftsensor_async_success"/>
</gpio>

<gpio name="${tf_prefix}freedrive_mode">
<command_interface name="async_success"/>
<command_interface name="enable"/>
<command_interface name="abort"/>
</gpio>

<gpio name="${tf_prefix}system_interface">
<state_interface name="initialized"/>
</gpio>

<gpio name="${tf_prefix}force_mode">
<command_interface name="task_frame_x"/>
<command_interface name="task_frame_y"/>
<command_interface name="task_frame_z"/>
<command_interface name="task_frame_rx"/>
<command_interface name="task_frame_ry"/>
<command_interface name="task_frame_rz"/>
<command_interface name="selection_vector_x"/>
<command_interface name="selection_vector_y"/>
<command_interface name="selection_vector_z"/>
<command_interface name="selection_vector_rx"/>
<command_interface name="selection_vector_ry"/>
<command_interface name="selection_vector_rz"/>
<command_interface name="wrench_x"/>
<command_interface name="wrench_y"/>
<command_interface name="wrench_z"/>
<command_interface name="wrench_rx"/>
<command_interface name="wrench_ry"/>
<command_interface name="wrench_rz"/>
<command_interface name="limits_x"/>
<command_interface name="limits_y"/>
<command_interface name="limits_z"/>
<command_interface name="limits_rx"/>
<command_interface name="limits_ry"/>
<command_interface name="limits_rz"/>
<command_interface name="type"/>
<command_interface name="damping"/>
<command_interface name="gain_scaling"/>
<command_interface name="disable_cmd"/>
<command_interface name="force_mode_async_success"/>
</gpio>

<gpio name="${tf_prefix}trajectory_passthrough">
<command_interface name="setpoint_positions_0"/>
<command_interface name="setpoint_positions_1"/>
<command_interface name="setpoint_positions_2"/>
<command_interface name="setpoint_positions_3"/>
<command_interface name="setpoint_positions_4"/>
<command_interface name="setpoint_positions_5"/>
<command_interface name="setpoint_velocities_0"/>
<command_interface name="setpoint_velocities_1"/>
<command_interface name="setpoint_velocities_2"/>
<command_interface name="setpoint_velocities_3"/>
<command_interface name="setpoint_velocities_4"/>
<command_interface name="setpoint_velocities_5"/>
<command_interface name="setpoint_accelerations_0"/>
<command_interface name="setpoint_accelerations_1"/>
<command_interface name="setpoint_accelerations_2"/>
<command_interface name="setpoint_accelerations_3"/>
<command_interface name="setpoint_accelerations_4"/>
<command_interface name="setpoint_accelerations_5"/>
<command_interface name="transfer_state"/>
<command_interface name="time_from_start"/>
<command_interface name="abort"/>
</gpio>

<gpio name="${tf_prefix}get_robot_software_version">
<state_interface name="get_version_major"/>
<state_interface name="get_version_minor"/>
Expand Down
Loading