15#ifndef ROS2_CONTROL_TEST_ASSETS__DESCRIPTIONS_HPP_
16#define ROS2_CONTROL_TEST_ASSETS__DESCRIPTIONS_HPP_
21namespace ros2_control_test_assets
25<?xml version="1.0" encoding="utf-8"?>
26<!-- =================================================================================== -->
27<!-- | This document was autogenerated by xacro from minimal_robot.urdf.xacro | -->
28<!-- | EDITING THIS FILE BY HAND IS NOT RECOMMENDED | -->
29<!-- =================================================================================== -->
30<robot name="MinimalRobot">
31 <!-- Used for fixing robot -->
33 <joint name="base_joint" type="fixed">
34 <origin rpy="0 0 0" xyz="0 0 0"/>
35 <parent link="world"/>
36 <child link="base_link"/>
38 <link name="base_link">
42 <inertia ixx="0.001" ixy="0.0" ixz="0.0" iyy="0.001" iyz="0.0" izz="0.001"/>
45 <origin rpy="0 0 0" xyz="0 0 0"/>
47 <cylinder length="0.2" radius="0.1"/>
49 <material name="DarkGrey">
50 <color rgba="0.4 0.4 0.4 1.0"/>
54 <origin rpy="0 0 0" xyz="0 0 0"/>
56 <cylinder length="1" radius="0.1"/>
60 <joint name="joint1" type="revolute">
61 <origin rpy="-1.57079632679 0 0" xyz="0 0 0.2"/>
62 <parent link="base_link"/>
64 <limit effort="0.1" lower="-3.14159265359" upper="3.14159265359" velocity="0.2"/>
70 <inertia ixx="0.001" ixy="0.0" ixz="0.0" iyy="0.001" iyz="0.0" izz="0.001"/>
73 <origin rpy="0 0 0" xyz="0 0 0"/>
75 <cylinder length="1" radius="0.1"/>
77 <material name="DarkGrey">
78 <color rgba="0.4 0.4 0.4 1.0"/>
82 <origin rpy="0 0 0" xyz="0 0 0"/>
84 <cylinder length="1" radius="0.1"/>
88 <joint name="joint2" type="revolute">
89 <origin rpy="1.57079632679 0 0" xyz="0 0 0.9"/>
90 <parent link="link1"/>
92 <limit effort="0.1" lower="-3.14159265359" upper="3.14159265359" velocity="0.2"/>
98 <inertia ixx="0.001" ixy="0.0" ixz="0.0" iyy="0.001" iyz="0.0" izz="0.001"/>
101 <origin rpy="0 0 0" xyz="0 0 0"/>
103 <cylinder length="1" radius="0.1"/>
105 <material name="DarkGrey">
106 <color rgba="0.4 0.4 0.4 1.0"/>
110 <origin rpy="0 0 0" xyz="0 0 0"/>
112 <cylinder length="1" radius="0.1"/>
116 <joint name="tool_joint" type="fixed">
117 <origin rpy="0 0 0" xyz="0 0 1"/>
118 <parent link="link2"/>
119 <child link="tool_link"/>
121 <link name="tool_link">
125const auto urdf_tail =
130const auto hardware_resources =
132 <ros2_control name="TestActuatorHardware" type="actuator">
134 <plugin>test_actuator</plugin>
136 <joint name="joint1">
137 <command_interface name="position"/>
138 <state_interface name="position"/>
139 <state_interface name="velocity"/>
140 <command_interface name="max_velocity" />
143 <ros2_control name="TestSensorHardware" type="sensor">
145 <plugin>test_sensor</plugin>
146 <param name="example_param_write_for_sec">2</param>
147 <param name="example_param_read_for_sec">2</param>
149 <sensor name="sensor1">
150 <state_interface name="velocity"/>
153 <ros2_control name="TestSystemHardware" type="system">
155 <plugin>test_system</plugin>
156 <param name="example_param_write_for_sec">2</param>
157 <param name="example_param_read_for_sec">2</param>
159 <joint name="joint2">
160 <command_interface name="velocity"/>
161 <state_interface name="position"/>
162 <state_interface name="velocity"/>
163 <state_interface name="acceleration"/>
164 <command_interface name="max_acceleration" />
166 <joint name="joint3">
167 <command_interface name="velocity"/>
168 <state_interface name="position"/>
169 <state_interface name="velocity"/>
170 <state_interface name="acceleration"/>
172 <joint name="configuration">
173 <command_interface name="max_tcp_jerk"/>
174 <state_interface name="max_tcp_jerk"/>
179const auto unitilizable_hardware_resources =
181 <ros2_control name="TestUnitilizableActuatorHardware" type="actuator">
183 <plugin>test_unitilizable_actuator</plugin>
185 <joint name="joint1">
186 <command_interface name="position"/>
187 <state_interface name="position"/>
188 <state_interface name="velocity"/>
189 <command_interface name="max_velocity" />
192 <ros2_control name="TestUnitilizableSensorHardware" type="sensor">
194 <plugin>test_unitilizable_sensor</plugin>
195 <param name="example_param_write_for_sec">2</param>
196 <param name="example_param_read_for_sec">2</param>
198 <sensor name="sensor1">
199 <state_interface name="velocity"/>
202 <ros2_control name="TestUnitilizableSystemHardware" type="system">
204 <plugin>test_unitilizable_system</plugin>
205 <param name="example_param_write_for_sec">2</param>
206 <param name="example_param_read_for_sec">2</param>
208 <joint name="joint2">
209 <command_interface name="velocity"/>
210 <state_interface name="position"/>
211 <state_interface name="velocity"/>
212 <state_interface name="acceleration"/>
213 <command_interface name="max_acceleration" />
215 <joint name="joint3">
216 <command_interface name="velocity"/>
217 <state_interface name="position"/>
218 <state_interface name="velocity"/>
219 <state_interface name="acceleration"/>
221 <joint name="configuration">
222 <command_interface name="max_tcp_jerk"/>
223 <state_interface name="max_tcp_jerk"/>
228const auto hardware_resources_missing_state_keys =
230 <ros2_control name="TestActuatorHardware" type="actuator">
232 <plugin>test_actuator</plugin>
234 <joint name="joint1">
235 <command_interface name="position"/>
236 <state_interface name="position"/>
237 <state_interface name="velocity"/>
240 <ros2_control name="TestSensorHardware" type="sensor">
242 <plugin>test_sensor</plugin>
243 <param name="example_param_write_for_sec">2</param>
244 <param name="example_param_read_for_sec">2</param>
246 <sensor name="sensor1">
247 <state_interface name="velocity"/>
248 <state_interface name="does_not_exist"/>
251 <ros2_control name="TestSystemHardware" type="system">
253 <plugin>test_system</plugin>
254 <param name="example_param_write_for_sec">2</param>
255 <param name="example_param_read_for_sec">2</param>
257 <joint name="joint2">
258 <command_interface name="velocity"/>
259 <state_interface name="position"/>
260 <state_interface name="does_not_exist"/>
262 <joint name="joint3">
263 <command_interface name="velocity"/>
264 <state_interface name="position"/>
265 <state_interface name="does_not_exist"/>
270const auto hardware_resources_missing_command_keys =
272 <ros2_control name="TestActuatorHardware" type="actuator">
274 <plugin>test_actuator</plugin>
276 <joint name="joint1">
277 <command_interface name="position"/>
278 <command_interface name="does_not_exist"/>
279 <state_interface name="position"/>
280 <state_interface name="velocity"/>
283 <ros2_control name="TestSensorHardware" type="sensor">
285 <plugin>test_sensor</plugin>
286 <param name="example_param_write_for_sec">2</param>
287 <param name="example_param_read_for_sec">2</param>
289 <sensor name="sensor1">
290 <state_interface name="velocity"/>
293 <ros2_control name="TestSystemHardware" type="system">
295 <plugin>test_system</plugin>
296 <param name="example_param_write_for_sec">2</param>
297 <param name="example_param_read_for_sec">2</param>
299 <joint name="joint2">
300 <command_interface name="velocity"/>
301 <command_interface name="does_not_exist"/>
302 <state_interface name="position"/>
304 <joint name="joint3">
305 <command_interface name="velocity"/>
306 <command_interface name="does_not_exist"/>
307 <state_interface name="position"/>
312const auto hardware_resources_with_exclusive_interface =
314 <ros2_control name="TestActuatorHardware1" type="actuator">
316 <plugin>test_actuator_exclusive_interfaces</plugin>
318 <joint name="joint1">
319 <command_interface name="position"/>
320 <command_interface name="velocity"/>
321 <command_interface name="effort"/>
322 <state_interface name="position"/>
323 <state_interface name="velocity"/>
324 <state_interface name="effort"/>
327 <ros2_control name="TestActuatorHardware2" type="actuator">
329 <plugin>test_actuator_exclusive_interfaces</plugin>
331 <joint name="joint2">
332 <command_interface name="position"/>
333 <command_interface name="velocity"/>
334 <command_interface name="effort"/>
335 <state_interface name="position"/>
336 <state_interface name="velocity"/>
337 <state_interface name="effort"/>
340 <ros2_control name="TestActuatorHardware3" type="actuator">
342 <plugin>test_actuator_exclusive_interfaces</plugin>
344 <joint name="joint3">
345 <command_interface name="position"/>
346 <command_interface name="velocity"/>
347 <command_interface name="effort"/>
348 <state_interface name="position"/>
349 <state_interface name="velocity"/>
350 <state_interface name="effort"/>
353 <ros2_control name="TestSensorHardware" type="sensor">
355 <plugin>test_sensor</plugin>
356 <param name="example_param_write_for_sec">2</param>
357 <param name="example_param_read_for_sec">2</param>
359 <sensor name="sensor1">
360 <state_interface name="velocity"/>
365const auto diffbot_urdf =
367<?xml version="1.0" ?>
369 <!-- Space btw top of beam and the each joint -->
370 <!-- Links: inertial,visual,collision -->
371 <link name="base_link">
373 <!-- origin is relative -->
374 <origin rpy="0 0 0" xyz="0 0 0"/>
376 <inertia ixx="5" ixy="0" ixz="0" iyy="5" iyz="0" izz="5"/>
380 <box size="0.5 0.1 0.1"/>
384 <!-- origin is relative -->
385 <origin xyz="0 0 0"/>
387 <box size="0.5 0.1 0.1"/>
391 <link name="base_footprint">
394 <sphere radius="0.01"/>
398 <origin xyz="0 0 0"/>
400 <sphere radius="0.00000001"/>
404 <joint name="base_footprint_joint" type="fixed">
405 <origin rpy="0 0 0" xyz="0 0 0.11"/>
406 <child link="base_link"/>
407 <parent link="base_footprint"/>
409 <link name="wheel_0_link">
411 <origin rpy="0 0 0" xyz="0 0 0"/>
413 <inertia ixx="0.2" ixy="0" ixz="0" iyy="0.2" iyz="0" izz="0.2"/>
416 <origin rpy="0 0 0" xyz="0 0 0"/>
418 <cylinder length="0.086" radius="0.11"/>
422 <origin rpy="0 0 0" xyz="0 0 0"/>
424 <cylinder length="0.086" radius="0.11"/>
428 <joint name="wheel_0_joint" type="continuous">
429 <parent link="base_link"/>
430 <child link="wheel_0_link"/>
431 <origin rpy="-1.5707963267948966 0 0" xyz="0.3 0 0"/>
434 <!-- Transmission is important to link the joints and the controller -->
435 <transmission name="wheel_0_joint_trans" type="SimpleTransmission">
436 <actuator name="wheel_0_joint_motor"/>
437 <joint name="wheel_0_joint"/>
438 <mechanicalReduction>1</mechanicalReduction>
439 <motorTorqueConstant>1</motorTorqueConstant>
441 <gazebo reference="wheel_0_link">
442 <material>Gazebo/Red</material>
444 <link name="wheel_1_link">
446 <origin rpy="0 0 0" xyz="0 0 0"/>
448 <inertia ixx="0.2" ixy="0" ixz="0" iyy="0.2" iyz="0" izz="0.2"/>
451 <origin rpy="0 0 0" xyz="0 0 0"/>
453 <cylinder length="0.086" radius="0.11"/>
457 <origin rpy="0 0 0" xyz="0 0 0"/>
459 <cylinder length="0.086" radius="0.11"/>
463 <joint name="wheel_1_joint" type="continuous">
464 <parent link="base_link"/>
465 <child link="wheel_1_link"/>
466 <origin rpy="-1.5707963267948966 0 0" xyz="-0.2 0 0"/>
469 <!-- Transmission is important to link the joints and the controller -->
470 <transmission name="wheel_1_joint_trans" type="SimpleTransmission">
471 <actuator name="wheel_1_joint_motor"/>
472 <joint name="wheel_1_joint"/>
473 <mechanicalReduction>1</mechanicalReduction>
474 <motorTorqueConstant>1</motorTorqueConstant>
476 <gazebo reference="wheel_1_link">
477 <material>Gazebo/Red</material>
480 <gazebo reference="base_link">
481 <material>Gazebo/Green</material>
483 <gazebo reference="base_footprint">
484 <material>Gazebo/Purple</material>
486 <ros2_control name="TestActuatorHardwareLeft" type="actuator">
488 <plugin>test_actuator</plugin>
490 <joint name="wheel_left">
491 <state_interface name="position"/>
492 <command_interface name="velocity"/>
493 <state_interface name="velocity"/>
496 <ros2_control name="TestActuatorHardwareRight" type="actuator">
498 <plugin>test_actuator</plugin>
500 <joint name="wheel_right">
501 <state_interface name="position"/>
502 <command_interface name="velocity"/>
503 <state_interface name="velocity"/>
509const auto minimal_robot_urdf =
510 std::string(urdf_head) + std::string(hardware_resources) + std::string(urdf_tail);
511const auto minimal_unitilizable_robot_urdf =
512 std::string(urdf_head) + std::string(unitilizable_hardware_resources) + std::string(urdf_tail);
514const auto minimal_robot_missing_state_keys_urdf =
515 std::string(urdf_head) + std::string(hardware_resources_missing_state_keys) +
516 std::string(urdf_tail);
518const auto minimal_robot_missing_command_keys_urdf =
519 std::string(urdf_head) + std::string(hardware_resources_missing_command_keys) +
520 std::string(urdf_tail);
522[[maybe_unused]]
const std::string TEST_ACTUATOR_HARDWARE_NAME =
"TestActuatorHardware";
523[[maybe_unused]]
const std::string TEST_ACTUATOR_HARDWARE_TYPE =
"actuator";
524[[maybe_unused]]
const std::string TEST_ACTUATOR_HARDWARE_CLASS_TYPE =
"test_actuator";
525[[maybe_unused]]
const std::vector<std::string> TEST_ACTUATOR_HARDWARE_COMMAND_INTERFACES = {
526 "joint1/position",
"joint1/max_velocity"};
527[[maybe_unused]]
const std::vector<std::string> TEST_ACTUATOR_HARDWARE_STATE_INTERFACES = {
528 "joint1/position",
"joint1/velocity",
"joint1/some_unlisted_interface"};
530[[maybe_unused]]
const std::string TEST_SENSOR_HARDWARE_NAME =
"TestSensorHardware";
531[[maybe_unused]]
const std::string TEST_SENSOR_HARDWARE_TYPE =
"sensor";
532[[maybe_unused]]
const std::string TEST_SENSOR_HARDWARE_CLASS_TYPE =
"test_sensor";
533[[maybe_unused]]
const std::vector<std::string> TEST_SENSOR_HARDWARE_COMMAND_INTERFACES = {
""};
534[[maybe_unused]]
const std::vector<std::string> TEST_SENSOR_HARDWARE_STATE_INTERFACES = {
537[[maybe_unused]]
const std::string TEST_SYSTEM_HARDWARE_NAME =
"TestSystemHardware";
538[[maybe_unused]]
const std::string TEST_SYSTEM_HARDWARE_TYPE =
"system";
539[[maybe_unused]]
const std::string TEST_SYSTEM_HARDWARE_CLASS_TYPE =
"test_system";
540[[maybe_unused]]
const std::vector<std::string> TEST_SYSTEM_HARDWARE_COMMAND_INTERFACES = {
541 "joint2/velocity",
"joint2/max_acceleration",
"joint3/velocity",
"configuration/max_tcp_jerk"};
542[[maybe_unused]]
const std::vector<std::string> TEST_SYSTEM_HARDWARE_STATE_INTERFACES = {
543 "joint2/position",
"joint2/velocity",
"joint2/acceleration",
"joint3/position",
544 "joint3/velocity",
"joint3/acceleration",
"configuration/max_tcp_jerk"};