ros2_control - jazzy
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
18namespace ros2_control_test_assets
19{
20// 1. Industrial Robots with only one interface
21const auto valid_urdf_ros2_control_system_one_interface =
22 R"(
23 <ros2_control name="RRBotSystemPositionOnly" type="system">
24 <hardware>
25 <plugin>ros2_control_demo_hardware/RRBotSystemPositionOnlyHardware</plugin>
26 <param name="example_param_write_for_sec">2</param>
27 <param name="example_param_read_for_sec">2</param>
28 </hardware>
29 <joint name="joint1">
30 <command_interface name="position">
31 <param name="min">-1</param>
32 <param name="max">1</param>
33 </command_interface>
34 <state_interface name="position"/>
35 </joint>
36 <joint name="joint2">
37 <command_interface name="position">
38 <param name="min">-1</param>
39 <param name="max">1</param>
40 </command_interface>
41 <state_interface name="position"/>
42 </joint>
43 </ros2_control>
44)";
45
46// 2.1 Industrial Robots with multiple interfaces (cannot be written at the same time)
47// Note, joint parameters can be any string
48const auto valid_urdf_ros2_control_system_multi_interface =
49 R"(
50 <ros2_control name="RRBotSystemMultiInterface" type="system">
51 <hardware>
52 <plugin>ros2_control_demo_hardware/RRBotSystemMultiInterfaceHardware</plugin>
53 <param name="example_param_write_for_sec">2</param>
54 <param name="example_param_read_for_sec">2</param>
55 </hardware>
56 <joint name="joint1">
57 <command_interface name="position">
58 <param name="min">-1</param>
59 <param name="max">1</param>
60 <param name="initial_value">1.2</param>
61 </command_interface>
62 <command_interface name="velocity">
63 <param name="min">-1</param>
64 <param name="max">1</param>
65 <param name="initial_value">3.4</param>
66 </command_interface>
67 <command_interface name="effort">
68 <param name="min">-0.5</param>
69 <param name="max">0.5"</param>
70 </command_interface>
71 <state_interface name="position"/>
72 <state_interface name="velocity"/>
73 <state_interface name="effort"/>
74 </joint>
75 <joint name="joint2">
76 <command_interface name="position">
77 <param name="min">-1</param>
78 <param name="max">1</param>
79 </command_interface>
80 <state_interface name="position"/>
81 <state_interface name="velocity"/>
82 <state_interface name="effort"/>
83 </joint>
84 </ros2_control>
85)";
86
87// 2.2 Industrial Robots with multiple interfaces (cannot be written at the same time)
88// Additionally some of the Command-/StateInterfaces have parameters defined per interface
89const auto valid_urdf_ros2_control_system_multi_interface_and_custom_interface_parameters =
90 R"(
91 <ros2_control name="RRBotSystemMultiInterface" type="system">
92 <hardware>
93 <plugin>ros2_control_demo_hardware/RRBotSystemMultiInterfaceHardware</plugin>
94 <param name="example_param_write_for_sec">2</param>
95 <param name="example_param_read_for_sec">2</param>
96 </hardware>
97 <joint name="joint1">
98 <command_interface name="position">
99 <param name="min">-1</param>
100 <param name="max">1</param>
101 <param name="initial_value">1.2</param>
102 <param name="register">1</param>
103 <param name="register_size">2</param>
104 </command_interface>
105 <command_interface name="velocity">
106 <param name="min">-1.5</param>
107 <param name="max">1.5</param>
108 <param name="initial_value">3.4</param>
109 <param name="register">2</param>
110 <param name="register_size">4</param>
111 </command_interface>
112 <command_interface name="effort">
113 <param name="min">-0.5</param>
114 <param name="max">0.5</param>
115 </command_interface>
116 <state_interface name="position">
117 <param name="register">3</param>
118 <param name="register_size">2</param>
119 </state_interface>
120 <state_interface name="velocity">
121 <param name="register">4</param>
122 <param name="register_size">4</param>
123 </state_interface>
124 <state_interface name="effort"/>
125 <param name="modbus_server_ip">1.1.1.1</param>
126 <param name="modbus_server_port">1234</param>
127 <param name="use_persistent_connection">true</param>
128 </joint>
129 <joint name="joint2">
130 <command_interface name="position">
131 <param name="min">-1</param>
132 <param name="max">1</param>
133 <param name="register">20</param>
134 <param name="data_type">int32_t</param>
135 </command_interface>
136 <state_interface name="position">
137 <param name="register">21</param>
138 <param name="data_type">int32_t</param>
139 </state_interface>
140 <state_interface name="velocity"/>
141 <state_interface name="effort">
142 <param name="register">21</param>
143 <param name="data_type">int32_t</param>
144 </state_interface>
145 <param name="modbus_server_ip">192.168.178.123</param>
146 <param name="modbus_server_port">4321</param>
147 </joint>
148 </ros2_control>
149)";
150
151// 3. Industrial Robots with integrated sensor
152const auto valid_urdf_ros2_control_system_robot_with_sensor =
153 R"(
154 <ros2_control name="RRBotSystemWithSensor" type="system">
155 <hardware>
156 <plugin>ros2_control_demo_hardware/RRBotSystemWithSensorHardware</plugin>
157 <param name="example_param_write_for_sec">2</param>
158 <param name="example_param_read_for_sec">2</param>
159 </hardware>
160 <joint name="joint1">
161 <command_interface name="position">
162 <param name="min">-1</param>
163 <param name="max">1</param>
164 </command_interface>
165 <state_interface name="position"/>
166 </joint>
167 <joint name="joint2">
168 <command_interface name="position">
169 <param name="min">-1</param>
170 <param name="max">1</param>
171 </command_interface>
172 <state_interface name="position"/>
173 </joint>
174 <sensor name="tcp_fts_sensor">
175 <state_interface name="fx"/>
176 <state_interface name="fy"/>
177 <state_interface name="fz"/>
178 <state_interface name="tx"/>
179 <state_interface name="ty"/>
180 <state_interface name="tz"/>
181 <param name="frame_id">kuka_tcp</param>
182 <param name="lower_limits">-100</param>
183 <param name="upper_limits">100</param>
184 </sensor>
185 </ros2_control>
186)";
187
188// 4. Industrial Robots with externally connected sensor
189const auto valid_urdf_ros2_control_system_robot_with_external_sensor =
190 R"(
191 <ros2_control name="RRBotSystemPositionOnlyWithExternalSensor" type="system">
192 <hardware>
193 <plugin>ros2_control_demo_hardware/RRBotSystemPositionOnlyHardware</plugin>
194 <param name="example_param_write_for_sec">2</param>
195 <param name="example_param_read_for_sec">2</param>
196 </hardware>
197 <joint name="joint1">
198 <command_interface name="position">
199 <param name="min">-1</param>
200 <param name="max">1</param>
201 </command_interface>
202 <state_interface name="position"/>
203 </joint>
204 <joint name="joint2">
205 <command_interface name="position">
206 <param name="min">-1</param>
207 <param name="max">1</param>
208 </command_interface>
209 <state_interface name="position"/>
210 </joint>
211 </ros2_control>
212 <ros2_control name="RRBotForceTorqueSensor2D" type="sensor">
213 <hardware>
214 <plugin>ros2_control_demo_hardware/ForceTorqueSensor2DHardware</plugin>
215 <param name="example_param_read_for_sec">0.43</param>
216 </hardware>
217 <sensor name="tcp_fts_sensor">
218 <state_interface name="fx"/>
219 <state_interface name="fy"/>
220 <state_interface name="fz"/>
221 <state_interface name="tx"/>
222 <state_interface name="ty"/>
223 <state_interface name="tz"/>
224 <param name="frame_id">kuka_tcp</param>
225 <param name="lower_limits">-100</param>
226 <param name="upper_limits">100</param>
227 </sensor>
228 </ros2_control>
229)";
230
231// 5. Modular Robots with separate communication to each actuator
232const auto valid_urdf_ros2_control_actuator_modular_robot =
233 R"(
234 <ros2_control name="RRBotModularJoint1" type="actuator">
235 <hardware>
236 <plugin>ros2_control_demo_hardware/PositionActuatorHardware</plugin>
237 <group>Hardware Group</group>
238 <param name="example_param_write_for_sec">1.23</param>
239 <param name="example_param_read_for_sec">3</param>
240 </hardware>
241 <joint name="joint1">
242 <command_interface name="position">
243 <param name="min">-1</param>
244 <param name="max">1</param>
245 </command_interface>
246 <state_interface name="position"/>
247 </joint>
248 </ros2_control>
249 <ros2_control name="RRBotModularJoint2" type="actuator">
250 <hardware>
251 <plugin>ros2_control_demo_hardware/PositionActuatorHardware</plugin>
252 <group>Hardware Group</group>
253 <param name="example_param_write_for_sec">1.23</param>
254 <param name="example_param_read_for_sec">3</param>
255 </hardware>
256 <joint name="joint2">
257 <command_interface name="position">
258 <param name="min">-1</param>
259 <param name="max">1</param>
260 </command_interface>
261 <state_interface name="position"/>
262 </joint>
263 </ros2_control>
264)";
265
266// 6. Modular Robots with actuators not providing states and with additional sensors
267// Example for simple transmission
268const auto valid_urdf_ros2_control_actuator_modular_robot_sensors =
269 R"(
270 <ros2_control name="RRBotModularJoint1" type="actuator">
271 <hardware>
272 <plugin>ros2_control_demo_hardware/VelocityActuatorHardware</plugin>
273 <group>Hardware Group 1</group>
274 <param name="example_param_write_for_sec">1.23</param>
275 <param name="example_param_read_for_sec">3</param>
276 </hardware>
277 <joint name="joint1">
278 <command_interface name="velocity">
279 <param name="min">-1</param>
280 <param name="max">1</param>
281 </command_interface>
282 <state_interface name="velocity"/>
283 </joint>
284 <transmission name="transmission1">
285 <plugin>transmission_interface/SimpleTansmission</plugin>
286 <joint name="joint1" role="joint1">
287 <mechanical_reduction>325.949</mechanical_reduction>
288 </joint>
289 </transmission>
290 </ros2_control>
291 <ros2_control name="RRBotModularJoint2" type="actuator">
292 <hardware>
293 <plugin>ros2_control_demo_hardware/VelocityActuatorHardware</plugin>
294 <group>Hardware Group 2</group>
295 <param name="example_param_write_for_sec">1.23</param>
296 <param name="example_param_read_for_sec">3</param>
297 </hardware>
298 <joint name="joint2">
299 <command_interface name="velocity">
300 <param name="min">-1</param>
301 <param name="max">1</param>
302 </command_interface>
303 <state_interface name="velocity"/>
304 </joint>
305 </ros2_control>
306 <ros2_control name="RRBotModularPositionSensorJoint1" type="sensor">
307 <hardware>
308 <plugin>ros2_control_demo_hardware/PositionSensorHardware</plugin>
309 <group>Hardware Group 1</group>
310 <param name="example_param_read_for_sec">2</param>
311 </hardware>
312 <joint name="joint1">
313 <state_interface name="position"/>
314 </joint>
315 </ros2_control>
316 <ros2_control name="RRBotModularPositionSensorJoint2" type="sensor">
317 <hardware>
318 <plugin>ros2_control_demo_hardware/PositionSensorHardware</plugin>
319 <group>Hardware Group 2</group>
320 <param name="example_param_read_for_sec">2</param>
321 </hardware>
322 <joint name="joint2">
323 <state_interface name="position"/>
324 </joint>
325 </ros2_control>
326)";
327
328// 7. Modular Robots with separate communication to each "actuator" with multi joints
329// Example for complex transmission (multi-joint/multi-actuator) - (system component is used)
330const auto valid_urdf_ros2_control_system_multi_joints_transmission =
331 R"(
332 <ros2_control name="RRBotModularWrist" type="system">
333 <hardware>
334 <plugin>ros2_control_demo_hardware/ActuatorHardwareMultiDOF</plugin>
335 <param name="example_param_write_for_sec">1.23</param>
336 <param name="example_param_read_for_sec">3</param>
337 </hardware>
338 <joint name="joint1">
339 <command_interface name="position">
340 <param name="min">-1</param>
341 <param name="max">1</param>
342 </command_interface>
343 <state_interface name="position"/>
344 </joint>
345 <joint name="joint2">
346 <command_interface name="position">
347 <param name="min">-1</param>
348 <param name="max">1</param>
349 </command_interface>
350 <state_interface name="position"/>
351 </joint>
352 <transmission name="transmission1">
353 <plugin>transmission_interface/DifferentialTransmission</plugin>
354 <actuator name="joint1_motor" role="actuator1"/>
355 <actuator name="joint2_motor" role="actuator2"/>
356 <joint name="joint1" role="joint1">
357 <mechanical_reduction>10</mechanical_reduction>
358 <offset>0.5</offset>
359 </joint>
360 <joint name="joint2" role="joint2">
361 <mechanical_reduction>50</mechanical_reduction>
362 </joint>
363 </transmission>
364 </ros2_control>
365)";
366
367// 8. Sensor only
368const auto valid_urdf_ros2_control_sensor_only =
369 R"(
370 <ros2_control name="CameraWithIMU" type="sensor">
371 <hardware>
372 <plugin>ros2_control_demo_hardware/CameraWithIMUSensor</plugin>
373 <param name="example_param_read_for_sec">2</param>
374 </hardware>
375 <sensor name="sensor1">
376 <state_interface name="roll"/>
377 <state_interface name="pitch"/>
378 <state_interface name="yaw"/>
379 </sensor>
380 <sensor name="sensor2">
381 <state_interface name="image"/>
382 </sensor>
383 </ros2_control>
384)";
385
386// 9. Actuator Only
387const auto valid_urdf_ros2_control_actuator_only =
388 R"(
389 <ros2_control name="ActuatorModularJoint1" type="actuator">
390 <hardware>
391 <plugin>ros2_control_demo_hardware/VelocityActuatorHardware</plugin>
392 <param name="example_param_write_for_sec">1.13</param>
393 <param name="example_param_read_for_sec">3</param>
394 </hardware>
395 <joint name="joint1">
396 <command_interface name="velocity">
397 <param name="min">-1</param>
398 <param name="max">1</param>
399 </command_interface>
400 <state_interface name="velocity"/>
401 </joint>
402 <transmission name="transmission1">
403 <plugin>transmission_interface/RotationToLinerTansmission</plugin>
404 <joint name="joint1" role="joint1">
405 <mechanical_reduction>325.949</mechanical_reduction>
406 </joint>
407 <param name="additional_special_parameter">1337</param>
408 </transmission>
409 </ros2_control>
410)";
411
412// 10. Industrial Robots with integrated GPIO
413const auto valid_urdf_ros2_control_system_robot_with_gpio =
414 R"(
415 <ros2_control name="RRBotSystemWithGPIO" type="system">
416 <hardware>
417 <plugin>ros2_control_demo_hardware/RRBotSystemWithGPIOHardware</plugin>
418 <param name="example_param_write_for_sec">2</param>
419 <param name="example_param_read_for_sec">2</param>
420 </hardware>
421 <joint name="joint1">
422 <command_interface name="position">
423 <param name="min">-1</param>
424 <param name="max">1</param>
425 </command_interface>
426 <state_interface name="position"/>
427 </joint>
428 <joint name="joint2">
429 <command_interface name="position">
430 <param name="min">-1</param>
431 <param name="max">1</param>
432 </command_interface>
433 <state_interface name="position"/>
434 </joint>
435 <gpio name="flange_analog_IOs">
436 <command_interface name="analog_output1"/>
437 <state_interface name="analog_output1"/> <!-- Needed to know current state of the output -->
438 <state_interface name="analog_input1"/>
439 <state_interface name="analog_input2"/>
440 </gpio>
441 <gpio name="flange_vacuum">
442 <command_interface name="vacuum"/>
443 <state_interface name="vacuum"> <!-- Needed to know current state of the input -->
444 <param name="initial_value">1.0</param>
445 </state_interface>
446 </gpio>
447 </ros2_control>
448)";
449
450// 11. Industrial Robots using size and data_type attributes
451const auto valid_urdf_ros2_control_system_robot_with_size_and_data_type =
452 R"(
453 <ros2_control name="RRBotSystemWithSizeAndDataType" type="system">
454 <hardware>
455 <plugin>ros2_control_demo_hardware/RRBotSystemWithSizeAndDataType</plugin>
456 <param name="example_param_write_for_sec">2</param>
457 <param name="example_param_read_for_sec">2</param>
458 </hardware>
459 <joint name="joint1">
460 <command_interface name="position"/>
461 <state_interface name="position"/>
462 </joint>
463 <gpio name="flange_IOS">
464 <command_interface name="digital_output" size="2" data_type="bool"/>
465 <state_interface name="analog_input" size="3"/>
466 <state_interface name="image" data_type="cv::Mat"/>
467 </gpio>
468 </ros2_control>
469)";
470
471// 12. Industrial Robots with integrated GPIO with few disabled limits in joints
472const auto valid_urdf_ros2_control_system_robot_with_gpio_and_disabled_interface_limits =
473 R"(
474 <ros2_control name="RRBotSystemWithGPIO" type="system">
475 <hardware>
476 <plugin>ros2_control_demo_hardware/RRBotSystemWithGPIOHardware</plugin>
477 <param name="example_param_write_for_sec">2</param>
478 <param name="example_param_read_for_sec">2</param>
479 </hardware>
480 <joint name="joint1">
481 <command_interface name="position">
482 <limits enable="false"/>
483 <param name="min">-1</param>
484 <param name="max">1</param>
485 </command_interface>
486 <command_interface name="velocity">
487 <param name="min">-0.05</param>
488 <param name="max">0.1</param>
489 </command_interface>
490 <command_interface name="effort">
491 <param name="min">-0.2</param>
492 <param name="max">0.2</param>
493 </command_interface>
494 <command_interface name="acceleration">
495 <param name="min">-0.5</param>
496 <param name="max">0.5</param>
497 </command_interface>
498 <command_interface name="jerk">
499 <param name="max">5.0</param>
500 </command_interface>
501 <state_interface name="position"/>
502 </joint>
503 <joint name="joint2">
504 <limits enable="false"/>
505 <command_interface name="position">
506 <param name="min">-1</param>
507 <param name="max">1</param>
508 </command_interface>
509 <command_interface name="velocity"/>
510 <command_interface name="effort"/>
511 <command_interface name="acceleration">
512 <param name="min">-0.3</param>
513 <param name="max">0.3</param>
514 </command_interface>
515 <command_interface name="jerk">
516 <param name="min">-2.0</param>
517 <param name="max">2.0</param>
518 </command_interface>
519 <state_interface name="position"/>
520 </joint>
521 <joint name="joint3">
522 <command_interface name="acceleration">
523 <param name="max">1.0</param>
524 </command_interface>
525 </joint>
526 <gpio name="flange_IOS">
527 <command_interface name="digital_output" size="2" data_type="bool"/>
528 <state_interface name="analog_input" size="3"/>
529 <state_interface name="image" data_type="cv::Mat"/>
530 </gpio>
531 </ros2_control>
532)";
533const auto valid_urdf_ros2_control_system_robot_with_unavailable_interfaces =
534 R"(
535 <ros2_control name="RRBotSystemWithGPIO" type="system">
536 <hardware>
537 <plugin>ros2_control_demo_hardware/RRBotSystemWithGPIOHardware</plugin>
538 <param name="example_param_write_for_sec">2</param>
539 <param name="example_param_read_for_sec">2</param>
540 </hardware>
541 <joint name="joint1">
542 <command_interface name="position">
543 <limits enable="false"/>
544 <param name="min">-1</param>
545 <param name="max">1</param>
546 </command_interface>
547 <command_interface name="velocity">
548 <param name="min">-0.05</param>
549 <param name="max">0.1</param>
550 </command_interface>
551 <command_interface name="effort">
552 <param name="min">-0.2</param>
553 <param name="max">0.2</param>
554 </command_interface>
555 <command_interface name="acceleration">
556 <param name="min">-0.5</param>
557 <param name="max">0.5</param>
558 </command_interface>
559 <command_interface name="jerk">
560 <param name="max">5.0</param>
561 </command_interface>
562 <state_interface name="position"/>
563 </joint>
564 <joint name="joint2">
565 <limits enable="false"/>
566 <command_interface name="position">
567 <param name="min">-1</param>
568 <param name="max">1</param>
569 </command_interface>
570 <command_interface name="velocity"/>
571 <command_interface name="effort"/>
572 <command_interface name="acceleration">
573 <param name="min">-0.3</param>
574 <param name="max">0.3</param>
575 </command_interface>
576 <command_interface name="jerk"/>
577 <state_interface name="position"/>
578 </joint>
579 <joint name="joint3">
580 <command_interface name="acceleration">
581 <param name="min">1.0</param>
582 </command_interface>
583 <command_interface name="unavailable">
584 <param name="min">-0.3</param>
585 <param name="max">0.3</param>
586 </command_interface>
587 </joint>
588 </ros2_control>
589)";
590const auto valid_urdf_ros2_control_system_robot_with_all_interfaces =
591 R"(
592 <ros2_control name="RRBotSystemWithGPIO" type="system">
593 <hardware>
594 <plugin>ros2_control_demo_hardware/RRBotSystemWithGPIOHardware</plugin>
595 <param name="example_param_write_for_sec">2</param>
596 <param name="example_param_read_for_sec">2</param>
597 </hardware>
598 <joint name="joint1">
599 <command_interface name="position">
600 <param name="min">-1</param>
601 <param name="max">1</param>
602 </command_interface>
603 <command_interface name="velocity">
604 <param name="min">-0.05</param>
605 <param name="max">0.1</param>
606 </command_interface>
607 <command_interface name="effort">
608 <param name="min">-0.2</param>
609 <param name="max">0.2</param>
610 </command_interface>
611 <command_interface name="acceleration">
612 <param name="min">-0.5</param>
613 <param name="max">0.5</param>
614 </command_interface>
615 <command_interface name="jerk">
616 <param name="max">5.0</param>
617 </command_interface>
618 <state_interface name="position"/>
619 </joint>
620 <joint name="joint2">
621 <command_interface name="position"/>
622 <command_interface name="velocity"/>
623 <command_interface name="effort"/>
624 <command_interface name="acceleration"/>
625 <command_interface name="jerk"/>
626 <state_interface name="position"/>
627 </joint>
628 </ros2_control>
629)";
630
631// Voltage Sensor only
632const auto valid_urdf_ros2_control_voltage_sensor_only =
633 R"(
634 <ros2_control name="SingleJointVoltage" type="sensor">
635 <hardware>
636 <plugin>ros2_control_demo_hardware/SingleJointVoltageSensor</plugin>
637 <param name="example_param_read_for_sec">2</param>
638 </hardware>
639 <sensor name="sens1">
640 <state_interface name="voltage" initial_value="0.0"/>
641 </sensor>
642 </ros2_control>
643)";
644
645// Joint+Voltage Sensor
646const auto valid_urdf_ros2_control_joint_voltage_sensor =
647 R"(
648 <ros2_control name="SingleJointVoltage" type="sensor">
649 <hardware>
650 <plugin>ros2_control_demo_hardware/SingleJointVoltageSensor</plugin>
651 <param name="example_param_read_for_sec">2</param>
652 </hardware>
653 <joint name="joint1">
654 <state_interface name="position"/>
655 </joint>
656 <sensor name="sens1">
657 <state_interface name="voltage" initial_value="0.0"/>
658 </sensor>
659 </ros2_control>
660)";
661
662const auto valid_urdf_ros2_control_dummy_actuator_only =
663 R"(
664 <ros2_control name="ActuatorModularJoint1" type="actuator">
665 <hardware>
666 <plugin>ros2_control_demo_hardware/VelocityActuatorHardware</plugin>
667 <param name="example_param_write_for_sec">1.13</param>
668 <param name="example_param_read_for_sec">3</param>
669 </hardware>
670 <joint name="joint1">
671 <command_interface name="velocity">
672 <param name="min">-1</param>
673 <param name="max">1</param>
674 </command_interface>
675 <state_interface name="position"/>
676 <state_interface name="velocity"/>
677 </joint>
678 <transmission name="transmission1">
679 <plugin>transmission_interface/RotationToLinerTansmission</plugin>
680 <joint name="joint1" role="joint1">
681 <mechanical_reduction>325.949</mechanical_reduction>
682 </joint>
683 <param name="additional_special_parameter">1337</param>
684 </transmission>
685 </ros2_control>
686)";
687
688const auto valid_urdf_ros2_control_dummy_system_robot =
689 R"(
690 <ros2_control name="RRBotSystemWithGPIO" type="system">
691 <hardware>
692 <plugin>ros2_control_demo_hardware/RRBotSystemWithGPIOHardware</plugin>
693 <param name="example_param_write_for_sec">2</param>
694 <param name="example_param_read_for_sec">2</param>
695 </hardware>
696 <joint name="joint1">
697 <command_interface name="velocity">
698 <param name="min">-1</param>
699 <param name="max">1</param>
700 </command_interface>
701 <state_interface name="position"/>
702 <state_interface name="velocity"/>
703 </joint>
704 <joint name="joint2">
705 <command_interface name="velocity">
706 <param name="min">-1</param>
707 <param name="max">1</param>
708 </command_interface>
709 <state_interface name="position"/>
710 <state_interface name="velocity"/>
711 </joint>
712 <joint name="joint3">
713 <command_interface name="velocity">
714 <param name="min">-1</param>
715 <param name="max">1</param>
716 </command_interface>
717 <state_interface name="position"/>
718 <state_interface name="velocity"/>
719 </joint>
720 </ros2_control>
721)";
722
723const auto valid_urdf_ros2_control_parameter_empty =
724 R"(
725 <ros2_control name="2DOF_System_Robot_Position_Only" type="system">
726 <hardware>
727 <plugin>ros2_control_demo_hardware/2DOF_System_Hardware_Position_Only</plugin>
728 <param name="example_param_write_for_sec"></param>
729 <param name="example_param_read_for_sec">2</param>
730 </hardware>
731 <joint name="joint1">
732 <command_interface name="position">
733 </command_interface>
734 </joint>
735 </ros2_control>
736)";
737
738const auto valid_urdf_ros2_control_system_robot_with_size_and_data_type_on_joint_sensor_and_gpio =
739 R"(
740 <ros2_control name="RRBotSystemWithSizeAndDataType" type="system">
741 <hardware>
742 <plugin>ros2_control_demo_hardware/RRBotSystemWithSizeAndDataType</plugin>
743 <param name="example_param_write_for_sec">2</param>
744 <param name="example_param_read_for_sec">2</param>
745 </hardware>
746 <joint name="joint1">
747 <command_interface name="position"/>
748 <state_interface name="position"/>
749 <state_interface name="status" data_type="bool"/>
750 <command_interface name="enable" data_type="bool"/>
751 </joint>
752 <sensor name="trigger">
753 <command_interface name="safety" data_type="bool"/>
754 <state_interface name="safety" data_type="bool"/>
755 </sensor>
756 <gpio name="flange_IOS">
757 <command_interface name="digital_output" size="2" data_type="bool"/>
758 <state_interface name="analog_input" size="3"/>
759 <state_interface name="image" data_type="cv::Mat"/>
760 </gpio>
761 </ros2_control>
762)";
763
764// Errors
765const auto invalid_urdf_ros2_control_invalid_child =
766 R"(
767 <ros2_control name="2DOF_System_Robot_Position_Only" type="system">
768 <hardwarert>
769 <plugin>ros2_control_demo_hardware/2DOF_System_Hardware_Position_Only</plugin>
770 <param name="example_param_write_for_sec">2</param>
771 <param name="example_param_read_for_sec">2</param>
772 </hardwarert>
773 </ros2_control>
774 )";
775
776const auto invalid_urdf_ros2_control_missing_attribute =
777 R"(
778 <ros2_control type="system">
779 <hardware>
780 <plugin>ros2_control_demo_hardware/2DOF_System_Hardware_Position_Only</plugin>
781 <param name="example_param_write_for_sec">2</param>
782 <param name="example_param_read_for_sec">2</param>
783 </hardware>
784 </ros2_control>
785 )";
786
787const auto invalid_urdf_ros2_control_component_missing_plugin_name =
788 R"(
789 <ros2_control name="2DOF_System_Robot_Position_Only" type="system">
790 <hardware>
791 <plugin>ros2_control_demo_hardware/2DOF_System_Hardware_Position_Only</plugin>
792 <param name="example_param_write_for_sec">2</param>
793 <param name="example_param_read_for_sec">2</param>
794 </hardware>
795 <joint name="joint1">
796 <param name="min_position_value">-1</param>
797 <param name="max_position_value">1</param>
798 </joint>
799 </ros2_control>
800)";
801
802const auto invalid_urdf_ros2_control_parameter_missing_name =
803 R"(
804 <ros2_control name="2DOF_System_Robot_Position_Only" type="system">
805 <hardware>
806 <plugin>ros2_control_demo_hardware/2DOF_System_Hardware_Position_Only</plugin>
807 <param>2</param>
808 <param name="example_param_read_for_sec">2</param>
809 </hardware>
810 <joint name="joint1">
811 <plugin>ros2_control_components/PositionJoint</plugin>
812 <param name="min_position_value">-1</param>
813 <param name="max_position_value">1</param>
814 </joint>
815 </ros2_control>
816)";
817
818const auto invalid_urdf_ros2_control_component_plugin_name_empty =
819 R"(
820 <ros2_control name="2DOF_System_Robot_Position_Only" type="system">
821 <hardware>
822 <plugin>ros2_control_demo_hardware/2DOF_System_Hardware_Position_Only</plugin>
823 <param name="example_param_write_for_sec">2</param>
824 <param name="example_param_read_for_sec">2</param>
825 </hardware>
826 <joint name="joint1">
827 <plugin></plugin>
828 <param name="min_position_value">-1</param>
829 <param name="max_position_value">1</param>
830 </joint>
831 </ros2_control>
832)";
833
834const auto invalid_urdf_ros2_control_component_interface_type_empty =
835 R"(
836 <ros2_control name="2DOF_System_Robot_Position_Only" type="system">
837 <hardware>
838 <plugin>ros2_control_demo_hardware/2DOF_System_Hardware_Position_Only</plugin>
839 <param name="example_param_write_for_sec">2</param>
840 <param name="example_param_read_for_sec">2</param>
841 </hardware>
842 <joint name="joint1">
843 <plugin>ros2_control_components/PositionJoint</plugin>
844 <state_interface></state_interface>
845 <param name="min_position_value">-1</param>
846 <param name="max_position_value">1</param>
847 </joint>
848 </ros2_control>
849)";
850
851const auto invalid_urdf2_ros2_control_illegal_size =
852 R"(
853 <ros2_control name="RRBotSystemWithIllegalSize" type="system">
854 <hardware>
855 <plugin>ros2_control_demo_hardware/RRBotSystemWithIllegalSize</plugin>
856 </hardware>
857 <gpio name="flange_IOS">
858 <command_interface name="digital_output" data_type="bool" size="-4"/>
859 </gpio>
860 </ros2_control>
861)";
862
863const auto invalid_urdf2_ros2_control_illegal_size2 =
864 R"(
865 <ros2_control name="RRBotSystemWithIllegalSize2" type="system">
866 <hardware>
867 <plugin>ros2_control_demo_hardware/RRBotSystemWithIllegalSize2</plugin>
868 </hardware>
869 <gpio name="flange_IOS">
870 <command_interface name="digital_output" data_type="bool" size="ILLEGAL"/>
871 </gpio>
872 </ros2_control>
873)";
874
875const auto invalid_urdf2_hw_transmission_joint_mismatch =
876 R"(
877 <ros2_control name="ActuatorModularJoint1" type="actuator">
878 <hardware>
879 <plugin>ros2_control_demo_hardware/VelocityActuatorHardware</plugin>
880 </hardware>
881 <joint name="joint1">
882 <command_interface name="velocity">
883 <param name="min">-1</param>
884 <param name="max">1</param>
885 </command_interface>
886 <state_interface name="velocity"/>
887 </joint>
888 <transmission name="transmission1">
889 <plugin>transmission_interface/SimpleTransmission</plugin>
890 <joint name="joint31415" role="joint1"/>
891 </transmission>
892 </ros2_control>
893)";
894
895const auto invalid_urdf2_transmission_given_too_many_joints =
896 R"(
897 <ros2_control name="ActuatorModularJoint1" type="actuator">
898 <hardware>
899 <plugin>ros2_control_demo_hardware/VelocityActuatorHardware</plugin>
900 </hardware>
901 <joint name="joint1">
902 <command_interface name="velocity">
903 <param name="min">-1</param>
904 <param name="max">1</param>
905 </command_interface>
906 <state_interface name="velocity"/>
907 </joint>
908 <transmission name="transmission1">
909 <plugin>transmission_interface/SimpleTransmission</plugin>
910 <joint name="joint1" role="joint1"/>
911 <joint name="joint2" role="joint2"/>
912 </transmission>
913 </ros2_control>
914)";
915
916const auto invalid_urdf_ros2_control_system_with_command_fixed_joint =
917 R"(
918 <ros2_control name="2DOF_System_Robot_Position_Only" type="system">
919 <hardware>
920 <plugin>ros2_control_demo_hardware/2DOF_System_Hardware_Position_Only</plugin>
921 <param name="example_param_write_for_sec">2</param>
922 <param name="example_param_read_for_sec">2</param>
923 </hardware>
924 <joint name="tool_joint">
925 <command_interface name="position">
926 </command_interface>
927 </joint>
928 </ros2_control>
929)";
930
931} // namespace ros2_control_test_assets
932
933#endif // ROS2_CONTROL_TEST_ASSETS__COMPONENTS_URDFS_HPP_