15#ifndef ROS2_CONTROL_TEST_ASSETS__COMPONENTS_URDFS_HPP_
16#define ROS2_CONTROL_TEST_ASSETS__COMPONENTS_URDFS_HPP_
20namespace ros2_control_test_assets
23const auto valid_urdf_ros2_control_system_one_interface =
25 <ros2_control name="RRBotSystemPositionOnly" type="system">
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>
32 <command_interface name="position">
33 <param name="min">-1</param>
34 <param name="max">1</param>
36 <state_interface name="position"/>
39 <command_interface name="position">
40 <param name="min">-1</param>
41 <param name="max">1</param>
43 <state_interface name="position"/>
50const auto valid_urdf_ros2_control_system_multi_interface =
52 <ros2_control name="RRBotSystemMultiInterface" type="system">
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>
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>
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>
69 <command_interface name="effort">
70 <param name="min">-0.5</param>
71 <param name="max">0.5"</param>
73 <state_interface name="position"/>
74 <state_interface name="velocity"/>
75 <state_interface name="effort"/>
78 <command_interface name="position">
79 <param name="min">-1</param>
80 <param name="max">1</param>
82 <state_interface name="position"/>
83 <state_interface name="velocity"/>
84 <state_interface name="effort"/>
90const auto valid_urdf_ros2_control_system_robot_with_sensor =
92 <ros2_control name="RRBotSystemWithSensor" type="system">
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>
99 <command_interface name="position">
100 <param name="min">-1</param>
101 <param name="max">1</param>
103 <state_interface name="position"/>
105 <joint name="joint2">
106 <command_interface name="position">
107 <param name="min">-1</param>
108 <param name="max">1</param>
110 <state_interface name="position"/>
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>
127const auto valid_urdf_ros2_control_system_robot_with_external_sensor =
129 <ros2_control name="RRBotSystemPositionOnlyWithExternalSensor" type="system">
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>
135 <joint name="joint1">
136 <command_interface name="position">
137 <param name="min">-1</param>
138 <param name="max">1</param>
140 <state_interface name="position"/>
142 <joint name="joint2">
143 <command_interface name="position">
144 <param name="min">-1</param>
145 <param name="max">1</param>
147 <state_interface name="position"/>
150 <ros2_control name="RRBotForceTorqueSensor2D" type="sensor">
152 <plugin>ros2_control_demo_hardware/ForceTorqueSensor2DHardware</plugin>
153 <param name="example_param_read_for_sec">0.43</param>
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>
170const auto valid_urdf_ros2_control_actuator_modular_robot =
172 <ros2_control name="RRBotModularJoint1" type="actuator">
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>
178 <joint name="joint1">
179 <command_interface name="position">
180 <param name="min">-1</param>
181 <param name="max">1</param>
183 <state_interface name="position"/>
186 <ros2_control name="RRBotModularJoint2" type="actuator">
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>
192 <joint name="joint2">
193 <command_interface name="position">
194 <param name="min">-1</param>
195 <param name="max">1</param>
197 <state_interface name="position"/>
204const auto valid_urdf_ros2_control_actuator_modular_robot_sensors =
206 <ros2_control name="RRBotModularJoint1" type="actuator">
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>
212 <joint name="joint1">
213 <command_interface name="velocity">
214 <param name="min">-1</param>
215 <param name="max">1</param>
217 <state_interface name="velocity"/>
219 <transmission name="transmission1">
220 <plugin>transmission_interface/SimpleTansmission</plugin>
221 <joint name="joint1" role="joint1">
222 <mechanical_reduction>325.949</mechanical_reduction>
226 <ros2_control name="RRBotModularJoint2" type="actuator">
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>
232 <joint name="joint2">
233 <command_interface name="velocity">
234 <param name="min">-1</param>
235 <param name="max">1</param>
237 <state_interface name="velocity"/>
240 <ros2_control name="RRBotModularPositionSensorJoint1" type="sensor">
242 <plugin>ros2_control_demo_hardware/PositionSensorHardware</plugin>
243 <param name="example_param_read_for_sec">2</param>
245 <joint name="joint1">
246 <state_interface name="position"/>
249 <ros2_control name="RRBotModularPositionSensorJoint2" type="sensor">
251 <plugin>ros2_control_demo_hardware/PositionSensorHardware</plugin>
252 <param name="example_param_read_for_sec">2</param>
254 <joint name="joint2">
255 <state_interface name="position"/>
262const auto valid_urdf_ros2_control_system_multi_joints_transmission =
264 <ros2_control name="RRBotModularWrist" type="system">
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>
270 <joint name="joint1">
271 <command_interface name="position">
272 <param name="min">-1</param>
273 <param name="max">1</param>
275 <state_interface name="position"/>
277 <joint name="joint2">
278 <command_interface name="position">
279 <param name="min">-1</param>
280 <param name="max">1</param>
282 <state_interface name="position"/>
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>
292 <joint name="joint2" role="joint2">
293 <mechanical_reduction>50</mechanical_reduction>
300const auto valid_urdf_ros2_control_sensor_only =
302 <ros2_control name="CameraWithIMU" type="sensor">
304 <plugin>ros2_control_demo_hardware/CameraWithIMUSensor</plugin>
305 <param name="example_param_read_for_sec">2</param>
307 <sensor name="sensor1">
308 <state_interface name="roll"/>
309 <state_interface name="pitch"/>
310 <state_interface name="yaw"/>
312 <sensor name="sensor2">
313 <state_interface name="image"/>
319const auto valid_urdf_ros2_control_actuator_only =
321 <ros2_control name="ActuatorModularJoint1" type="actuator">
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>
327 <joint name="joint1">
328 <command_interface name="velocity">
329 <param name="min">-1</param>
330 <param name="max">1</param>
332 <state_interface name="velocity"/>
334 <transmission name="transmission1">
335 <plugin>transmission_interface/RotationToLinerTansmission</plugin>
336 <joint name="joint1" role="joint1">
337 <mechanical_reduction>325.949</mechanical_reduction>
339 <param name="additional_special_parameter">1337</param>
345const auto valid_urdf_ros2_control_system_robot_with_gpio =
347 <ros2_control name="RRBotSystemWithGPIO" type="system">
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>
353 <joint name="joint1">
354 <command_interface name="position">
355 <param name="min">-1</param>
356 <param name="max">1</param>
358 <state_interface name="position"/>
360 <joint name="joint2">
361 <command_interface name="position">
362 <param name="min">-1</param>
363 <param name="max">1</param>
365 <state_interface name="position"/>
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"/>
373 <gpio name="flange_vacuum">
374 <command_interface name="vacuum"/>
375 <state_interface name="vacuum"/> <!-- Needed to know current state of the input -->
381const auto valid_urdf_ros2_control_system_robot_with_size_and_data_type =
383 <ros2_control name="RRBotSystemWithSizeAndDataType" type="system">
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>
389 <joint name="joint1">
390 <command_interface name="position"/>
391 <state_interface name="position"/>
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"/>
401const auto valid_urdf_ros2_control_parameter_empty =
403 <ros2_control name="2DOF_System_Robot_Position_Only" type="system">
405 <plugin>ros2_control_demo_hardware/2DOF_System_Hardware_Position_Only</plugin>
406 <param name="example_param_write_for_sec"></param>
407 <param name="example_param_read_for_sec">2</param>
409 <joint name="joint1">
410 <command_interface name="position">
417const auto invalid_urdf_ros2_control_invalid_child =
419 <ros2_control name="2DOF_System_Robot_Position_Only" type="system">
421 <plugin>ros2_control_demo_hardware/2DOF_System_Hardware_Position_Only</plugin>
422 <param name="example_param_write_for_sec">2</param>
423 <param name="example_param_read_for_sec">2</param>
428const auto invalid_urdf_ros2_control_missing_attribute =
430 <ros2_control type="system">
432 <plugin>ros2_control_demo_hardware/2DOF_System_Hardware_Position_Only</plugin>
433 <param name="example_param_write_for_sec">2</param>
434 <param name="example_param_read_for_sec">2</param>
439const auto invalid_urdf_ros2_control_component_missing_class_type =
441 <ros2_control name="2DOF_System_Robot_Position_Only" type="system">
443 <plugin>ros2_control_demo_hardware/2DOF_System_Hardware_Position_Only</plugin>
444 <param name="example_param_write_for_sec">2</param>
445 <param name="example_param_read_for_sec">2</param>
447 <joint name="joint1">
448 <param name="min_position_value">-1</param>
449 <param name="max_position_value">1</param>
454const auto invalid_urdf_ros2_control_parameter_missing_name =
456 <ros2_control name="2DOF_System_Robot_Position_Only" type="system">
458 <plugin>ros2_control_demo_hardware/2DOF_System_Hardware_Position_Only</plugin>
460 <param name="example_param_read_for_sec">2</param>
462 <joint name="joint1">
463 <plugin>ros2_control_components/PositionJoint</plugin>
464 <param name="min_position_value">-1</param>
465 <param name="max_position_value">1</param>
470const auto invalid_urdf_ros2_control_component_class_type_empty =
472 <ros2_control name="2DOF_System_Robot_Position_Only" type="system">
474 <plugin>ros2_control_demo_hardware/2DOF_System_Hardware_Position_Only</plugin>
475 <param name="example_param_write_for_sec">2</param>
476 <param name="example_param_read_for_sec">2</param>
478 <joint name="joint1">
480 <param name="min_position_value">-1</param>
481 <param name="max_position_value">1</param>
486const auto invalid_urdf_ros2_control_component_interface_type_empty =
488 <ros2_control name="2DOF_System_Robot_Position_Only" type="system">
490 <plugin>ros2_control_demo_hardware/2DOF_System_Hardware_Position_Only</plugin>
491 <param name="example_param_write_for_sec">2</param>
492 <param name="example_param_read_for_sec">2</param>
494 <joint name="joint1">
495 <plugin>ros2_control_components/PositionJoint</plugin>
496 <state_interface></state_interface>
497 <param name="min_position_value">-1</param>
498 <param name="max_position_value">1</param>
503const auto invalid_urdf2_ros2_control_illegal_size =
505 <ros2_control name="RRBotSystemWithIllegalSize" type="system">
507 <plugin>ros2_control_demo_hardware/RRBotSystemWithIllegalSize</plugin>
509 <gpio name="flange_IOS">
510 <command_interface name="digital_output" data_type="bool" size="-4"/>
515const auto invalid_urdf2_ros2_control_illegal_size2 =
517 <ros2_control name="RRBotSystemWithIllegalSize2" type="system">
519 <plugin>ros2_control_demo_hardware/RRBotSystemWithIllegalSize2</plugin>
521 <gpio name="flange_IOS">
522 <command_interface name="digital_output" data_type="bool" size="ILLEGAL"/>
527const auto invalid_urdf2_hw_transmission_joint_mismatch =
529 <ros2_control name="ActuatorModularJoint1" type="actuator">
531 <plugin>ros2_control_demo_hardware/VelocityActuatorHardware</plugin>
533 <joint name="joint1">
534 <command_interface name="velocity">
535 <param name="min">-1</param>
536 <param name="max">1</param>
538 <state_interface name="velocity"/>
540 <transmission name="transmission1">
541 <plugin>transmission_interface/SimpleTransmission</plugin>
542 <joint name="joint31415" role="joint1"/>
547const auto invalid_urdf2_transmission_given_too_many_joints =
549 <ros2_control name="ActuatorModularJoint1" type="actuator">
551 <plugin>ros2_control_demo_hardware/VelocityActuatorHardware</plugin>
553 <joint name="joint1">
554 <command_interface name="velocity">
555 <param name="min">-1</param>
556 <param name="max">1</param>
558 <state_interface name="velocity"/>
560 <transmission name="transmission1">
561 <plugin>transmission_interface/SimpleTransmission</plugin>
562 <joint name="joint1" role="joint1"/>
563 <joint name="joint2" role="joint2"/>