ros2_control - foxy
Loading...
Searching...
No Matches
components_urdfs.hpp
1// Copyright (c) 2021 Stogl Robotics Consulting
2//
3// Licensed under the Apache License, Version 2.0 (the "License");
4// you may not use this file except in compliance with the License.
5// You may obtain a copy of the License at
6//
7// http://www.apache.org/licenses/LICENSE-2.0
8//
9// Unless required by applicable law or agreed to in writing, software
10// distributed under the License is distributed on an "AS IS" BASIS,
11// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
12// See the License for the specific language governing permissions and
13// limitations under the License.
14
15#ifndef ROS2_CONTROL_TEST_ASSETS__COMPONENTS_URDFS_HPP_
16#define ROS2_CONTROL_TEST_ASSETS__COMPONENTS_URDFS_HPP_
17
18#include <string>
19
20namespace ros2_control_test_assets
21{
22// 1. Industrial Robots with only one interface
23const auto valid_urdf_ros2_control_system_one_interface =
24 R"(
25 <ros2_control name="RRBotSystemPositionOnly" type="system">
26 <hardware>
27 <plugin>ros2_control_demo_hardware/RRBotSystemPositionOnlyHardware</plugin>
28 <param name="example_param_write_for_sec">2</param>
29 <param name="example_param_read_for_sec">2</param>
30 </hardware>
31 <joint name="joint1">
32 <command_interface name="position">
33 <param name="min">-1</param>
34 <param name="max">1</param>
35 </command_interface>
36 <state_interface name="position"/>
37 </joint>
38 <joint name="joint2">
39 <command_interface name="position">
40 <param name="min">-1</param>
41 <param name="max">1</param>
42 </command_interface>
43 <state_interface name="position"/>
44 </joint>
45 </ros2_control>
46)";
47
48// 2. Industrial Robots with multiple interfaces (cannot be written at the same time)
49// Note, joint parameters can be any string
50const auto valid_urdf_ros2_control_system_multi_interface =
51 R"(
52 <ros2_control name="RRBotSystemMultiInterface" type="system">
53 <hardware>
54 <plugin>ros2_control_demo_hardware/RRBotSystemMultiInterfaceHardware</plugin>
55 <param name="example_param_write_for_sec">2</param>
56 <param name="example_param_read_for_sec">2</param>
57 </hardware>
58 <joint name="joint1">
59 <command_interface name="position">
60 <param name="min">-1</param>
61 <param name="max">1</param>
62 <param name="initial_value">1.2</param>
63 </command_interface>
64 <command_interface name="velocity">
65 <param name="min">-1</param>
66 <param name="max">1</param>
67 <param name="initial_value">3.4</param>
68 </command_interface>
69 <command_interface name="effort">
70 <param name="min">-0.5</param>
71 <param name="max">0.5"</param>
72 </command_interface>
73 <state_interface name="position"/>
74 <state_interface name="velocity"/>
75 <state_interface name="effort"/>
76 </joint>
77 <joint name="joint2">
78 <command_interface name="position">
79 <param name="min">-1</param>
80 <param name="max">1</param>
81 </command_interface>
82 <state_interface name="position"/>
83 <state_interface name="velocity"/>
84 <state_interface name="effort"/>
85 </joint>
86 </ros2_control>
87)";
88
89// 3. Industrial Robots with integrated sensor
90const auto valid_urdf_ros2_control_system_robot_with_sensor =
91 R"(
92 <ros2_control name="RRBotSystemWithSensor" type="system">
93 <hardware>
94 <plugin>ros2_control_demo_hardware/RRBotSystemWithSensorHardware</plugin>
95 <param name="example_param_write_for_sec">2</param>
96 <param name="example_param_read_for_sec">2</param>
97 </hardware>
98 <joint name="joint1">
99 <command_interface name="position">
100 <param name="min">-1</param>
101 <param name="max">1</param>
102 </command_interface>
103 <state_interface name="position"/>
104 </joint>
105 <joint name="joint2">
106 <command_interface name="position">
107 <param name="min">-1</param>
108 <param name="max">1</param>
109 </command_interface>
110 <state_interface name="position"/>
111 </joint>
112 <sensor name="tcp_fts_sensor">
113 <state_interface name="fx"/>
114 <state_interface name="fy"/>
115 <state_interface name="fz"/>
116 <state_interface name="tx"/>
117 <state_interface name="ty"/>
118 <state_interface name="tz"/>
119 <param name="frame_id">kuka_tcp</param>
120 <param name="lower_limits">-100</param>
121 <param name="upper_limits">100</param>
122 </sensor>
123 </ros2_control>
124)";
125
126// 4. Industrial Robots with externally connected sensor
127const auto valid_urdf_ros2_control_system_robot_with_external_sensor =
128 R"(
129 <ros2_control name="RRBotSystemPositionOnlyWithExternalSensor" type="system">
130 <hardware>
131 <plugin>ros2_control_demo_hardware/RRBotSystemPositionOnlyHardware</plugin>
132 <param name="example_param_write_for_sec">2</param>
133 <param name="example_param_read_for_sec">2</param>
134 </hardware>
135 <joint name="joint1">
136 <command_interface name="position">
137 <param name="min">-1</param>
138 <param name="max">1</param>
139 </command_interface>
140 <state_interface name="position"/>
141 </joint>
142 <joint name="joint2">
143 <command_interface name="position">
144 <param name="min">-1</param>
145 <param name="max">1</param>
146 </command_interface>
147 <state_interface name="position"/>
148 </joint>
149 </ros2_control>
150 <ros2_control name="RRBotForceTorqueSensor2D" type="sensor">
151 <hardware>
152 <plugin>ros2_control_demo_hardware/ForceTorqueSensor2DHardware</plugin>
153 <param name="example_param_read_for_sec">0.43</param>
154 </hardware>
155 <sensor name="tcp_fts_sensor">
156 <state_interface name="fx"/>
157 <state_interface name="fy"/>
158 <state_interface name="fz"/>
159 <state_interface name="tx"/>
160 <state_interface name="ty"/>
161 <state_interface name="tz"/>
162 <param name="frame_id">kuka_tcp</param>
163 <param name="lower_limits">-100</param>
164 <param name="upper_limits">100</param>
165 </sensor>
166 </ros2_control>
167)";
168
169// 5. Modular Robots with separate communication to each actuator
170const auto valid_urdf_ros2_control_actuator_modular_robot =
171 R"(
172 <ros2_control name="RRBotModularJoint1" type="actuator">
173 <hardware>
174 <plugin>ros2_control_demo_hardware/PositionActuatorHardware</plugin>
175 <param name="example_param_write_for_sec">1.23</param>
176 <param name="example_param_read_for_sec">3</param>
177 </hardware>
178 <joint name="joint1">
179 <command_interface name="position">
180 <param name="min">-1</param>
181 <param name="max">1</param>
182 </command_interface>
183 <state_interface name="position"/>
184 </joint>
185 </ros2_control>
186 <ros2_control name="RRBotModularJoint2" type="actuator">
187 <hardware>
188 <plugin>ros2_control_demo_hardware/PositionActuatorHardware</plugin>
189 <param name="example_param_write_for_sec">1.23</param>
190 <param name="example_param_read_for_sec">3</param>
191 </hardware>
192 <joint name="joint2">
193 <command_interface name="position">
194 <param name="min">-1</param>
195 <param name="max">1</param>
196 </command_interface>
197 <state_interface name="position"/>
198 </joint>
199 </ros2_control>
200)";
201
202// 6. Modular Robots with actuators not providing states and with additional sensors
203// Example for simple transmission
204const auto valid_urdf_ros2_control_actuator_modular_robot_sensors =
205 R"(
206 <ros2_control name="RRBotModularJoint1" type="actuator">
207 <hardware>
208 <plugin>ros2_control_demo_hardware/VelocityActuatorHardware</plugin>
209 <param name="example_param_write_for_sec">1.23</param>
210 <param name="example_param_read_for_sec">3</param>
211 </hardware>
212 <joint name="joint1">
213 <command_interface name="velocity">
214 <param name="min">-1</param>
215 <param name="max">1</param>
216 </command_interface>
217 <state_interface name="velocity"/>
218 </joint>
219 <transmission name="transmission1">
220 <plugin>transmission_interface/SimpleTansmission</plugin>
221 <joint name="joint1" role="joint1">
222 <mechanical_reduction>325.949</mechanical_reduction>
223 </joint>
224 </transmission>
225 </ros2_control>
226 <ros2_control name="RRBotModularJoint2" type="actuator">
227 <hardware>
228 <plugin>ros2_control_demo_hardware/VelocityActuatorHardware</plugin>
229 <param name="example_param_write_for_sec">1.23</param>
230 <param name="example_param_read_for_sec">3</param>
231 </hardware>
232 <joint name="joint2">
233 <command_interface name="velocity">
234 <param name="min">-1</param>
235 <param name="max">1</param>
236 </command_interface>
237 <state_interface name="velocity"/>
238 </joint>
239 </ros2_control>
240 <ros2_control name="RRBotModularPositionSensorJoint1" type="sensor">
241 <hardware>
242 <plugin>ros2_control_demo_hardware/PositionSensorHardware</plugin>
243 <param name="example_param_read_for_sec">2</param>
244 </hardware>
245 <joint name="joint1">
246 <state_interface name="position"/>
247 </joint>
248 </ros2_control>
249 <ros2_control name="RRBotModularPositionSensorJoint2" type="sensor">
250 <hardware>
251 <plugin>ros2_control_demo_hardware/PositionSensorHardware</plugin>
252 <param name="example_param_read_for_sec">2</param>
253 </hardware>
254 <joint name="joint2">
255 <state_interface name="position"/>
256 </joint>
257 </ros2_control>
258)";
259
260// 7. Modular Robots with separate communication to each "actuator" with multi joints
261// Example for complex transmission (multi-joint/multi-actuator) - (system component is used)
262const auto valid_urdf_ros2_control_system_multi_joints_transmission =
263 R"(
264 <ros2_control name="RRBotModularWrist" type="system">
265 <hardware>
266 <plugin>ros2_control_demo_hardware/ActuatorHardwareMultiDOF</plugin>
267 <param name="example_param_write_for_sec">1.23</param>
268 <param name="example_param_read_for_sec">3</param>
269 </hardware>
270 <joint name="joint1">
271 <command_interface name="position">
272 <param name="min">-1</param>
273 <param name="max">1</param>
274 </command_interface>
275 <state_interface name="position"/>
276 </joint>
277 <joint name="joint2">
278 <command_interface name="position">
279 <param name="min">-1</param>
280 <param name="max">1</param>
281 </command_interface>
282 <state_interface name="position"/>
283 </joint>
284 <transmission name="transmission1">
285 <plugin>transmission_interface/DifferentialTransmission</plugin>
286 <actuator name="joint1_motor" role="actuator1"/>
287 <actuator name="joint2_motor" role="actuator2"/>
288 <joint name="joint1" role="joint1">
289 <mechanical_reduction>10</mechanical_reduction>
290 <offset>0.5</offset>
291 </joint>
292 <joint name="joint2" role="joint2">
293 <mechanical_reduction>50</mechanical_reduction>
294 </joint>
295 </transmission>
296 </ros2_control>
297)";
298
299// 8. Sensor only
300const auto valid_urdf_ros2_control_sensor_only =
301 R"(
302 <ros2_control name="CameraWithIMU" type="sensor">
303 <hardware>
304 <plugin>ros2_control_demo_hardware/CameraWithIMUSensor</plugin>
305 <param name="example_param_read_for_sec">2</param>
306 </hardware>
307 <sensor name="sensor1">
308 <state_interface name="roll"/>
309 <state_interface name="pitch"/>
310 <state_interface name="yaw"/>
311 </sensor>
312 <sensor name="sensor2">
313 <state_interface name="image"/>
314 </sensor>
315 </ros2_control>
316)";
317
318// 9. Actuator Only
319const auto valid_urdf_ros2_control_actuator_only =
320 R"(
321 <ros2_control name="ActuatorModularJoint1" type="actuator">
322 <hardware>
323 <plugin>ros2_control_demo_hardware/VelocityActuatorHardware</plugin>
324 <param name="example_param_write_for_sec">1.13</param>
325 <param name="example_param_read_for_sec">3</param>
326 </hardware>
327 <joint name="joint1">
328 <command_interface name="velocity">
329 <param name="min">-1</param>
330 <param name="max">1</param>
331 </command_interface>
332 <state_interface name="velocity"/>
333 </joint>
334 <transmission name="transmission1">
335 <plugin>transmission_interface/RotationToLinerTansmission</plugin>
336 <joint name="joint1" role="joint1">
337 <mechanical_reduction>325.949</mechanical_reduction>
338 </joint>
339 <param name="additional_special_parameter">1337</param>
340 </transmission>
341 </ros2_control>
342)";
343
344// 10. Industrial Robots with integrated GPIO
345const auto valid_urdf_ros2_control_system_robot_with_gpio =
346 R"(
347 <ros2_control name="RRBotSystemWithGPIO" type="system">
348 <hardware>
349 <plugin>ros2_control_demo_hardware/RRBotSystemWithGPIOHardware</plugin>
350 <param name="example_param_write_for_sec">2</param>
351 <param name="example_param_read_for_sec">2</param>
352 </hardware>
353 <joint name="joint1">
354 <command_interface name="position">
355 <param name="min">-1</param>
356 <param name="max">1</param>
357 </command_interface>
358 <state_interface name="position"/>
359 </joint>
360 <joint name="joint2">
361 <command_interface name="position">
362 <param name="min">-1</param>
363 <param name="max">1</param>
364 </command_interface>
365 <state_interface name="position"/>
366 </joint>
367 <gpio name="flange_analog_IOs">
368 <command_interface name="analog_output1"/>
369 <state_interface name="analog_output1"/> <!-- Needed to know current state of the output -->
370 <state_interface name="analog_input1"/>
371 <state_interface name="analog_input2"/>
372 </gpio>
373 <gpio name="flange_vacuum">
374 <command_interface name="vacuum"/>
375 <state_interface name="vacuum"/> <!-- Needed to know current state of the input -->
376 </gpio>
377 </ros2_control>
378)";
379
380// 11. Industrial Robots using size and data_type attributes
381const auto valid_urdf_ros2_control_system_robot_with_size_and_data_type =
382 R"(
383 <ros2_control name="RRBotSystemWithSizeAndDataType" type="system">
384 <hardware>
385 <plugin>ros2_control_demo_hardware/RRBotSystemWithSizeAndDataType</plugin>
386 <param name="example_param_write_for_sec">2</param>
387 <param name="example_param_read_for_sec">2</param>
388 </hardware>
389 <joint name="joint1">
390 <command_interface name="position"/>
391 <state_interface name="position"/>
392 </joint>
393 <gpio name="flange_IOS">
394 <command_interface name="digital_output" size="2" data_type="bool"/>
395 <state_interface name="analog_input" size="3"/>
396 <state_interface name="image" data_type="cv::Mat"/>
397 </gpio>
398 </ros2_control>
399)";
400
401// Errors
402const auto invalid_urdf_ros2_control_invalid_child =
403 R"(
404 <ros2_control name="2DOF_System_Robot_Position_Only" type="system">
405 <hardwarert>
406 <plugin>ros2_control_demo_hardware/2DOF_System_Hardware_Position_Only</plugin>
407 <param name="example_param_write_for_sec">2</param>
408 <param name="example_param_read_for_sec">2</param>
409 </hardwarert>
410 </ros2_control>
411 )";
412
413const auto invalid_urdf_ros2_control_missing_attribute =
414 R"(
415 <ros2_control type="system">
416 <hardware>
417 <plugin>ros2_control_demo_hardware/2DOF_System_Hardware_Position_Only</plugin>
418 <param name="example_param_write_for_sec">2</param>
419 <param name="example_param_read_for_sec">2</param>
420 </hardware>
421 </ros2_control>
422 )";
423
424const auto invalid_urdf_ros2_control_component_missing_class_type =
425 R"(
426 <ros2_control name="2DOF_System_Robot_Position_Only" type="system">
427 <hardware>
428 <plugin>ros2_control_demo_hardware/2DOF_System_Hardware_Position_Only</plugin>
429 <param name="example_param_write_for_sec">2</param>
430 <param name="example_param_read_for_sec">2</param>
431 </hardware>
432 <joint name="joint1">
433 <param name="min_position_value">-1</param>
434 <param name="max_position_value">1</param>
435 </joint>
436 </ros2_control>
437)";
438
439const auto invalid_urdf_ros2_control_parameter_missing_name =
440 R"(
441 <ros2_control name="2DOF_System_Robot_Position_Only" type="system">
442 <hardware>
443 <plugin>ros2_control_demo_hardware/2DOF_System_Hardware_Position_Only</plugin>
444 <param>2</param>
445 <param name="example_param_read_for_sec">2</param>
446 </hardware>
447 <joint name="joint1">
448 <plugin>ros2_control_components/PositionJoint</plugin>
449 <param name="min_position_value">-1</param>
450 <param name="max_position_value">1</param>
451 </joint>
452 </ros2_control>
453)";
454
455const auto invalid_urdf_ros2_control_component_class_type_empty =
456 R"(
457 <ros2_control name="2DOF_System_Robot_Position_Only" type="system">
458 <hardware>
459 <plugin>ros2_control_demo_hardware/2DOF_System_Hardware_Position_Only</plugin>
460 <param name="example_param_write_for_sec">2</param>
461 <param name="example_param_read_for_sec">2</param>
462 </hardware>
463 <joint name="joint1">
464 <plugin></plugin>
465 <param name="min_position_value">-1</param>
466 <param name="max_position_value">1</param>
467 </joint>
468 </ros2_control>
469)";
470
471const auto invalid_urdf_ros2_control_component_interface_type_empty =
472 R"(
473 <ros2_control name="2DOF_System_Robot_Position_Only" type="system">
474 <hardware>
475 <plugin>ros2_control_demo_hardware/2DOF_System_Hardware_Position_Only</plugin>
476 <param name="example_param_write_for_sec">2</param>
477 <param name="example_param_read_for_sec">2</param>
478 </hardware>
479 <joint name="joint1">
480 <plugin>ros2_control_components/PositionJoint</plugin>
481 <state_interface></state_interface>
482 <param name="min_position_value">-1</param>
483 <param name="max_position_value">1</param>
484 </joint>
485 </ros2_control>
486)";
487
488const auto invalid_urdf_ros2_control_parameter_empty =
489 R"(
490 <ros2_control name="2DOF_System_Robot_Position_Only" type="system">
491 <hardware>
492 <plugin>ros2_control_demo_hardware/2DOF_System_Hardware_Position_Only</plugin>
493 <param name="example_param_write_for_sec"></param>
494 <param name="example_param_read_for_sec">2</param>
495 </hardware>
496 <joint name="joint1">
497 <command_interface name="position">
498 <param name="min_position_value">-1</param>
499 <param name="max_position_value">1</param>
500 </command_interface>
501 </joint>
502 </ros2_control>
503)";
504
505const auto invalid_urdf2_ros2_control_illegal_size =
506 R"(
507 <ros2_control name="RRBotSystemWithIllegalSize" type="system">
508 <hardware>
509 <plugin>ros2_control_demo_hardware/RRBotSystemWithIllegalSize</plugin>
510 </hardware>
511 <gpio name="flange_IOS">
512 <command_interface name="digital_output" data_type="bool" size="-4"/>
513 </gpio>
514 </ros2_control>
515)";
516
517const auto invalid_urdf2_ros2_control_illegal_size2 =
518 R"(
519 <ros2_control name="RRBotSystemWithIllegalSize2" type="system">
520 <hardware>
521 <plugin>ros2_control_demo_hardware/RRBotSystemWithIllegalSize2</plugin>
522 </hardware>
523 <gpio name="flange_IOS">
524 <command_interface name="digital_output" data_type="bool" size="ILLEGAL"/>
525 </gpio>
526 </ros2_control>
527)";
528
529const auto invalid_urdf2_hw_transmission_joint_mismatch =
530 R"(
531 <ros2_control name="ActuatorModularJoint1" type="actuator">
532 <hardware>
533 <plugin>ros2_control_demo_hardware/VelocityActuatorHardware</plugin>
534 </hardware>
535 <joint name="joint1">
536 <command_interface name="velocity">
537 <param name="min">-1</param>
538 <param name="max">1</param>
539 </command_interface>
540 <state_interface name="velocity"/>
541 </joint>
542 <transmission name="transmission1">
543 <plugin>transmission_interface/SimpleTransmission</plugin>
544 <joint name="joint31415" role="joint1"/>
545 </transmission>
546 </ros2_control>
547)";
548
549const auto invalid_urdf2_transmission_given_too_many_joints =
550 R"(
551 <ros2_control name="ActuatorModularJoint1" type="actuator">
552 <hardware>
553 <plugin>ros2_control_demo_hardware/VelocityActuatorHardware</plugin>
554 </hardware>
555 <joint name="joint1">
556 <command_interface name="velocity">
557 <param name="min">-1</param>
558 <param name="max">1</param>
559 </command_interface>
560 <state_interface name="velocity"/>
561 </joint>
562 <transmission name="transmission1">
563 <plugin>transmission_interface/SimpleTransmission</plugin>
564 <joint name="joint1" role="joint1"/>
565 <joint name="joint2" role="joint2"/>
566 </transmission>
567 </ros2_control>
568)";
569
570} // namespace ros2_control_test_assets
571
572#endif // ROS2_CONTROL_TEST_ASSETS__COMPONENTS_URDFS_HPP_