15#ifndef ROS2_CONTROL_TEST_ASSETS__DESCRIPTIONS_HPP_
16#define ROS2_CONTROL_TEST_ASSETS__DESCRIPTIONS_HPP_
20namespace ros2_control_test_assets
24<?xml version="1.0" encoding="utf-8"?>
25<!-- =================================================================================== -->
26<!-- | This document was autogenerated by xacro from minimal_robot.urdf.xacro | -->
27<!-- | EDITING THIS FILE BY HAND IS NOT RECOMMENDED | -->
28<!-- =================================================================================== -->
29<robot name="MinimalRobot">
30 <!-- Used for fixing robot -->
32 <joint name="base_joint" type="fixed">
33 <origin rpy="0 0 0" xyz="0 0 0"/>
34 <parent link="world"/>
35 <child link="base_link"/>
37 <link name="base_link">
41 <inertia ixx="0.001" ixy="0.0" ixz="0.0" iyy="0.001" iyz="0.0" izz="0.001"/>
44 <origin rpy="0 0 0" xyz="0 0 0"/>
46 <cylinder length="0.2" radius="0.1"/>
48 <material name="DarkGrey">
49 <color rgba="0.4 0.4 0.4 1.0"/>
53 <origin rpy="0 0 0" xyz="0 0 0"/>
55 <cylinder length="1" radius="0.1"/>
59 <joint name="joint1" type="revolute">
60 <origin rpy="-1.57079632679 0 0" xyz="0 0 0.2"/>
61 <parent link="base_link"/>
63 <limit effort="0.1" lower="-3.14159265359" upper="3.14159265359" velocity="0.2"/>
69 <inertia ixx="0.001" ixy="0.0" ixz="0.0" iyy="0.001" iyz="0.0" izz="0.001"/>
72 <origin rpy="0 0 0" xyz="0 0 0"/>
74 <cylinder length="1" radius="0.1"/>
76 <material name="DarkGrey">
77 <color rgba="0.4 0.4 0.4 1.0"/>
81 <origin rpy="0 0 0" xyz="0 0 0"/>
83 <cylinder length="1" radius="0.1"/>
87 <joint name="joint2" type="revolute">
88 <origin rpy="1.57079632679 0 0" xyz="0 0 0.9"/>
89 <parent link="link1"/>
91 <limit effort="0.1" lower="-3.14159265359" upper="3.14159265359" velocity="0.2"/>
97 <inertia ixx="0.001" ixy="0.0" ixz="0.0" iyy="0.001" iyz="0.0" izz="0.001"/>
100 <origin rpy="0 0 0" xyz="0 0 0"/>
102 <cylinder length="1" radius="0.1"/>
104 <material name="DarkGrey">
105 <color rgba="0.4 0.4 0.4 1.0"/>
109 <origin rpy="0 0 0" xyz="0 0 0"/>
111 <cylinder length="1" radius="0.1"/>
115 <joint name="tool_joint" type="fixed">
116 <origin rpy="0 0 0" xyz="0 0 1"/>
117 <parent link="link2"/>
118 <child link="tool_link"/>
120 <link name="tool_link">
124const auto urdf_tail =
129const auto hardware_resources =
131 <ros2_control name="TestActuatorHardware" type="actuator">
133 <plugin>test_actuator</plugin>
135 <joint name="joint1">
136 <command_interface name="position"/>
137 <state_interface name="position"/>
138 <state_interface name="velocity"/>
141 <ros2_control name="TestSensorHardware" type="sensor">
143 <plugin>test_sensor</plugin>
144 <param name="example_param_write_for_sec">2</param>
145 <param name="example_param_read_for_sec">2</param>
147 <sensor name="sensor1">
148 <state_interface name="velocity"/>
151 <ros2_control name="TestSystemHardware" type="system">
153 <plugin>test_system</plugin>
154 <param name="example_param_write_for_sec">2</param>
155 <param name="example_param_read_for_sec">2</param>
157 <joint name="joint2">
158 <command_interface name="velocity"/>
159 <state_interface name="position"/>
161 <joint name="joint3">
162 <command_interface name="velocity"/>
163 <state_interface name="position"/>
168const auto hardware_resources_missing_state_keys =
170 <ros2_control name="TestActuatorHardware" type="actuator">
172 <plugin>test_actuator</plugin>
174 <joint name="joint1">
175 <command_interface name="position"/>
176 <state_interface name="position"/>
177 <state_interface name="velocity"/>
180 <ros2_control name="TestSensorHardware" type="sensor">
182 <plugin>test_sensor</plugin>
183 <param name="example_param_write_for_sec">2</param>
184 <param name="example_param_read_for_sec">2</param>
186 <sensor name="sensor1">
187 <state_interface name="velocity"/>
188 <state_interface name="does_not_exist"/>
191 <ros2_control name="TestSystemHardware" type="system">
193 <plugin>test_system</plugin>
194 <param name="example_param_write_for_sec">2</param>
195 <param name="example_param_read_for_sec">2</param>
197 <joint name="joint2">
198 <command_interface name="velocity"/>
199 <state_interface name="position"/>
200 <state_interface name="does_not_exist"/>
202 <joint name="joint3">
203 <command_interface name="velocity"/>
204 <state_interface name="position"/>
205 <state_interface name="does_not_exist"/>
210const auto hardware_resources_missing_command_keys =
212 <ros2_control name="TestActuatorHardware" type="actuator">
214 <plugin>test_actuator</plugin>
216 <joint name="joint1">
217 <command_interface name="position"/>
218 <command_interface name="does_not_exist"/>
219 <state_interface name="position"/>
220 <state_interface name="velocity"/>
223 <ros2_control name="TestSensorHardware" type="sensor">
225 <plugin>test_sensor</plugin>
226 <param name="example_param_write_for_sec">2</param>
227 <param name="example_param_read_for_sec">2</param>
229 <sensor name="sensor1">
230 <state_interface name="velocity"/>
233 <ros2_control name="TestSystemHardware" type="system">
235 <plugin>test_system</plugin>
236 <param name="example_param_write_for_sec">2</param>
237 <param name="example_param_read_for_sec">2</param>
239 <joint name="joint2">
240 <command_interface name="velocity"/>
241 <command_interface name="does_not_exist"/>
242 <state_interface name="position"/>
244 <joint name="joint3">
245 <command_interface name="velocity"/>
246 <command_interface name="does_not_exist"/>
247 <state_interface name="position"/>
252const auto minimal_robot_urdf =
253 std::string(urdf_head) + std::string(hardware_resources) + std::string(urdf_tail);
255const auto minimal_robot_missing_state_keys_urdf =
256 std::string(urdf_head) + std::string(hardware_resources_missing_state_keys) +
257 std::string(urdf_tail);
259const auto minimal_robot_missing_command_keys_urdf =
260 std::string(urdf_head) + std::string(hardware_resources_missing_command_keys) +
261 std::string(urdf_tail);