Skip to content

Commit 585180c

Browse files
Dan Zimmermandanzimmerman
authored andcommitted
Inject ROS 2 Control hardware as a block parameter.
Basic block injection example Better (and correct) non-joint interface handling Formatting Add tf_prefix and kinematics_hash properly Change block name Revert joint dynamics changes Revert fake hardware default
1 parent 61691b7 commit 585180c

File tree

4 files changed

+118
-105
lines changed

4 files changed

+118
-105
lines changed

urdf/ur.ros2_control.xacro

Lines changed: 7 additions & 55 deletions
Original file line numberDiff line numberDiff line change
@@ -4,67 +4,19 @@
44
<xacro:macro name="ur_ros2_control" params="
55
name
66
prefix
7-
use_fake_hardware:=false fake_sensor_commands:=false
8-
sim_gazebo:=false
9-
sim_ignition:=false
10-
headless_mode:=false
7+
add_non_joint_interfaces:=true
118
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)}
12-
use_tool_communication:=false
13-
script_filename output_recipe_filename
14-
input_recipe_filename tf_prefix
15-
hash_kinematics robot_ip
16-
tool_voltage:=0 tool_parity:=0 tool_baud_rate:=115200 tool_stop_bits:=1
17-
tool_rx_idle_chars:=1.5 tool_tx_idle_chars:=3.5 tool_device_name:=/tmp/ttyUR tool_tcp_port:=54321
18-
reverse_port:=50001
19-
script_sender_port:=50002
20-
reverse_ip:=0.0.0.0
21-
script_command_port:=50004
229
transmission_hw_interface:=hardware_interface/PositionJointInterface
10+
**ros2_control_hardware
2311
">
2412

2513
<!-- Add URDF transmission elements (for ros_control) -->
2614
<!--<xacro:ur_arm_transmission prefix="${prefix}" hw_interface="${transmission_hw_interface}" />-->
2715

2816
<ros2_control name="${name}" type="system">
29-
<hardware>
30-
<xacro:if value="${sim_gazebo}">
31-
<plugin>gazebo_ros2_control/GazeboSystem</plugin>
32-
</xacro:if>
33-
<xacro:if value="${sim_ignition}">
34-
<plugin>ign_ros2_control/IgnitionSystem</plugin>
35-
</xacro:if>
36-
<xacro:if value="${use_fake_hardware}">
37-
<plugin>mock_components/GenericSystem</plugin>
38-
<param name="fake_sensor_commands">${fake_sensor_commands}</param>
39-
<param name="state_following_offset">0.0</param>
40-
</xacro:if>
41-
<xacro:unless value="${use_fake_hardware or sim_gazebo or sim_ignition}">
42-
<plugin>ur_robot_driver/URPositionHardwareInterface</plugin>
43-
<param name="robot_ip">${robot_ip}</param>
44-
<param name="script_filename">${script_filename}</param>
45-
<param name="output_recipe_filename">${output_recipe_filename}</param>
46-
<param name="input_recipe_filename">${input_recipe_filename}</param>
47-
<param name="headless_mode">${headless_mode}</param>
48-
<param name="reverse_port">${reverse_port}</param>
49-
<param name="script_sender_port">${script_sender_port}</param>
50-
<param name="reverse_ip">${reverse_ip}</param>
51-
<param name="script_command_port">${script_command_port}</param>
52-
<param name="tf_prefix">"${tf_prefix}"</param>
53-
<param name="non_blocking_read">0</param>
54-
<param name="servoj_gain">2000</param>
55-
<param name="servoj_lookahead_time">0.03</param>
56-
<param name="use_tool_communication">${use_tool_communication}</param>
57-
<param name="kinematics/hash">${hash_kinematics}</param>
58-
<param name="tool_voltage">${tool_voltage}</param>
59-
<param name="tool_parity">${tool_parity}</param>
60-
<param name="tool_baud_rate">${tool_baud_rate}</param>
61-
<param name="tool_stop_bits">${tool_stop_bits}</param>
62-
<param name="tool_rx_idle_chars">${tool_rx_idle_chars}</param>
63-
<param name="tool_tx_idle_chars">${tool_tx_idle_chars}</param>
64-
<param name="tool_device_name">${tool_device_name}</param>
65-
<param name="tool_tcp_port">${tool_tcp_port}</param>
66-
</xacro:unless>
67-
</hardware>
17+
<!-- Start hardware dependency injection from outside the macro-->
18+
<xacro:insert_block name="ros2_control_hardware" />
19+
<!-- End hardware dependency injection -->
6820
<joint name="${prefix}shoulder_pan_joint">
6921
<command_interface name="position">
7022
<param name="min">{-2*pi}</param>
@@ -162,7 +114,7 @@
162114
<state_interface name="effort"/>
163115
</joint>
164116

165-
<xacro:unless value="${sim_gazebo or sim_ignition}">
117+
<xacro:if value="${add_non_joint_interfaces}">
166118
<sensor name="tcp_fts_sensor">
167119
<state_interface name="force.x"/>
168120
<state_interface name="force.y"/>
@@ -311,7 +263,7 @@
311263
<state_interface name="initialized"/>
312264
</gpio>
313265

314-
</xacro:unless>
266+
</xacro:if>
315267

316268
</ros2_control>
317269

urdf/ur.urdf.xacro

Lines changed: 64 additions & 27 deletions
Original file line numberDiff line numberDiff line change
@@ -6,6 +6,8 @@
66
<xacro:include filename="$(find ur_description)/urdf/ur_macro.xacro"/>
77
<!-- include ros2 control -->
88
<xacro:include filename="$(find ur_description)/urdf/ur.ros2_control.xacro" />
9+
<!-- include ros2_control hardware instantiation (for now, then migrate later to responsible packages) -->
10+
<xacro:include filename="$(find ur_description)/urdf/ur_hardware.xacro"/>
911

1012
<!-- possible 'ur_type' values: ur3, ur3e, ur5, ur5e, ur10, ur10e, ur16e -->
1113
<!-- the default value should raise an error in case this was called without defining the type -->
@@ -17,6 +19,7 @@
1719
<xacro:arg name="kinematics_params" default="$(find ur_description)/config/$(arg ur_type)/default_kinematics.yaml"/>
1820
<xacro:arg name="physical_params" default="$(find ur_description)/config/$(arg ur_type)/physical_parameters.yaml"/>
1921
<xacro:arg name="visual_params" default="$(find ur_description)/config/$(arg ur_type)/visual_parameters.yaml"/>
22+
2023
<xacro:arg name="transmission_hw_interface" default=""/>
2124
<xacro:arg name="safety_limits" default="false"/>
2225
<xacro:arg name="safety_pos_margin" default="0.15"/>
@@ -54,11 +57,15 @@
5457
<xacro:property name="initial_positions_file" default="$(arg initial_positions_file)"/>
5558
<xacro:property name="sim_gazebo" default="$(arg sim_gazebo)"/>
5659
<xacro:property name="sim_ignition" default="$(arg sim_ignition)"/>
60+
<xacro:property name="fake_hardware" default="$(arg use_fake_hardware)"/>
61+
5762

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

6166
<!-- load model data -->
67+
<!-- This puts a bunch of named parameters in the top-level scope which are consumed inside later macros-->
68+
<!-- See https://github.com/ros/xacro/pull/105 -->
6269
<xacro:read_model_data
6370
joint_limits_parameters_file="$(arg joint_limit_params)"
6471
kinematics_parameters_file="$(arg kinematics_params)"
@@ -78,35 +85,65 @@
7885
<origin xyz="0 0 0" rpy="0 0 0" /> <!-- position robot in the world -->
7986
</xacro:ur_robot>
8087

81-
82-
<!-- ros2 control instance -->
88+
<!-- ros2 control, if needed -->
89+
<!-- ur_description might eventually prepare fake/mock hardware only, delegating the <hardware> block to a consumer package -->
90+
<xacro:property name="needs_non_joint_interfaces" value="${not (sim_gazebo or sim_ignition)}"/>
91+
<!-- Kinematics hash comes from read_model_data -->
8392
<xacro:ur_ros2_control
84-
name="$(arg name)" prefix="$(arg prefix)"
85-
use_fake_hardware="$(arg use_fake_hardware)"
86-
fake_sensor_commands="$(arg fake_sensor_commands)"
87-
sim_gazebo="$(arg sim_gazebo)"
88-
sim_ignition="$(arg sim_ignition)"
89-
headless_mode="$(arg headless_mode)"
90-
initial_positions="${xacro.load_yaml(initial_positions_file)}"
91-
use_tool_communication="$(arg use_tool_communication)"
92-
tool_voltage="$(arg tool_voltage)"
93-
tool_parity="$(arg tool_parity)"
94-
tool_baud_rate="$(arg tool_baud_rate)"
95-
tool_stop_bits="$(arg tool_stop_bits)"
96-
tool_rx_idle_chars="$(arg tool_rx_idle_chars)"
97-
tool_tx_idle_chars="$(arg tool_tx_idle_chars)"
98-
tool_device_name="$(arg tool_device_name)"
99-
tool_tcp_port="$(arg tool_tcp_port)"
100-
robot_ip="$(arg robot_ip)"
101-
script_filename="$(arg script_filename)"
102-
output_recipe_filename="$(arg output_recipe_filename)"
103-
input_recipe_filename="$(arg input_recipe_filename)"
104-
reverse_ip="$(arg reverse_ip)"
105-
script_command_port="$(arg script_command_port)"
106-
tf_prefix=""
107-
hash_kinematics="${kinematics_hash}"
108-
/>
93+
name="$(arg name)" prefix="$(arg prefix)"
94+
add_non_joint_interfaces="${needs_non_joint_interfaces}"
95+
initial_positions="${xacro.load_yaml(initial_positions_file)}"
96+
>
97+
<!-- dz: For now, I conditionally pass the right <hardware> as a block param. -->
98+
<!-- dz: Later, this wouldn't be necessary, a consumer package could create and pass it in its top-level xacro -->
99+
<ros2_control_hardware>
100+
<xacro:unless value="${sim_gazebo or sim_ignition or fake_hardware}">
101+
<xacro:ur_real_hardware_block
102+
headless_mode="$(arg headless_mode)"
103+
initial_positions="${xacro.load_yaml(initial_positions_file)}"
104+
use_tool_communication="$(arg use_tool_communication)"
105+
tool_voltage="$(arg tool_voltage)"
106+
tool_parity="$(arg tool_parity)"
107+
tool_baud_rate="$(arg tool_baud_rate)"
108+
tool_stop_bits="$(arg tool_stop_bits)"
109+
tool_rx_idle_chars="$(arg tool_rx_idle_chars)"
110+
tool_tx_idle_chars="$(arg tool_tx_idle_chars)"
111+
tool_device_name="$(arg tool_device_name)"
112+
tool_tcp_port="$(arg tool_tcp_port)"
113+
robot_ip="$(arg robot_ip)"
114+
script_filename="$(arg script_filename)"
115+
output_recipe_filename="$(arg output_recipe_filename)"
116+
input_recipe_filename="$(arg input_recipe_filename)"
117+
reverse_ip="$(arg reverse_ip)"
118+
script_command_port="$(arg script_command_port)"
119+
transmission_hw_interface="$(arg transmission_hw_interface)"
120+
tf_prefix=""
121+
hash_kinematics="${kinematics_hash}"
122+
/>
123+
</xacro:unless>
124+
<xacro:if value="${fake_hardware and not (sim_gazebo or sim_ignition)}">
125+
<hardware>
126+
<plugin>mock_components/GenericSystem</plugin>
127+
<param name="fake_sensor_commands">$(arg fake_sensor_commands)</param>
128+
<param name="state_following_offset">0.0</param>
129+
</hardware>
130+
</xacro:if>
131+
<xacro:if value="${sim_gazebo}">
132+
<hardware>
133+
<plugin>gazebo_ros2_control/GazeboSystem</plugin>
134+
</hardware>
135+
</xacro:if>
136+
<xacro:if value="${sim_ignition}">
137+
<hardware>
138+
<plugin>ign_ros2_control/IgnitionSystem</plugin>
139+
</hardware>
140+
</xacro:if>
141+
</ros2_control_hardware>
142+
</xacro:ur_ros2_control>
143+
144+
109145

146+
<!-- dz: These move to their respective simulation packages -->
110147
<xacro:if value="$(arg sim_gazebo)">
111148
<!-- Gazebo plugins -->
112149
<gazebo reference="world">

urdf/ur_hardware.xacro

Lines changed: 46 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,46 @@
1+
<?xml version="1.0"?>
2+
<robot xmlns:xacro="http://www.ros.org/wiki/xacro">
3+
4+
<xacro:macro name="ur_real_hardware_block" params="
5+
headless_mode:=false
6+
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)}
7+
use_tool_communication:=false
8+
script_filename output_recipe_filename
9+
input_recipe_filename tf_prefix
10+
hash_kinematics robot_ip
11+
tool_voltage:=0 tool_parity:=0 tool_baud_rate:=115200 tool_stop_bits:=1
12+
tool_rx_idle_chars:=1.5 tool_tx_idle_chars:=3.5 tool_device_name:=/tmp/ttyUR tool_tcp_port:=54321
13+
reverse_port:=50001
14+
script_sender_port:=50002
15+
reverse_ip:=0.0.0.0
16+
script_command_port:=50004
17+
transmission_hw_interface:=hardware_interface/PositionJointInterface
18+
">
19+
<hardware>
20+
<plugin>ur_robot_driver/URPositionHardwareInterface</plugin>
21+
<param name="robot_ip">${robot_ip}</param>
22+
<param name="script_filename">${script_filename}</param>
23+
<param name="output_recipe_filename">${output_recipe_filename}</param>
24+
<param name="input_recipe_filename">${input_recipe_filename}</param>
25+
<param name="headless_mode">${headless_mode}</param>
26+
<param name="reverse_port">${reverse_port}</param>
27+
<param name="script_sender_port">${script_sender_port}</param>
28+
<param name="reverse_ip">${reverse_ip}</param>
29+
<param name="script_command_port">${script_command_port}</param>
30+
<param name="tf_prefix">"${tf_prefix}"</param>
31+
<param name="non_blocking_read">0</param>
32+
<param name="servoj_gain">2000</param>
33+
<param name="servoj_lookahead_time">0.03</param>
34+
<param name="use_tool_communication">${use_tool_communication}</param>
35+
<param name="kinematics/hash">${hash_kinematics}</param>
36+
<param name="tool_voltage">${tool_voltage}</param>
37+
<param name="tool_parity">${tool_parity}</param>
38+
<param name="tool_baud_rate">${tool_baud_rate}</param>
39+
<param name="tool_stop_bits">${tool_stop_bits}</param>
40+
<param name="tool_rx_idle_chars">${tool_rx_idle_chars}</param>
41+
<param name="tool_tx_idle_chars">${tool_tx_idle_chars}</param>
42+
<param name="tool_device_name">${tool_device_name}</param>
43+
<param name="tool_tcp_port">${tool_tcp_port}</param>
44+
</hardware>
45+
</xacro:macro>
46+
</robot>

urdf/ur_macro.xacro

Lines changed: 1 addition & 23 deletions
Original file line numberDiff line numberDiff line change
@@ -61,29 +61,7 @@
6161
safety_limits:=false
6262
safety_pos_margin:=0.15
6363
safety_k_position:=20
64-
use_fake_hardware:=false
65-
fake_sensor_commands:=false
66-
sim_gazebo:=false
67-
sim_ignition:=false
68-
headless_mode:=false
69-
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)}
70-
use_tool_communication:=false
71-
tool_voltage:=0
72-
tool_parity:=0
73-
tool_baud_rate:=115200
74-
tool_stop_bits:=1
75-
tool_rx_idle_chars:=1.5
76-
tool_tx_idle_chars:=3.5
77-
tool_device_name:=/tmp/ttyUR
78-
tool_tcp_port:=54321
79-
robot_ip:=0.0.0.0
80-
script_filename:=to_be_filled_by_ur_robot_driver
81-
output_recipe_filename:=to_be_filled_by_ur_robot_driver
82-
input_recipe_filename:=to_be_filled_by_ur_robot_driver
83-
reverse_port:=50001
84-
script_sender_port:=50002
85-
reverse_ip:=0.0.0.0
86-
script_command_port:=50004">
64+
">
8765

8866

8967

0 commit comments

Comments
 (0)