ros2_control - humble
Loading...
Searching...
No Matches
descriptions.hpp
1// Copyright 2020 ros2_control Development Team
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__DESCRIPTIONS_HPP_
16#define ROS2_CONTROL_TEST_ASSETS__DESCRIPTIONS_HPP_
17
18#include <string>
19#include <vector>
20
21namespace ros2_control_test_assets
22{
23const auto urdf_head =
24 R"(
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 -->
32 <link name="world"/>
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"/>
37 </joint>
38 <link name="base_link">
39 <inertial>
40 <mass value="0.01"/>
41 <origin xyz="0 0 0"/>
42 <inertia ixx="0.001" ixy="0.0" ixz="0.0" iyy="0.001" iyz="0.0" izz="0.001"/>
43 </inertial>
44 <visual>
45 <origin rpy="0 0 0" xyz="0 0 0"/>
46 <geometry>
47 <cylinder length="0.2" radius="0.1"/>
48 </geometry>
49 <material name="DarkGrey">
50 <color rgba="0.4 0.4 0.4 1.0"/>
51 </material>
52 </visual>
53 <collision>
54 <origin rpy="0 0 0" xyz="0 0 0"/>
55 <geometry>
56 <cylinder length="1" radius="0.1"/>
57 </geometry>
58 </collision>
59 </link>
60 <joint name="joint1" type="revolute">
61 <origin rpy="-1.57079632679 0 0" xyz="0 0 0.2"/>
62 <parent link="base_link"/>
63 <child link="link1"/>
64 <limit effort="0.1" lower="-3.14159265359" upper="3.14159265359" velocity="0.2"/>
65 </joint>
66 <link name="link1">
67 <inertial>
68 <mass value="0.01"/>
69 <origin xyz="0 0 0"/>
70 <inertia ixx="0.001" ixy="0.0" ixz="0.0" iyy="0.001" iyz="0.0" izz="0.001"/>
71 </inertial>
72 <visual>
73 <origin rpy="0 0 0" xyz="0 0 0"/>
74 <geometry>
75 <cylinder length="1" radius="0.1"/>
76 </geometry>
77 <material name="DarkGrey">
78 <color rgba="0.4 0.4 0.4 1.0"/>
79 </material>
80 </visual>
81 <collision>
82 <origin rpy="0 0 0" xyz="0 0 0"/>
83 <geometry>
84 <cylinder length="1" radius="0.1"/>
85 </geometry>
86 </collision>
87 </link>
88 <joint name="joint2" type="revolute">
89 <origin rpy="1.57079632679 0 0" xyz="0 0 0.9"/>
90 <parent link="link1"/>
91 <child link="link2"/>
92 <limit effort="0.1" lower="-3.14159265359" upper="3.14159265359" velocity="0.2"/>
93 </joint>
94 <link name="link2">
95 <inertial>
96 <mass value="0.01"/>
97 <origin xyz="0 0 0"/>
98 <inertia ixx="0.001" ixy="0.0" ixz="0.0" iyy="0.001" iyz="0.0" izz="0.001"/>
99 </inertial>
100 <visual>
101 <origin rpy="0 0 0" xyz="0 0 0"/>
102 <geometry>
103 <cylinder length="1" radius="0.1"/>
104 </geometry>
105 <material name="DarkGrey">
106 <color rgba="0.4 0.4 0.4 1.0"/>
107 </material>
108 </visual>
109 <collision>
110 <origin rpy="0 0 0" xyz="0 0 0"/>
111 <geometry>
112 <cylinder length="1" radius="0.1"/>
113 </geometry>
114 </collision>
115 </link>
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"/>
120 </joint>
121 <link name="tool_link">
122 </link>
123)";
124
125const auto urdf_tail =
126 R"(
127</robot>
128)";
129
130const auto hardware_resources =
131 R"(
132 <ros2_control name="TestActuatorHardware" type="actuator">
133 <hardware>
134 <plugin>test_actuator</plugin>
135 </hardware>
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" />
141 </joint>
142 </ros2_control>
143 <ros2_control name="TestSensorHardware" type="sensor">
144 <hardware>
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>
148 </hardware>
149 <sensor name="sensor1">
150 <state_interface name="velocity"/>
151 </sensor>
152 </ros2_control>
153 <ros2_control name="TestSystemHardware" type="system">
154 <hardware>
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>
158 </hardware>
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" />
165 </joint>
166 <joint name="joint3">
167 <command_interface name="velocity"/>
168 <state_interface name="position"/>
169 <state_interface name="velocity"/>
170 <state_interface name="acceleration"/>
171 </joint>
172 <joint name="configuration">
173 <command_interface name="max_tcp_jerk"/>
174 <state_interface name="max_tcp_jerk"/>
175 </joint>
176 </ros2_control>
177)";
178
179const auto unitilizable_hardware_resources =
180 R"(
181 <ros2_control name="TestUnitilizableActuatorHardware" type="actuator">
182 <hardware>
183 <plugin>test_unitilizable_actuator</plugin>
184 </hardware>
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" />
190 </joint>
191 </ros2_control>
192 <ros2_control name="TestUnitilizableSensorHardware" type="sensor">
193 <hardware>
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>
197 </hardware>
198 <sensor name="sensor1">
199 <state_interface name="velocity"/>
200 </sensor>
201 </ros2_control>
202 <ros2_control name="TestUnitilizableSystemHardware" type="system">
203 <hardware>
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>
207 </hardware>
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" />
214 </joint>
215 <joint name="joint3">
216 <command_interface name="velocity"/>
217 <state_interface name="position"/>
218 <state_interface name="velocity"/>
219 <state_interface name="acceleration"/>
220 </joint>
221 <joint name="configuration">
222 <command_interface name="max_tcp_jerk"/>
223 <state_interface name="max_tcp_jerk"/>
224 </joint>
225 </ros2_control>
226)";
227
228const auto hardware_resources_missing_state_keys =
229 R"(
230 <ros2_control name="TestActuatorHardware" type="actuator">
231 <hardware>
232 <plugin>test_actuator</plugin>
233 </hardware>
234 <joint name="joint1">
235 <command_interface name="position"/>
236 <state_interface name="position"/>
237 <state_interface name="velocity"/>
238 </joint>
239 </ros2_control>
240 <ros2_control name="TestSensorHardware" type="sensor">
241 <hardware>
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>
245 </hardware>
246 <sensor name="sensor1">
247 <state_interface name="velocity"/>
248 <state_interface name="does_not_exist"/>
249 </sensor>
250 </ros2_control>
251 <ros2_control name="TestSystemHardware" type="system">
252 <hardware>
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>
256 </hardware>
257 <joint name="joint2">
258 <command_interface name="velocity"/>
259 <state_interface name="position"/>
260 <state_interface name="does_not_exist"/>
261 </joint>
262 <joint name="joint3">
263 <command_interface name="velocity"/>
264 <state_interface name="position"/>
265 <state_interface name="does_not_exist"/>
266 </joint>
267 </ros2_control>
268)";
269
270const auto hardware_resources_missing_command_keys =
271 R"(
272 <ros2_control name="TestActuatorHardware" type="actuator">
273 <hardware>
274 <plugin>test_actuator</plugin>
275 </hardware>
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"/>
281 </joint>
282 </ros2_control>
283 <ros2_control name="TestSensorHardware" type="sensor">
284 <hardware>
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>
288 </hardware>
289 <sensor name="sensor1">
290 <state_interface name="velocity"/>
291 </sensor>
292 </ros2_control>
293 <ros2_control name="TestSystemHardware" type="system">
294 <hardware>
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>
298 </hardware>
299 <joint name="joint2">
300 <command_interface name="velocity"/>
301 <command_interface name="does_not_exist"/>
302 <state_interface name="position"/>
303 </joint>
304 <joint name="joint3">
305 <command_interface name="velocity"/>
306 <command_interface name="does_not_exist"/>
307 <state_interface name="position"/>
308 </joint>
309 </ros2_control>
310)";
311
312const auto diffbot_urdf =
313 R"(
314<?xml version="1.0" ?>
315<robot name="robot">
316 <!-- Space btw top of beam and the each joint -->
317 <!-- Links: inertial,visual,collision -->
318 <link name="base_link">
319 <inertial>
320 <!-- origin is relative -->
321 <origin rpy="0 0 0" xyz="0 0 0"/>
322 <mass value="5"/>
323 <inertia ixx="5" ixy="0" ixz="0" iyy="5" iyz="0" izz="5"/>
324 </inertial>
325 <visual>
326 <geometry>
327 <box size="0.5 0.1 0.1"/>
328 </geometry>
329 </visual>
330 <collision>
331 <!-- origin is relative -->
332 <origin xyz="0 0 0"/>
333 <geometry>
334 <box size="0.5 0.1 0.1"/>
335 </geometry>
336 </collision>
337 </link>
338 <link name="base_footprint">
339 <visual>
340 <geometry>
341 <sphere radius="0.01"/>
342 </geometry>
343 </visual>
344 <collision>
345 <origin xyz="0 0 0"/>
346 <geometry>
347 <sphere radius="0.00000001"/>
348 </geometry>
349 </collision>
350 </link>
351 <joint name="base_footprint_joint" type="fixed">
352 <origin rpy="0 0 0" xyz="0 0 0.11"/>
353 <child link="base_link"/>
354 <parent link="base_footprint"/>
355 </joint>
356 <link name="wheel_0_link">
357 <inertial>
358 <origin rpy="0 0 0" xyz="0 0 0"/>
359 <mass value="1"/>
360 <inertia ixx="0.2" ixy="0" ixz="0" iyy="0.2" iyz="0" izz="0.2"/>
361 </inertial>
362 <visual>
363 <origin rpy="0 0 0" xyz="0 0 0"/>
364 <geometry>
365 <cylinder length="0.086" radius="0.11"/>
366 </geometry>
367 </visual>
368 <collision>
369 <origin rpy="0 0 0" xyz="0 0 0"/>
370 <geometry>
371 <cylinder length="0.086" radius="0.11"/>
372 </geometry>
373 </collision>
374 </link>
375 <joint name="wheel_0_joint" type="continuous">
376 <parent link="base_link"/>
377 <child link="wheel_0_link"/>
378 <origin rpy="-1.5707963267948966 0 0" xyz="0.3 0 0"/>
379 <axis xyz="0 0 1"/>
380 </joint>
381 <!-- Transmission is important to link the joints and the controller -->
382 <transmission name="wheel_0_joint_trans" type="SimpleTransmission">
383 <actuator name="wheel_0_joint_motor"/>
384 <joint name="wheel_0_joint"/>
385 <mechanicalReduction>1</mechanicalReduction>
386 <motorTorqueConstant>1</motorTorqueConstant>
387 </transmission>
388 <gazebo reference="wheel_0_link">
389 <material>Gazebo/Red</material>
390 </gazebo>
391 <link name="wheel_1_link">
392 <inertial>
393 <origin rpy="0 0 0" xyz="0 0 0"/>
394 <mass value="1"/>
395 <inertia ixx="0.2" ixy="0" ixz="0" iyy="0.2" iyz="0" izz="0.2"/>
396 </inertial>
397 <visual>
398 <origin rpy="0 0 0" xyz="0 0 0"/>
399 <geometry>
400 <cylinder length="0.086" radius="0.11"/>
401 </geometry>
402 </visual>
403 <collision>
404 <origin rpy="0 0 0" xyz="0 0 0"/>
405 <geometry>
406 <cylinder length="0.086" radius="0.11"/>
407 </geometry>
408 </collision>
409 </link>
410 <joint name="wheel_1_joint" type="continuous">
411 <parent link="base_link"/>
412 <child link="wheel_1_link"/>
413 <origin rpy="-1.5707963267948966 0 0" xyz="-0.2 0 0"/>
414 <axis xyz="0 0 1"/>
415 </joint>
416 <!-- Transmission is important to link the joints and the controller -->
417 <transmission name="wheel_1_joint_trans" type="SimpleTransmission">
418 <actuator name="wheel_1_joint_motor"/>
419 <joint name="wheel_1_joint"/>
420 <mechanicalReduction>1</mechanicalReduction>
421 <motorTorqueConstant>1</motorTorqueConstant>
422 </transmission>
423 <gazebo reference="wheel_1_link">
424 <material>Gazebo/Red</material>
425 </gazebo>
426 <!-- Colour -->
427 <gazebo reference="base_link">
428 <material>Gazebo/Green</material>
429 </gazebo>
430 <gazebo reference="base_footprint">
431 <material>Gazebo/Purple</material>
432 </gazebo>
433 <ros2_control name="TestActuatorHardwareLeft" type="actuator">
434 <hardware>
435 <plugin>test_actuator</plugin>
436 </hardware>
437 <joint name="wheel_left">
438 <state_interface name="position"/>
439 <command_interface name="velocity"/>
440 <state_interface name="velocity"/>
441 </joint>
442 </ros2_control>
443 <ros2_control name="TestActuatorHardwareRight" type="actuator">
444 <hardware>
445 <plugin>test_actuator</plugin>
446 </hardware>
447 <joint name="wheel_right">
448 <state_interface name="position"/>
449 <command_interface name="velocity"/>
450 <state_interface name="velocity"/>
451 </joint>
452 </ros2_control>
453</robot>
454)";
455
456const auto minimal_robot_urdf =
457 std::string(urdf_head) + std::string(hardware_resources) + std::string(urdf_tail);
458const auto minimal_unitilizable_robot_urdf =
459 std::string(urdf_head) + std::string(unitilizable_hardware_resources) + std::string(urdf_tail);
460
461const auto minimal_robot_missing_state_keys_urdf =
462 std::string(urdf_head) + std::string(hardware_resources_missing_state_keys) +
463 std::string(urdf_tail);
464
465const auto minimal_robot_missing_command_keys_urdf =
466 std::string(urdf_head) + std::string(hardware_resources_missing_command_keys) +
467 std::string(urdf_tail);
468
469[[maybe_unused]] const std::string TEST_ACTUATOR_HARDWARE_NAME = "TestActuatorHardware";
470[[maybe_unused]] const std::string TEST_ACTUATOR_HARDWARE_TYPE = "actuator";
471[[maybe_unused]] const std::string TEST_ACTUATOR_HARDWARE_CLASS_TYPE = "test_actuator";
472[[maybe_unused]] const std::vector<std::string> TEST_ACTUATOR_HARDWARE_COMMAND_INTERFACES = {
473 "joint1/position", "joint1/max_velocity"};
474[[maybe_unused]] const std::vector<std::string> TEST_ACTUATOR_HARDWARE_STATE_INTERFACES = {
475 "joint1/position", "joint1/velocity", "joint1/some_unlisted_interface"};
476
477[[maybe_unused]] const std::string TEST_SENSOR_HARDWARE_NAME = "TestSensorHardware";
478[[maybe_unused]] const std::string TEST_SENSOR_HARDWARE_TYPE = "sensor";
479[[maybe_unused]] const std::string TEST_SENSOR_HARDWARE_CLASS_TYPE = "test_sensor";
480[[maybe_unused]] const std::vector<std::string> TEST_SENSOR_HARDWARE_COMMAND_INTERFACES = {""};
481[[maybe_unused]] const std::vector<std::string> TEST_SENSOR_HARDWARE_STATE_INTERFACES = {
482 "sensor1/velocity"};
483
484[[maybe_unused]] const std::string TEST_SYSTEM_HARDWARE_NAME = "TestSystemHardware";
485[[maybe_unused]] const std::string TEST_SYSTEM_HARDWARE_TYPE = "system";
486[[maybe_unused]] const std::string TEST_SYSTEM_HARDWARE_CLASS_TYPE = "test_system";
487[[maybe_unused]] const std::vector<std::string> TEST_SYSTEM_HARDWARE_COMMAND_INTERFACES = {
488 "joint2/velocity", "joint2/max_acceleration", "joint3/velocity", "configuration/max_tcp_jerk"};
489[[maybe_unused]] const std::vector<std::string> TEST_SYSTEM_HARDWARE_STATE_INTERFACES = {
490 "joint2/position", "joint2/velocity", "joint2/acceleration", "joint3/position",
491 "joint3/velocity", "joint3/acceleration", "configuration/max_tcp_jerk"};
492
493} // namespace ros2_control_test_assets
494
495#endif // ROS2_CONTROL_TEST_ASSETS__DESCRIPTIONS_HPP_