|
3 | 3 |
|
4 | 4 | <xacro:macro name="ur_ros2_control" params=" |
5 | 5 | name |
6 | | - prefix |
7 | 6 | use_fake_hardware:=false fake_sensor_commands:=false |
8 | 7 | sim_gazebo:=false |
9 | 8 | sim_ignition:=false |
|
39 | 38 | </xacro:if> |
40 | 39 | <xacro:unless value="${use_fake_hardware or sim_gazebo or sim_ignition}"> |
41 | 40 | <plugin>ur_robot_driver/URPositionHardwareInterface</plugin> |
42 | | - <param name="prefix">${prefix}</param> |
43 | 41 | <param name="robot_ip">${robot_ip}</param> |
44 | 42 | <param name="script_filename">${script_filename}</param> |
45 | 43 | <param name="output_recipe_filename">${output_recipe_filename}</param> |
|
67 | 65 | <param name="keep_alive_count">${keep_alive_count}</param> |
68 | 66 | </xacro:unless> |
69 | 67 | </hardware> |
70 | | - <joint name="${prefix}shoulder_pan_joint"> |
| 68 | + <joint name="${tf_prefix}shoulder_pan_joint"> |
71 | 69 | <command_interface name="position"> |
72 | 70 | <param name="min">{-2*pi}</param> |
73 | 71 | <param name="max">{2*pi}</param> |
|
83 | 81 | <state_interface name="velocity"/> |
84 | 82 | <state_interface name="effort"/> |
85 | 83 | </joint> |
86 | | - <joint name="${prefix}shoulder_lift_joint"> |
| 84 | + <joint name="${tf_prefix}shoulder_lift_joint"> |
87 | 85 | <command_interface name="position"> |
88 | 86 | <param name="min">{-2*pi}</param> |
89 | 87 | <param name="max">{2*pi}</param> |
|
99 | 97 | <state_interface name="velocity"/> |
100 | 98 | <state_interface name="effort"/> |
101 | 99 | </joint> |
102 | | - <joint name="${prefix}elbow_joint"> |
| 100 | + <joint name="${tf_prefix}elbow_joint"> |
103 | 101 | <command_interface name="position"> |
104 | 102 | <param name="min">{-pi}</param> |
105 | 103 | <param name="max">{pi}</param> |
|
115 | 113 | <state_interface name="velocity"/> |
116 | 114 | <state_interface name="effort"/> |
117 | 115 | </joint> |
118 | | - <joint name="${prefix}wrist_1_joint"> |
| 116 | + <joint name="${tf_prefix}wrist_1_joint"> |
119 | 117 | <command_interface name="position"> |
120 | 118 | <param name="min">{-2*pi}</param> |
121 | 119 | <param name="max">{2*pi}</param> |
|
131 | 129 | <state_interface name="velocity"/> |
132 | 130 | <state_interface name="effort"/> |
133 | 131 | </joint> |
134 | | - <joint name="${prefix}wrist_2_joint"> |
| 132 | + <joint name="${tf_prefix}wrist_2_joint"> |
135 | 133 | <command_interface name="position"> |
136 | 134 | <param name="min">{-2*pi}</param> |
137 | 135 | <param name="max">{2*pi}</param> |
|
147 | 145 | <state_interface name="velocity"/> |
148 | 146 | <state_interface name="effort"/> |
149 | 147 | </joint> |
150 | | - <joint name="${prefix}wrist_3_joint"> |
| 148 | + <joint name="${tf_prefix}wrist_3_joint"> |
151 | 149 | <command_interface name="position"> |
152 | 150 | <param name="min">{-2*pi}</param> |
153 | 151 | <param name="max">{2*pi}</param> |
|
165 | 163 | </joint> |
166 | 164 |
|
167 | 165 | <xacro:unless value="${sim_gazebo or sim_ignition}"> |
168 | | - <sensor name="${prefix}tcp_fts_sensor"> |
| 166 | + <sensor name="${tf_prefix}tcp_fts_sensor"> |
169 | 167 | <state_interface name="force.x"/> |
170 | 168 | <state_interface name="force.y"/> |
171 | 169 | <state_interface name="force.z"/> |
|
175 | 173 | </sensor> |
176 | 174 |
|
177 | 175 | <!-- NOTE The following are joints used only for testing with fake hardware and will change in the future --> |
178 | | - <gpio name="${prefix}speed_scaling"> |
| 176 | + <gpio name="${tf_prefix}speed_scaling"> |
179 | 177 | <state_interface name="speed_scaling_factor"/> |
180 | 178 | <param name="initial_speed_scaling_factor">1</param> |
181 | 179 | <command_interface name="target_speed_fraction_cmd"/> |
182 | 180 | <command_interface name="target_speed_fraction_async_success"/> |
183 | 181 | </gpio> |
184 | 182 |
|
185 | | - <gpio name="${prefix}gpio"> |
| 183 | + <gpio name="${tf_prefix}gpio"> |
186 | 184 | <command_interface name="standard_digital_output_cmd_0"/> |
187 | 185 | <command_interface name="standard_digital_output_cmd_1"/> |
188 | 186 | <command_interface name="standard_digital_output_cmd_2"/> |
|
291 | 289 | <state_interface name="program_running"/> |
292 | 290 | </gpio> |
293 | 291 |
|
294 | | - <gpio name="${prefix}payload"> |
| 292 | + <gpio name="${tf_prefix}payload"> |
295 | 293 | <command_interface name="mass"/> |
296 | 294 | <command_interface name="cog.x"/> |
297 | 295 | <command_interface name="cog.y"/> |
298 | 296 | <command_interface name="cog.z"/> |
299 | 297 | <command_interface name="payload_async_success"/> |
300 | 298 | </gpio> |
301 | 299 |
|
302 | | - <gpio name="${prefix}resend_robot_program"> |
| 300 | + <gpio name="${tf_prefix}resend_robot_program"> |
303 | 301 | <command_interface name="resend_robot_program_cmd"/> |
304 | 302 | <command_interface name="resend_robot_program_async_success"/> |
305 | 303 | </gpio> |
306 | 304 |
|
307 | | - <gpio name="${prefix}zero_ftsensor"> |
| 305 | + <gpio name="${tf_prefix}zero_ftsensor"> |
308 | 306 | <command_interface name="zero_ftsensor_cmd"/> |
309 | 307 | <command_interface name="zero_ftsensor_async_success"/> |
310 | 308 | </gpio> |
311 | 309 |
|
312 | | - <gpio name="${prefix}system_interface"> |
| 310 | + <gpio name="${tf_prefix}system_interface"> |
313 | 311 | <state_interface name="initialized"/> |
314 | 312 | </gpio> |
315 | 313 |
|
|
0 commit comments