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>
63 <command_interface name="velocity">
64 <param name="min">-1</param>
65 <param name="max">1</param>
67 <command_interface name="effort">
68 <param name="min">-0.5</param>
69 <param name="max">0.5"</param>
71 <state_interface name="position"/>
72 <state_interface name="velocity"/>
73 <state_interface name="effort"/>
76 <command_interface name="position">
77 <param name="min">-1</param>
78 <param name="max">1</param>
80 <state_interface name="position"/>
81 <state_interface name="velocity"/>
82 <state_interface name="effort"/>
88const auto valid_urdf_ros2_control_system_robot_with_sensor =
90 <ros2_control name="RRBotSystemWithSensor" type="system">
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>
97 <command_interface name="position">
98 <param name="min">-1</param>
99 <param name="max">1</param>
101 <state_interface name="position"/>
103 <joint name="joint2">
104 <command_interface name="position">
105 <param name="min">-1</param>
106 <param name="max">1</param>
108 <state_interface name="position"/>
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>
125const auto valid_urdf_ros2_control_system_robot_with_external_sensor =
127 <ros2_control name="RRBotSystemPositionOnlyWithExternalSensor" type="system">
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>
133 <joint name="joint1">
134 <command_interface name="position">
135 <param name="min">-1</param>
136 <param name="max">1</param>
138 <state_interface name="position"/>
140 <joint name="joint2">
141 <command_interface name="position">
142 <param name="min">-1</param>
143 <param name="max">1</param>
145 <state_interface name="position"/>
148 <ros2_control name="RRBotForceTorqueSensor2D" type="sensor">
150 <plugin>ros2_control_demo_hardware/ForceTorqueSensor2DHardware</plugin>
151 <param name="example_param_read_for_sec">0.43</param>
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>
168const auto valid_urdf_ros2_control_actuator_modular_robot =
170 <ros2_control name="RRBotModularJoint1" type="actuator">
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>
176 <joint name="joint1">
177 <command_interface name="position">
178 <param name="min">-1</param>
179 <param name="max">1</param>
181 <state_interface name="position"/>
184 <ros2_control name="RRBotModularJoint2" type="actuator">
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>
190 <joint name="joint2">
191 <command_interface name="position">
192 <param name="min">-1</param>
193 <param name="max">1</param>
195 <state_interface name="position"/>
202const auto valid_urdf_ros2_control_actuator_modular_robot_sensors =
204 <ros2_control name="RRBotModularJoint1" type="actuator">
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>
210 <joint name="joint1">
211 <command_interface name="velocity">
212 <param name="min">-1</param>
213 <param name="max">1</param>
215 <state_interface name="velocity"/>
217 <transmission name="transmission1">
218 <plugin>transmission_interface/SimpleTansmission</plugin>
219 <joint name="joint1" role="joint1">
220 <mechanical_reduction>325.949</mechanical_reduction>
224 <ros2_control name="RRBotModularJoint2" type="actuator">
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>
230 <joint name="joint2">
231 <command_interface name="velocity">
232 <param name="min">-1</param>
233 <param name="max">1</param>
235 <state_interface name="velocity"/>
238 <ros2_control name="RRBotModularPositionSensorJoint1" type="sensor">
240 <plugin>ros2_control_demo_hardware/PositionSensorHardware</plugin>
241 <param name="example_param_read_for_sec">2</param>
243 <joint name="joint1">
244 <state_interface name="position"/>
247 <ros2_control name="RRBotModularPositionSensorJoint2" type="sensor">
249 <plugin>ros2_control_demo_hardware/PositionSensorHardware</plugin>
250 <param name="example_param_read_for_sec">2</param>
252 <joint name="joint2">
253 <state_interface name="position"/>
260const auto valid_urdf_ros2_control_system_multi_joints_transmission =
262 <ros2_control name="RRBotModularWrist" type="system">
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>
268 <joint name="joint1">
269 <command_interface name="position">
270 <param name="min">-1</param>
271 <param name="max">1</param>
273 <state_interface name="position"/>
275 <joint name="joint2">
276 <command_interface name="position">
277 <param name="min">-1</param>
278 <param name="max">1</param>
280 <state_interface name="position"/>
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>
290 <joint name="joint2" role="joint2">
291 <mechanical_reduction>50</mechanical_reduction>
298const auto valid_urdf_ros2_control_sensor_only =
300 <ros2_control name="CameraWithIMU" type="sensor">
302 <plugin>ros2_control_demo_hardware/CameraWithIMUSensor</plugin>
303 <param name="example_param_read_for_sec">2</param>
305 <sensor name="sensor1">
306 <state_interface name="roll"/>
307 <state_interface name="pitch"/>
308 <state_interface name="yaw"/>
310 <sensor name="sensor2">
311 <state_interface name="image"/>
317const auto valid_urdf_ros2_control_actuator_only =
319 <ros2_control name="ActuatorModularJoint1" type="actuator">
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>
325 <joint name="joint1">
326 <command_interface name="velocity">
327 <param name="min">-1</param>
328 <param name="max">1</param>
330 <state_interface name="velocity"/>
332 <transmission name="transmission1">
333 <plugin>transmission_interface/RotationToLinerTansmission</plugin>
334 <joint name="joint1" role="joint1">
335 <mechanical_reduction>325.949</mechanical_reduction>
337 <param name="additional_special_parameter">1337</param>
343const auto valid_urdf_ros2_control_system_robot_with_gpio =
345 <ros2_control name="RRBotSystemWithGPIO" type="system">
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>
351 <joint name="joint1">
352 <command_interface name="position">
353 <param name="min">-1</param>
354 <param name="max">1</param>
356 <state_interface name="position"/>
358 <joint name="joint2">
359 <command_interface name="position">
360 <param name="min">-1</param>
361 <param name="max">1</param>
363 <state_interface name="position"/>
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"/>
371 <gpio name="flange_vacuum">
372 <command_interface name="vacuum"/>
373 <state_interface name="vacuum"/> <!-- Needed to know current state of the input -->
379const auto valid_urdf_ros2_control_system_robot_with_size_and_data_type =
381 <ros2_control name="RRBotSystemWithSizeAndDataType" type="system">
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>
387 <joint name="joint1">
388 <command_interface name="position"/>
389 <state_interface name="position"/>
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"/>
400const auto invalid_urdf_ros2_control_invalid_child =
402 <ros2_control name="2DOF_System_Robot_Position_Only" type="system">
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>
411const auto invalid_urdf_ros2_control_missing_attribute =
413 <ros2_control type="system">
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>
422const auto invalid_urdf_ros2_control_component_missing_class_type =
424 <ros2_control name="2DOF_System_Robot_Position_Only" type="system">
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>
430 <joint name="joint1">
431 <param name="min_position_value">-1</param>
432 <param name="max_position_value">1</param>
437const auto invalid_urdf_ros2_control_parameter_missing_name =
439 <ros2_control name="2DOF_System_Robot_Position_Only" type="system">
441 <plugin>ros2_control_demo_hardware/2DOF_System_Hardware_Position_Only</plugin>
443 <param name="example_param_read_for_sec">2</param>
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>
453const auto invalid_urdf_ros2_control_component_class_type_empty =
455 <ros2_control name="2DOF_System_Robot_Position_Only" type="system">
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>
461 <joint name="joint1">
463 <param name="min_position_value">-1</param>
464 <param name="max_position_value">1</param>
469const auto invalid_urdf_ros2_control_component_interface_type_empty =
471 <ros2_control name="2DOF_System_Robot_Position_Only" type="system">
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>
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>
486const auto invalid_urdf_ros2_control_parameter_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"></param>
492 <param name="example_param_read_for_sec">2</param>
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>
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"/>