ros2_control - galactic
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 </command_interface>
63 <command_interface name="velocity">
64 <param name="min">-1</param>
65 <param name="max">1</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// 3. Industrial Robots with integrated sensor
88const auto valid_urdf_ros2_control_system_robot_with_sensor =
89 R"(
90 <ros2_control name="RRBotSystemWithSensor" type="system">
91 <hardware>
92 <plugin>ros2_control_demo_hardware/RRBotSystemWithSensorHardware</plugin>
93 <param name="example_param_write_for_sec">2</param>
94 <param name="example_param_read_for_sec">2</param>
95 </hardware>
96 <joint name="joint1">
97 <command_interface name="position">
98 <param name="min">-1</param>
99 <param name="max">1</param>
100 </command_interface>
101 <state_interface name="position"/>
102 </joint>
103 <joint name="joint2">
104 <command_interface name="position">
105 <param name="min">-1</param>
106 <param name="max">1</param>
107 </command_interface>
108 <state_interface name="position"/>
109 </joint>
110 <sensor name="tcp_fts_sensor">
111 <state_interface name="fx"/>
112 <state_interface name="fy"/>
113 <state_interface name="fz"/>
114 <state_interface name="tx"/>
115 <state_interface name="ty"/>
116 <state_interface name="tz"/>
117 <param name="frame_id">kuka_tcp</param>
118 <param name="lower_limits">-100</param>
119 <param name="upper_limits">100</param>
120 </sensor>
121 </ros2_control>
122)";
123
124// 4. Industrial Robots with externally connected sensor
125const auto valid_urdf_ros2_control_system_robot_with_external_sensor =
126 R"(
127 <ros2_control name="RRBotSystemPositionOnlyWithExternalSensor" type="system">
128 <hardware>
129 <plugin>ros2_control_demo_hardware/RRBotSystemPositionOnlyHardware</plugin>
130 <param name="example_param_write_for_sec">2</param>
131 <param name="example_param_read_for_sec">2</param>
132 </hardware>
133 <joint name="joint1">
134 <command_interface name="position">
135 <param name="min">-1</param>
136 <param name="max">1</param>
137 </command_interface>
138 <state_interface name="position"/>
139 </joint>
140 <joint name="joint2">
141 <command_interface name="position">
142 <param name="min">-1</param>
143 <param name="max">1</param>
144 </command_interface>
145 <state_interface name="position"/>
146 </joint>
147 </ros2_control>
148 <ros2_control name="RRBotForceTorqueSensor2D" type="sensor">
149 <hardware>
150 <plugin>ros2_control_demo_hardware/ForceTorqueSensor2DHardware</plugin>
151 <param name="example_param_read_for_sec">0.43</param>
152 </hardware>
153 <sensor name="tcp_fts_sensor">
154 <state_interface name="fx"/>
155 <state_interface name="fy"/>
156 <state_interface name="fz"/>
157 <state_interface name="tx"/>
158 <state_interface name="ty"/>
159 <state_interface name="tz"/>
160 <param name="frame_id">kuka_tcp</param>
161 <param name="lower_limits">-100</param>
162 <param name="upper_limits">100</param>
163 </sensor>
164 </ros2_control>
165)";
166
167// 5. Modular Robots with separate communication to each actuator
168const auto valid_urdf_ros2_control_actuator_modular_robot =
169 R"(
170 <ros2_control name="RRBotModularJoint1" type="actuator">
171 <hardware>
172 <plugin>ros2_control_demo_hardware/PositionActuatorHardware</plugin>
173 <param name="example_param_write_for_sec">1.23</param>
174 <param name="example_param_read_for_sec">3</param>
175 </hardware>
176 <joint name="joint1">
177 <command_interface name="position">
178 <param name="min">-1</param>
179 <param name="max">1</param>
180 </command_interface>
181 <state_interface name="position"/>
182 </joint>
183 </ros2_control>
184 <ros2_control name="RRBotModularJoint2" type="actuator">
185 <hardware>
186 <plugin>ros2_control_demo_hardware/PositionActuatorHardware</plugin>
187 <param name="example_param_write_for_sec">1.23</param>
188 <param name="example_param_read_for_sec">3</param>
189 </hardware>
190 <joint name="joint2">
191 <command_interface name="position">
192 <param name="min">-1</param>
193 <param name="max">1</param>
194 </command_interface>
195 <state_interface name="position"/>
196 </joint>
197 </ros2_control>
198)";
199
200// 6. Modular Robots with actuators not providing states and with additional sensors
201// Example for simple transmission
202const auto valid_urdf_ros2_control_actuator_modular_robot_sensors =
203 R"(
204 <ros2_control name="RRBotModularJoint1" type="actuator">
205 <hardware>
206 <plugin>ros2_control_demo_hardware/VelocityActuatorHardware</plugin>
207 <param name="example_param_write_for_sec">1.23</param>
208 <param name="example_param_read_for_sec">3</param>
209 </hardware>
210 <joint name="joint1">
211 <command_interface name="velocity">
212 <param name="min">-1</param>
213 <param name="max">1</param>
214 </command_interface>
215 <state_interface name="velocity"/>
216 </joint>
217 <transmission name="transmission1">
218 <plugin>transmission_interface/SimpleTansmission</plugin>
219 <joint name="joint1" role="joint1">
220 <mechanical_reduction>325.949</mechanical_reduction>
221 </joint>
222 </transmission>
223 </ros2_control>
224 <ros2_control name="RRBotModularJoint2" type="actuator">
225 <hardware>
226 <plugin>ros2_control_demo_hardware/VelocityActuatorHardware</plugin>
227 <param name="example_param_write_for_sec">1.23</param>
228 <param name="example_param_read_for_sec">3</param>
229 </hardware>
230 <joint name="joint2">
231 <command_interface name="velocity">
232 <param name="min">-1</param>
233 <param name="max">1</param>
234 </command_interface>
235 <state_interface name="velocity"/>
236 </joint>
237 </ros2_control>
238 <ros2_control name="RRBotModularPositionSensorJoint1" type="sensor">
239 <hardware>
240 <plugin>ros2_control_demo_hardware/PositionSensorHardware</plugin>
241 <param name="example_param_read_for_sec">2</param>
242 </hardware>
243 <joint name="joint1">
244 <state_interface name="position"/>
245 </joint>
246 </ros2_control>
247 <ros2_control name="RRBotModularPositionSensorJoint2" type="sensor">
248 <hardware>
249 <plugin>ros2_control_demo_hardware/PositionSensorHardware</plugin>
250 <param name="example_param_read_for_sec">2</param>
251 </hardware>
252 <joint name="joint2">
253 <state_interface name="position"/>
254 </joint>
255 </ros2_control>
256)";
257
258// 7. Modular Robots with separate communication to each "actuator" with multi joints
259// Example for complex transmission (multi-joint/multi-actuator) - (system component is used)
260const auto valid_urdf_ros2_control_system_multi_joints_transmission =
261 R"(
262 <ros2_control name="RRBotModularWrist" type="system">
263 <hardware>
264 <plugin>ros2_control_demo_hardware/ActuatorHardwareMultiDOF</plugin>
265 <param name="example_param_write_for_sec">1.23</param>
266 <param name="example_param_read_for_sec">3</param>
267 </hardware>
268 <joint name="joint1">
269 <command_interface name="position">
270 <param name="min">-1</param>
271 <param name="max">1</param>
272 </command_interface>
273 <state_interface name="position"/>
274 </joint>
275 <joint name="joint2">
276 <command_interface name="position">
277 <param name="min">-1</param>
278 <param name="max">1</param>
279 </command_interface>
280 <state_interface name="position"/>
281 </joint>
282 <transmission name="transmission1">
283 <plugin>transmission_interface/DifferentialTransmission</plugin>
284 <actuator name="joint1_motor" role="actuator1"/>
285 <actuator name="joint2_motor" role="actuator2"/>
286 <joint name="joint1" role="joint1">
287 <mechanical_reduction>10</mechanical_reduction>
288 <offset>0.5</offset>
289 </joint>
290 <joint name="joint2" role="joint2">
291 <mechanical_reduction>50</mechanical_reduction>
292 </joint>
293 </transmission>
294 </ros2_control>
295)";
296
297// 8. Sensor only
298const auto valid_urdf_ros2_control_sensor_only =
299 R"(
300 <ros2_control name="CameraWithIMU" type="sensor">
301 <hardware>
302 <plugin>ros2_control_demo_hardware/CameraWithIMUSensor</plugin>
303 <param name="example_param_read_for_sec">2</param>
304 </hardware>
305 <sensor name="sensor1">
306 <state_interface name="roll"/>
307 <state_interface name="pitch"/>
308 <state_interface name="yaw"/>
309 </sensor>
310 <sensor name="sensor2">
311 <state_interface name="image"/>
312 </sensor>
313 </ros2_control>
314)";
315
316// 9. Actuator Only
317const auto valid_urdf_ros2_control_actuator_only =
318 R"(
319 <ros2_control name="ActuatorModularJoint1" type="actuator">
320 <hardware>
321 <plugin>ros2_control_demo_hardware/VelocityActuatorHardware</plugin>
322 <param name="example_param_write_for_sec">1.13</param>
323 <param name="example_param_read_for_sec">3</param>
324 </hardware>
325 <joint name="joint1">
326 <command_interface name="velocity">
327 <param name="min">-1</param>
328 <param name="max">1</param>
329 </command_interface>
330 <state_interface name="velocity"/>
331 </joint>
332 <transmission name="transmission1">
333 <plugin>transmission_interface/RotationToLinerTansmission</plugin>
334 <joint name="joint1" role="joint1">
335 <mechanical_reduction>325.949</mechanical_reduction>
336 </joint>
337 <param name="additional_special_parameter">1337</param>
338 </transmission>
339 </ros2_control>
340)";
341
342// 10. Industrial Robots with integrated GPIO
343const auto valid_urdf_ros2_control_system_robot_with_gpio =
344 R"(
345 <ros2_control name="RRBotSystemWithGPIO" type="system">
346 <hardware>
347 <plugin>ros2_control_demo_hardware/RRBotSystemWithGPIOHardware</plugin>
348 <param name="example_param_write_for_sec">2</param>
349 <param name="example_param_read_for_sec">2</param>
350 </hardware>
351 <joint name="joint1">
352 <command_interface name="position">
353 <param name="min">-1</param>
354 <param name="max">1</param>
355 </command_interface>
356 <state_interface name="position"/>
357 </joint>
358 <joint name="joint2">
359 <command_interface name="position">
360 <param name="min">-1</param>
361 <param name="max">1</param>
362 </command_interface>
363 <state_interface name="position"/>
364 </joint>
365 <gpio name="flange_analog_IOs">
366 <command_interface name="analog_output1"/>
367 <state_interface name="analog_output1"/> <!-- Needed to know current state of the output -->
368 <state_interface name="analog_input1"/>
369 <state_interface name="analog_input2"/>
370 </gpio>
371 <gpio name="flange_vacuum">
372 <command_interface name="vacuum"/>
373 <state_interface name="vacuum"/> <!-- Needed to know current state of the input -->
374 </gpio>
375 </ros2_control>
376)";
377
378// 11. Industrial Robots using size and data_type attributes
379const auto valid_urdf_ros2_control_system_robot_with_size_and_data_type =
380 R"(
381 <ros2_control name="RRBotSystemWithSizeAndDataType" type="system">
382 <hardware>
383 <plugin>ros2_control_demo_hardware/RRBotSystemWithSizeAndDataType</plugin>
384 <param name="example_param_write_for_sec">2</param>
385 <param name="example_param_read_for_sec">2</param>
386 </hardware>
387 <joint name="joint1">
388 <command_interface name="position"/>
389 <state_interface name="position"/>
390 </joint>
391 <gpio name="flange_IOS">
392 <command_interface name="digital_output" size="2" data_type="bool"/>
393 <state_interface name="analog_input" size="3"/>
394 <state_interface name="image" data_type="cv::Mat"/>
395 </gpio>
396 </ros2_control>
397)";
398
399// Errors
400const auto invalid_urdf_ros2_control_invalid_child =
401 R"(
402 <ros2_control name="2DOF_System_Robot_Position_Only" type="system">
403 <hardwarert>
404 <plugin>ros2_control_demo_hardware/2DOF_System_Hardware_Position_Only</plugin>
405 <param name="example_param_write_for_sec">2</param>
406 <param name="example_param_read_for_sec">2</param>
407 </hardwarert>
408 </ros2_control>
409 )";
410
411const auto invalid_urdf_ros2_control_missing_attribute =
412 R"(
413 <ros2_control type="system">
414 <hardware>
415 <plugin>ros2_control_demo_hardware/2DOF_System_Hardware_Position_Only</plugin>
416 <param name="example_param_write_for_sec">2</param>
417 <param name="example_param_read_for_sec">2</param>
418 </hardware>
419 </ros2_control>
420 )";
421
422const auto invalid_urdf_ros2_control_component_missing_class_type =
423 R"(
424 <ros2_control name="2DOF_System_Robot_Position_Only" type="system">
425 <hardware>
426 <plugin>ros2_control_demo_hardware/2DOF_System_Hardware_Position_Only</plugin>
427 <param name="example_param_write_for_sec">2</param>
428 <param name="example_param_read_for_sec">2</param>
429 </hardware>
430 <joint name="joint1">
431 <param name="min_position_value">-1</param>
432 <param name="max_position_value">1</param>
433 </joint>
434 </ros2_control>
435)";
436
437const auto invalid_urdf_ros2_control_parameter_missing_name =
438 R"(
439 <ros2_control name="2DOF_System_Robot_Position_Only" type="system">
440 <hardware>
441 <plugin>ros2_control_demo_hardware/2DOF_System_Hardware_Position_Only</plugin>
442 <param>2</param>
443 <param name="example_param_read_for_sec">2</param>
444 </hardware>
445 <joint name="joint1">
446 <plugin>ros2_control_components/PositionJoint</plugin>
447 <param name="min_position_value">-1</param>
448 <param name="max_position_value">1</param>
449 </joint>
450 </ros2_control>
451)";
452
453const auto invalid_urdf_ros2_control_component_class_type_empty =
454 R"(
455 <ros2_control name="2DOF_System_Robot_Position_Only" type="system">
456 <hardware>
457 <plugin>ros2_control_demo_hardware/2DOF_System_Hardware_Position_Only</plugin>
458 <param name="example_param_write_for_sec">2</param>
459 <param name="example_param_read_for_sec">2</param>
460 </hardware>
461 <joint name="joint1">
462 <plugin></plugin>
463 <param name="min_position_value">-1</param>
464 <param name="max_position_value">1</param>
465 </joint>
466 </ros2_control>
467)";
468
469const auto invalid_urdf_ros2_control_component_interface_type_empty =
470 R"(
471 <ros2_control name="2DOF_System_Robot_Position_Only" type="system">
472 <hardware>
473 <plugin>ros2_control_demo_hardware/2DOF_System_Hardware_Position_Only</plugin>
474 <param name="example_param_write_for_sec">2</param>
475 <param name="example_param_read_for_sec">2</param>
476 </hardware>
477 <joint name="joint1">
478 <plugin>ros2_control_components/PositionJoint</plugin>
479 <state_interface></state_interface>
480 <param name="min_position_value">-1</param>
481 <param name="max_position_value">1</param>
482 </joint>
483 </ros2_control>
484)";
485
486const auto invalid_urdf_ros2_control_parameter_empty =
487 R"(
488 <ros2_control name="2DOF_System_Robot_Position_Only" type="system">
489 <hardware>
490 <plugin>ros2_control_demo_hardware/2DOF_System_Hardware_Position_Only</plugin>
491 <param name="example_param_write_for_sec"></param>
492 <param name="example_param_read_for_sec">2</param>
493 </hardware>
494 <joint name="joint1">
495 <command_interface name="position">
496 <param name="min_position_value">-1</param>
497 <param name="max_position_value">1</param>
498 </command_interface>
499 </joint>
500 </ros2_control>
501)";
502
503const auto invalid_urdf2_ros2_control_illegal_size =
504 R"(
505 <ros2_control name="RRBotSystemWithIllegalSize" type="system">
506 <hardware>
507 <plugin>ros2_control_demo_hardware/RRBotSystemWithIllegalSize</plugin>
508 </hardware>
509 <gpio name="flange_IOS">
510 <command_interface name="digital_output" data_type="bool" size="-4"/>
511 </gpio>
512 </ros2_control>
513)";
514
515const auto invalid_urdf2_ros2_control_illegal_size2 =
516 R"(
517 <ros2_control name="RRBotSystemWithIllegalSize2" type="system">
518 <hardware>
519 <plugin>ros2_control_demo_hardware/RRBotSystemWithIllegalSize2</plugin>
520 </hardware>
521 <gpio name="flange_IOS">
522 <command_interface name="digital_output" data_type="bool" size="ILLEGAL"/>
523 </gpio>
524 </ros2_control>
525)";
526
527const auto invalid_urdf2_hw_transmission_joint_mismatch =
528 R"(
529 <ros2_control name="ActuatorModularJoint1" type="actuator">
530 <hardware>
531 <plugin>ros2_control_demo_hardware/VelocityActuatorHardware</plugin>
532 </hardware>
533 <joint name="joint1">
534 <command_interface name="velocity">
535 <param name="min">-1</param>
536 <param name="max">1</param>
537 </command_interface>
538 <state_interface name="velocity"/>
539 </joint>
540 <transmission name="transmission1">
541 <plugin>transmission_interface/SimpleTransmission</plugin>
542 <joint name="joint31415" role="joint1"/>
543 </transmission>
544 </ros2_control>
545)";
546
547const auto invalid_urdf2_transmission_given_too_many_joints =
548 R"(
549 <ros2_control name="ActuatorModularJoint1" type="actuator">
550 <hardware>
551 <plugin>ros2_control_demo_hardware/VelocityActuatorHardware</plugin>
552 </hardware>
553 <joint name="joint1">
554 <command_interface name="velocity">
555 <param name="min">-1</param>
556 <param name="max">1</param>
557 </command_interface>
558 <state_interface name="velocity"/>
559 </joint>
560 <transmission name="transmission1">
561 <plugin>transmission_interface/SimpleTransmission</plugin>
562 <joint name="joint1" role="joint1"/>
563 <joint name="joint2" role="joint2"/>
564 </transmission>
565 </ros2_control>
566)";
567
568} // namespace ros2_control_test_assets
569
570#endif // ROS2_CONTROL_TEST_ASSETS__COMPONENTS_URDFS_HPP_