|
1 | 1 | <?xml version="1.0"?>
|
2 | 2 | <robot xmlns:xacro="http://ros.org/wiki/xacro">
|
3 | 3 | <xacro:arg name="is_sim" default="false"/>
|
4 |
| - <xacro:arg name="use_fake_hardware" default="false"/> |
| 4 | + <xacro:arg name="use_mock_hardware" default="false"/> |
5 | 5 | <xacro:arg name="use_manipulation_controllers" default="false"/>
|
6 | 6 |
|
7 | 7 | <xacro:include filename="$(find ur_description)/urdf/ur_macro.xacro"/>
|
|
20 | 20 | safety_limits:=''
|
21 | 21 | safety_pos_margin:=''
|
22 | 22 | safety_k_position:=''
|
23 |
| - generate_ros2_control_tag:='' |
24 | 23 | headless_mode:=''
|
25 | 24 | robot_ip:=''
|
26 | 25 | script_filename:=''
|
|
43 | 42 | tool_tx_idle_chars:=''
|
44 | 43 | tool_device_name:=''
|
45 | 44 | tool_tcp_port:=''
|
46 |
| - use_fake_hardware:='' |
47 |
| - fake_sensor_commands:='' |
| 45 | + use_mock_hardware:='' |
| 46 | + mock_sensor_commands:='' |
48 | 47 | sim_gazebo:=''
|
49 | 48 | sim_ignition:=''
|
50 | 49 | ">
|
|
61 | 60 | <xacro:property name="_safety_k_position" value="20" lazy_eval="false"/>
|
62 | 61 |
|
63 | 62 | <!-- Default ros2_control Parameters -->
|
64 |
| - <xacro:property name="_generate_ros2_control_tag" value="$(arg use_manipulation_controllers)" lazy_eval="false"/> |
65 | 63 | <xacro:property name="_headless_mode" value="false" lazy_eval="false"/>
|
66 | 64 | <xacro:property name="_robot_ip" value="192.168.131.40" lazy_eval="false"/>
|
67 | 65 | <xacro:property name="_script_filename" value="$(find ur_client_library)/resources/external_control.urscript" lazy_eval="false"/>
|
|
88 | 86 | <xacro:property name="_tool_tcp_port" value="54321" lazy_eval="false"/>
|
89 | 87 |
|
90 | 88 | <!-- Default Simulation Parameters -->
|
91 |
| - <xacro:property name="_use_fake_hardware" value="false" /> |
92 |
| - <xacro:property name="_fake_sensor_commands" value="false" /> |
| 89 | + <xacro:property name="_use_mock_hardware" value="false" /> |
| 90 | + <xacro:property name="_mock_sensor_commands" value="false" /> |
93 | 91 | <xacro:property name="_sim_gazebo" value="false" />
|
94 | 92 | <xacro:property name="_sim_ignition" value="$(arg is_sim)" />
|
95 | 93 |
|
|
105 | 103 | <xacro:if value="${safety_pos_margin != ''}"> <xacro:property name="_safety_pos_margin" value="${safety_pos_margin}" lazy_eval="false"/> </xacro:if>
|
106 | 104 | <xacro:if value="${safety_k_position != ''}"> <xacro:property name="_safety_k_position" value="${safety_k_position}" lazy_eval="false"/> </xacro:if>
|
107 | 105 |
|
108 |
| - <xacro:if value="${generate_ros2_control_tag != ''}"> <xacro:property name="_generate_ros2_control_tag" value="${generate_ros2_control_tag}" lazy_eval="false"/> </xacro:if> |
109 | 106 | <xacro:if value="${headless_mode != ''}"> <xacro:property name="_headless_mode" value="${headless_mode}" lazy_eval="false"/> </xacro:if>
|
110 | 107 | <xacro:if value="${robot_ip != ''}"> <xacro:property name="_robot_ip" value="${robot_ip}" lazy_eval="false"/> </xacro:if>
|
111 | 108 | <xacro:if value="${script_filename != ''}"> <xacro:property name="_script_filename" value="${script_filename}" lazy_eval="false"/> </xacro:if>
|
|
130 | 127 | <xacro:if value="${tool_device_name != ''}"> <xacro:property name="_tool_device_name" value="${tool_device_name}" lazy_eval="false"/> </xacro:if>
|
131 | 128 | <xacro:if value="${tool_tcp_port != ''}"> <xacro:property name="_tool_tcp_port" value="${tool_tcp_port}" lazy_eval="false"/> </xacro:if>
|
132 | 129 |
|
133 |
| - <xacro:if value="${use_fake_hardware != ''}"> <xacro:property name="_use_fake_hardware" value="${use_fake_hardware}" lazy_eval="false"/> </xacro:if> |
134 |
| - <xacro:if value="${fake_sensor_commands != ''}"> <xacro:property name="_fake_sensor_commands" value="${fake_sensor_commands}" lazy_eval="false"/> </xacro:if> |
| 130 | + <xacro:if value="${use_mock_hardware != ''}"> <xacro:property name="_use_mock_hardware" value="${use_mock_hardware}" lazy_eval="false"/> </xacro:if> |
| 131 | + <xacro:if value="${mock_sensor_commands != ''}"> <xacro:property name="_mock_sensor_commands" value="${mock_sensor_commands}" lazy_eval="false"/> </xacro:if> |
135 | 132 | <xacro:if value="${sim_gazebo != ''}"> <xacro:property name="_sim_gazebo" value="${sim_gazebo}" lazy_eval="false"/> </xacro:if>
|
136 | 133 | <xacro:if value="${sim_ignition != ''}"> <xacro:property name="_sim_ignition" value="${sim_ignition}" lazy_eval="false"/> </xacro:if>
|
137 | 134 |
|
138 |
| - <!-- Universal_Robots_ROS2_Description --> |
139 | 135 | <xacro:ur_robot
|
140 | 136 | name="${name}"
|
141 |
| - parent="${parent_link}" |
142 | 137 | tf_prefix="${_tf_prefix}"
|
143 |
| - initial_positions="${_initial_positions}" |
| 138 | + parent="${parent_link}" |
144 | 139 | joint_limits_parameters_file="${_joint_limits_parameters_file}"
|
145 | 140 | kinematics_parameters_file="${_kinematics_parameters_file}"
|
146 | 141 | physical_parameters_file="${_physical_parameters_file}"
|
147 | 142 | visual_parameters_file="${_visual_parameters_file}"
|
148 | 143 | safety_limits="${_safety_limits}"
|
149 | 144 | safety_pos_margin="${_safety_pos_margin}"
|
150 | 145 | safety_k_position="${_safety_k_position}"
|
151 |
| - generate_ros2_control_tag="${_generate_ros2_control_tag}" |
152 |
| - headless_mode="${_headless_mode}" |
153 |
| - robot_ip="${_robot_ip}" |
154 |
| - script_filename="${_script_filename}" |
155 |
| - output_recipe_filename="${_output_recipe_filename}" |
156 |
| - input_recipe_filename="${_input_recipe_filename}" |
157 |
| - reverse_ip="${_reverse_ip}" |
158 |
| - script_command_port="${_script_command_port}" |
159 |
| - reverse_port="${_reverse_port}" |
160 |
| - script_sender_port="${_script_sender_port}" |
161 |
| - trajectory_port="${_trajectory_port}" |
162 |
| - transmission_hw_interface="${_transmission_hw_interface}" |
163 |
| - non_blocking_read="{_non_blocking_read}" |
164 |
| - use_tool_communication="${_use_tool_communication}" |
165 |
| - tool_voltage="${_tool_voltage}" |
166 |
| - tool_parity="${_tool_parity}" |
167 |
| - tool_baud_rate="${_tool_baud_rate}" |
168 |
| - tool_stop_bits="${_tool_stop_bits}" |
169 |
| - tool_rx_idle_chars="${_tool_rx_idle_chars}" |
170 |
| - tool_tx_idle_chars="${_tool_tx_idle_chars}" |
171 |
| - tool_device_name="${_tool_device_name}" |
172 |
| - tool_tcp_port="${_tool_tcp_port}" |
173 |
| - use_fake_hardware="${_use_fake_hardware}" |
174 |
| - fake_sensor_commands="${_fake_sensor_commands}" |
175 |
| - sim_gazebo="${_sim_gazebo}" |
176 |
| - sim_ignition="${_sim_ignition}" |
177 | 146 | >
|
178 | 147 | <xacro:insert_block name="origin"/>
|
179 | 148 | </xacro:ur_robot>
|
| 149 | + |
| 150 | + <!-- Universal_Robots_ROS2_Driver HardwareInterface --> |
| 151 | + <xacro:if value="$(arg use_manipulation_controllers)"> |
| 152 | + <xacro:include filename="$(find ur_robot_driver)/urdf/ur.ros2_control.xacro" /> |
| 153 | + |
| 154 | + <xacro:ur_ros2_control |
| 155 | + name="${name}" |
| 156 | + tf_prefix="${_tf_prefix}" |
| 157 | + kinematics_parameters_file="${_kinematics_parameters_file}" |
| 158 | + transmission_hw_interface="${_transmission_hw_interface}" |
| 159 | + use_mock_hardware="${_use_mock_hardware}" |
| 160 | + mock_sensor_commands="${_mock_sensor_commands}" |
| 161 | + headless_mode="${_headless_mode}" |
| 162 | + initial_positions="${_initial_positions}" |
| 163 | + use_tool_communication="${_use_tool_communication}" |
| 164 | + tool_voltage="${_tool_voltage}" |
| 165 | + tool_parity="${_tool_parity}" |
| 166 | + tool_baud_rate="${_tool_baud_rate}" |
| 167 | + tool_stop_bits="${_tool_stop_bits}" |
| 168 | + tool_rx_idle_chars="${_tool_rx_idle_chars}" |
| 169 | + tool_tx_idle_chars="${_tool_tx_idle_chars}" |
| 170 | + tool_device_name="${_tool_device_name}" |
| 171 | + tool_tcp_port="${_tool_tcp_port}" |
| 172 | + robot_ip="${_robot_ip}" |
| 173 | + script_filename="${_script_filename}" |
| 174 | + output_recipe_filename="${_output_recipe_filename}" |
| 175 | + input_recipe_filename="${_input_recipe_filename}" |
| 176 | + reverse_ip="${_reverse_ip}" |
| 177 | + script_command_port="${_script_command_port}" |
| 178 | + reverse_port="${_reverse_port}" |
| 179 | + script_sender_port="${_script_sender_port}" |
| 180 | + trajectory_port="${_trajectory_port}" |
| 181 | + /> |
| 182 | + </xacro:if> |
180 | 183 | </xacro:macro>
|
181 | 184 | </robot>
|
0 commit comments