Skip to content

Commit

Permalink
Add control description and ros2_control tag to driver. (#877)
Browse files Browse the repository at this point in the history
  • Loading branch information
fmauch authored Dec 20, 2023
1 parent fcc9d36 commit ee9b420
Show file tree
Hide file tree
Showing 4 changed files with 338 additions and 2 deletions.
2 changes: 1 addition & 1 deletion ur_robot_driver/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -167,7 +167,7 @@ install(PROGRAMS scripts/start_ursim.sh
DESTINATION lib/${PROJECT_NAME}
)

install(DIRECTORY config launch
install(DIRECTORY config launch urdf
DESTINATION share/${PROJECT_NAME}
)

Expand Down
2 changes: 1 addition & 1 deletion ur_robot_driver/launch/ur_control.launch.py
Original file line number Diff line number Diff line change
Expand Up @@ -101,7 +101,7 @@ def launch_setup(context, *args, **kwargs):
[
PathJoinSubstitution([FindExecutable(name="xacro")]),
" ",
PathJoinSubstitution([FindPackageShare(description_package), "urdf", description_file]),
PathJoinSubstitution([FindPackageShare("ur_robot_driver"), "urdf", description_file]),
" ",
"robot_ip:=",
robot_ip,
Expand Down
230 changes: 230 additions & 0 deletions ur_robot_driver/urdf/ur.ros2_control.xacro
Original file line number Diff line number Diff line change
@@ -0,0 +1,230 @@
<?xml version="1.0"?>
<robot xmlns:xacro="http://www.ros.org/wiki/xacro">

<xacro:include filename="$(find ur_description)/urdf/inc/ur_joint_control.xacro" />
<xacro:include filename="$(find ur_description)/urdf/inc/ur_sensors.xacro" />

<xacro:macro name="ur_ros2_control" params="
name
tf_prefix
kinematics_parameters_file
robot_ip
script_filename
input_recipe_filename
output_recipe_filename
transmission_hw_interface:=hardware_interface/PositionJointInterface
use_mock_hardware:=false mock_sensor_commands:=false
headless_mode:=false
initial_positions:=${dict(shoulder_pan_joint=0.0,shoulder_lift_joint=-1.57,elbow_joint=0.0,wrist_1_joint=-1.57,wrist_2_joint=0.0,wrist_3_joint=0.0)}
use_tool_communication:=false
tool_voltage:=0 tool_parity:=0 tool_baud_rate:=115200 tool_stop_bits:=1
tool_rx_idle_chars:=1.5 tool_tx_idle_chars:=3.5 tool_device_name:=/tmp/ttyUR tool_tcp_port:=54321
reverse_port:=50001
script_sender_port:=50002
reverse_ip:=0.0.0.0
script_command_port:=50004
trajectory_port:=50003
non_blocking_read:=true
keep_alive_count:=2
">

<xacro:property name="config_kinematics_parameters" value="${xacro.load_yaml(kinematics_parameters_file)}"/>
<xacro:property name="sec_kinematics" value="${config_kinematics_parameters['kinematics']}" />
<xacro:property name="kinematics_hash" value="${sec_kinematics['hash']}" scope="parent"/>

<!-- Add URDF transmission elements (for ros_control) -->
<!--<xacro:ur_arm_transmission prefix="${prefix}" hw_interface="${transmission_hw_interface}" />-->
<!-- Placeholder for ros2_control transmission which don't yet exist -->

<ros2_control name="${name}" type="system">
<hardware>
<xacro:if value="${use_mock_hardware}">
<plugin>mock_components/GenericSystem</plugin>
<param name="mock_sensor_commands">${mock_sensor_commands}</param>
<param name="state_following_offset">0.0</param>
</xacro:if>
<xacro:unless value="${use_mock_hardware}">
<plugin>ur_robot_driver/URPositionHardwareInterface</plugin>
<param name="robot_ip">${robot_ip}</param>
<param name="script_filename">${script_filename}</param>
<param name="output_recipe_filename">${output_recipe_filename}</param>
<param name="input_recipe_filename">${input_recipe_filename}</param>
<param name="headless_mode">${headless_mode}</param>
<param name="reverse_port">${reverse_port}</param>
<param name="script_sender_port">${script_sender_port}</param>
<param name="reverse_ip">${reverse_ip}</param>
<param name="script_command_port">${script_command_port}</param>
<param name="trajectory_port">${trajectory_port}</param>
<param name="tf_prefix">${tf_prefix}</param>
<param name="non_blocking_read">${non_blocking_read}</param>
<param name="servoj_gain">2000</param>
<param name="servoj_lookahead_time">0.03</param>
<param name="use_tool_communication">${use_tool_communication}</param>
<param name="kinematics/hash">${kinematics_hash}</param>
<param name="tool_voltage">${tool_voltage}</param>
<param name="tool_parity">${tool_parity}</param>
<param name="tool_baud_rate">${tool_baud_rate}</param>
<param name="tool_stop_bits">${tool_stop_bits}</param>
<param name="tool_rx_idle_chars">${tool_rx_idle_chars}</param>
<param name="tool_tx_idle_chars">${tool_tx_idle_chars}</param>
<param name="tool_device_name">${tool_device_name}</param>
<param name="tool_tcp_port">${tool_tcp_port}</param>
<param name="keep_alive_count">${keep_alive_count}</param>
</xacro:unless>
</hardware>

<xacro:ur_joint_control_description
tf_prefix="${tf_prefix}"
initial_positions="${initial_positions}"
/>

<xacro:ur_sensors
tf_prefix="${tf_prefix}"
/>

<!-- NOTE The following are joints used only for testing with mock hardware and will change in the future -->
<gpio name="${tf_prefix}speed_scaling">
<state_interface name="speed_scaling_factor"/>
<param name="initial_speed_scaling_factor">1</param>
<command_interface name="target_speed_fraction_cmd"/>
<command_interface name="target_speed_fraction_async_success"/>
</gpio>

<gpio name="${tf_prefix}gpio">
<command_interface name="standard_digital_output_cmd_0"/>
<command_interface name="standard_digital_output_cmd_1"/>
<command_interface name="standard_digital_output_cmd_2"/>
<command_interface name="standard_digital_output_cmd_3"/>
<command_interface name="standard_digital_output_cmd_4"/>
<command_interface name="standard_digital_output_cmd_5"/>
<command_interface name="standard_digital_output_cmd_6"/>
<command_interface name="standard_digital_output_cmd_7"/>
<command_interface name="standard_digital_output_cmd_8"/>
<command_interface name="standard_digital_output_cmd_9"/>
<command_interface name="standard_digital_output_cmd_10"/>
<command_interface name="standard_digital_output_cmd_11"/>
<command_interface name="standard_digital_output_cmd_12"/>
<command_interface name="standard_digital_output_cmd_13"/>
<command_interface name="standard_digital_output_cmd_14"/>
<command_interface name="standard_digital_output_cmd_15"/>
<command_interface name="standard_digital_output_cmd_16"/>
<command_interface name="standard_digital_output_cmd_17"/>

<command_interface name="standard_analog_output_cmd_0"/>
<command_interface name="standard_analog_output_cmd_1"/>

<command_interface name="tool_voltage_cmd"/>

<command_interface name="io_async_success"/>

<state_interface name="digital_output_0"/>
<state_interface name="digital_output_1"/>
<state_interface name="digital_output_2"/>
<state_interface name="digital_output_3"/>
<state_interface name="digital_output_4"/>
<state_interface name="digital_output_5"/>
<state_interface name="digital_output_6"/>
<state_interface name="digital_output_7"/>
<state_interface name="digital_output_8"/>
<state_interface name="digital_output_9"/>
<state_interface name="digital_output_10"/>
<state_interface name="digital_output_11"/>
<state_interface name="digital_output_12"/>
<state_interface name="digital_output_13"/>
<state_interface name="digital_output_14"/>
<state_interface name="digital_output_15"/>
<state_interface name="digital_output_16"/>
<state_interface name="digital_output_17"/>

<state_interface name="digital_input_0"/>
<state_interface name="digital_input_1"/>
<state_interface name="digital_input_2"/>
<state_interface name="digital_input_3"/>
<state_interface name="digital_input_4"/>
<state_interface name="digital_input_5"/>
<state_interface name="digital_input_6"/>
<state_interface name="digital_input_7"/>
<state_interface name="digital_input_8"/>
<state_interface name="digital_input_9"/>
<state_interface name="digital_input_10"/>
<state_interface name="digital_input_11"/>
<state_interface name="digital_input_12"/>
<state_interface name="digital_input_13"/>
<state_interface name="digital_input_14"/>
<state_interface name="digital_input_15"/>
<state_interface name="digital_input_16"/>
<state_interface name="digital_input_17"/>

<state_interface name="standard_analog_output_0"/>
<state_interface name="standard_analog_output_1"/>

<state_interface name="standard_analog_input_0"/>
<state_interface name="standard_analog_input_1"/>

<state_interface name="analog_io_type_0"/>
<state_interface name="analog_io_type_1"/>
<state_interface name="analog_io_type_2"/>
<state_interface name="analog_io_type_3"/>

<state_interface name="tool_mode"/>
<state_interface name="tool_output_voltage"/>
<state_interface name="tool_output_current"/>
<state_interface name="tool_temperature"/>

<state_interface name="tool_analog_input_0"/>
<state_interface name="tool_analog_input_1"/>

<state_interface name="tool_analog_input_type_0"/>
<state_interface name="tool_analog_input_type_1"/>

<state_interface name="robot_mode"/>
<state_interface name="robot_status_bit_0"/>
<state_interface name="robot_status_bit_1"/>
<state_interface name="robot_status_bit_2"/>
<state_interface name="robot_status_bit_3"/>

<state_interface name="safety_mode"/>
<state_interface name="safety_status_bit_0"/>
<state_interface name="safety_status_bit_1"/>
<state_interface name="safety_status_bit_2"/>
<state_interface name="safety_status_bit_3"/>
<state_interface name="safety_status_bit_4"/>
<state_interface name="safety_status_bit_5"/>
<state_interface name="safety_status_bit_6"/>
<state_interface name="safety_status_bit_7"/>
<state_interface name="safety_status_bit_8"/>
<state_interface name="safety_status_bit_9"/>
<state_interface name="safety_status_bit_10"/>

<state_interface name="program_running"/>
</gpio>

<gpio name="${tf_prefix}payload">
<command_interface name="mass"/>
<command_interface name="cog.x"/>
<command_interface name="cog.y"/>
<command_interface name="cog.z"/>
<command_interface name="payload_async_success"/>
</gpio>

<gpio name="${tf_prefix}resend_robot_program">
<command_interface name="resend_robot_program_cmd"/>
<command_interface name="resend_robot_program_async_success"/>
</gpio>

<gpio name="${tf_prefix}hand_back_control">
<command_interface name="hand_back_control_cmd"/>
<command_interface name="hand_back_control_async_success"/>
</gpio>

<gpio name="${tf_prefix}zero_ftsensor">
<command_interface name="zero_ftsensor_cmd"/>
<command_interface name="zero_ftsensor_async_success"/>
</gpio>

<gpio name="${tf_prefix}system_interface">
<state_interface name="initialized"/>
</gpio>
</ros2_control>
</xacro:macro>
</robot>
106 changes: 106 additions & 0 deletions ur_robot_driver/urdf/ur.urdf.xacro
Original file line number Diff line number Diff line change
@@ -0,0 +1,106 @@
<?xml version="1.0"?>
<robot xmlns:xacro="http://wiki.ros.org/xacro" name="$(arg name)">
<!-- robot name parameter -->
<xacro:arg name="name" default="ur"/>

<xacro:include filename="$(find ur_description)/urdf/ur_macro.xacro"/>
<!-- ros2 control include -->
<xacro:include filename="$(find ur_robot_driver)/urdf/ur.ros2_control.xacro" />
<xacro:include filename="$(find ur_description)/urdf/inc/ur_transmissions.xacro" />

<!-- possible 'ur_type' values: ur3, ur3e, ur5, ur5e, ur10, ur10e, ur16e, ur20 -->
<!-- the default value should raise an error in case this was called without defining the type -->
<xacro:arg name="ur_type" default="urXe"/>

<!-- parameters -->
<xacro:arg name="tf_prefix" default="" />
<xacro:arg name="joint_limit_params" default="$(find ur_description)/config/$(arg ur_type)/joint_limits.yaml"/>
<xacro:arg name="kinematics_params" default="$(find ur_description)/config/$(arg ur_type)/default_kinematics.yaml"/>
<xacro:arg name="physical_params" default="$(find ur_description)/config/$(arg ur_type)/physical_parameters.yaml"/>
<xacro:arg name="visual_params" default="$(find ur_description)/config/$(arg ur_type)/visual_parameters.yaml"/>
<xacro:arg name="transmission_hw_interface" default=""/>
<xacro:arg name="safety_limits" default="false"/>
<xacro:arg name="safety_pos_margin" default="0.15"/>
<xacro:arg name="safety_k_position" default="20"/>
<!-- ros2_control related parameters -->
<xacro:arg name="headless_mode" default="false" />
<xacro:arg name="robot_ip" default="0.0.0.0" />
<xacro:arg name="script_filename" default=""/>
<xacro:arg name="output_recipe_filename" default=""/>
<xacro:arg name="input_recipe_filename" default=""/>
<xacro:arg name="reverse_ip" default="0.0.0.0"/>
<xacro:arg name="script_command_port" default="50004"/>
<xacro:arg name="reverse_port" default="50001"/>
<xacro:arg name="script_sender_port" default="50002"/>
<xacro:arg name="trajectory_port" default="50003"/>
<!-- tool communication related parameters-->
<xacro:arg name="use_tool_communication" default="false" />
<xacro:arg name="tool_voltage" default="0" />
<xacro:arg name="tool_parity" default="0" />
<xacro:arg name="tool_baud_rate" default="115200" />
<xacro:arg name="tool_stop_bits" default="1" />
<xacro:arg name="tool_rx_idle_chars" default="1.5" />
<xacro:arg name="tool_tx_idle_chars" default="3.5" />
<xacro:arg name="tool_device_name" default="/tmp/ttyUR" />
<xacro:arg name="tool_tcp_port" default="54321" />

<!-- Simulation parameters -->
<xacro:arg name="use_mock_hardware" default="false" />
<xacro:arg name="mock_sensor_commands" default="false" />
<xacro:arg name="simulation_controllers" default="" />

<!-- initial position for simulations (Mock Hardware, Gazebo, Ignition) -->
<xacro:arg name="initial_positions_file" default="$(find ur_description)/config/initial_positions.yaml"/>

<!-- convert to property to use substitution in function -->
<xacro:property name="initial_positions_file" default="$(arg initial_positions_file)"/>

<!-- create link fixed to the "world" -->
<link name="world" />

<xacro:ur_robot
name="$(arg name)"
tf_prefix="$(arg tf_prefix)"
parent="world"
joint_limits_parameters_file="$(arg joint_limit_params)"
kinematics_parameters_file="$(arg kinematics_params)"
physical_parameters_file="$(arg physical_params)"
visual_parameters_file="$(arg visual_params)"
safety_limits="$(arg safety_limits)"
safety_pos_margin="$(arg safety_pos_margin)"
safety_k_position="$(arg safety_k_position)"
>
<origin xyz="0 0 0" rpy="0 0 0" /> <!-- position robot in the world -->
</xacro:ur_robot>

<!-- ros2 control instance -->
<xacro:ur_ros2_control
name="$(arg name)"
tf_prefix="$(arg tf_prefix)"
kinematics_parameters_file="$(arg kinematics_params)"
transmission_hw_interface="$(arg transmission_hw_interface)"
use_mock_hardware="$(arg use_mock_hardware)"
mock_sensor_commands="$(arg mock_sensor_commands)"
headless_mode="$(arg headless_mode)"
initial_positions="${xacro.load_yaml(initial_positions_file)}"
use_tool_communication="$(arg use_tool_communication)"
tool_voltage="$(arg tool_voltage)"
tool_parity="$(arg tool_parity)"
tool_baud_rate="$(arg tool_baud_rate)"
tool_stop_bits="$(arg tool_stop_bits)"
tool_rx_idle_chars="$(arg tool_rx_idle_chars)"
tool_tx_idle_chars="$(arg tool_tx_idle_chars)"
tool_device_name="$(arg tool_device_name)"
tool_tcp_port="$(arg tool_tcp_port)"
robot_ip="$(arg robot_ip)"
script_filename="$(arg script_filename)"
output_recipe_filename="$(arg output_recipe_filename)"
input_recipe_filename="$(arg input_recipe_filename)"
reverse_ip="$(arg reverse_ip)"
script_command_port="$(arg script_command_port)"
reverse_port="$(arg reverse_port)"
script_sender_port="$(arg script_sender_port)"
trajectory_port="$(arg trajectory_port)"
/>

</robot>

0 comments on commit ee9b420

Please sign in to comment.