ros2_control - galactic
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
20namespace ros2_control_test_assets
21{
22const auto urdf_head =
23 R"(
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 -->
31 <link name="world"/>
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"/>
36 </joint>
37 <link name="base_link">
38 <inertial>
39 <mass value="0.01"/>
40 <origin xyz="0 0 0"/>
41 <inertia ixx="0.001" ixy="0.0" ixz="0.0" iyy="0.001" iyz="0.0" izz="0.001"/>
42 </inertial>
43 <visual>
44 <origin rpy="0 0 0" xyz="0 0 0"/>
45 <geometry>
46 <cylinder length="0.2" radius="0.1"/>
47 </geometry>
48 <material name="DarkGrey">
49 <color rgba="0.4 0.4 0.4 1.0"/>
50 </material>
51 </visual>
52 <collision>
53 <origin rpy="0 0 0" xyz="0 0 0"/>
54 <geometry>
55 <cylinder length="1" radius="0.1"/>
56 </geometry>
57 </collision>
58 </link>
59 <joint name="joint1" type="revolute">
60 <origin rpy="-1.57079632679 0 0" xyz="0 0 0.2"/>
61 <parent link="base_link"/>
62 <child link="link1"/>
63 <limit effort="0.1" lower="-3.14159265359" upper="3.14159265359" velocity="0.2"/>
64 </joint>
65 <link name="link1">
66 <inertial>
67 <mass value="0.01"/>
68 <origin xyz="0 0 0"/>
69 <inertia ixx="0.001" ixy="0.0" ixz="0.0" iyy="0.001" iyz="0.0" izz="0.001"/>
70 </inertial>
71 <visual>
72 <origin rpy="0 0 0" xyz="0 0 0"/>
73 <geometry>
74 <cylinder length="1" radius="0.1"/>
75 </geometry>
76 <material name="DarkGrey">
77 <color rgba="0.4 0.4 0.4 1.0"/>
78 </material>
79 </visual>
80 <collision>
81 <origin rpy="0 0 0" xyz="0 0 0"/>
82 <geometry>
83 <cylinder length="1" radius="0.1"/>
84 </geometry>
85 </collision>
86 </link>
87 <joint name="joint2" type="revolute">
88 <origin rpy="1.57079632679 0 0" xyz="0 0 0.9"/>
89 <parent link="link1"/>
90 <child link="link2"/>
91 <limit effort="0.1" lower="-3.14159265359" upper="3.14159265359" velocity="0.2"/>
92 </joint>
93 <link name="link2">
94 <inertial>
95 <mass value="0.01"/>
96 <origin xyz="0 0 0"/>
97 <inertia ixx="0.001" ixy="0.0" ixz="0.0" iyy="0.001" iyz="0.0" izz="0.001"/>
98 </inertial>
99 <visual>
100 <origin rpy="0 0 0" xyz="0 0 0"/>
101 <geometry>
102 <cylinder length="1" radius="0.1"/>
103 </geometry>
104 <material name="DarkGrey">
105 <color rgba="0.4 0.4 0.4 1.0"/>
106 </material>
107 </visual>
108 <collision>
109 <origin rpy="0 0 0" xyz="0 0 0"/>
110 <geometry>
111 <cylinder length="1" radius="0.1"/>
112 </geometry>
113 </collision>
114 </link>
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"/>
119 </joint>
120 <link name="tool_link">
121 </link>
122)";
123
124const auto urdf_tail =
125 R"(
126</robot>
127)";
128
129const auto hardware_resources =
130 R"(
131 <ros2_control name="TestActuatorHardware" type="actuator">
132 <hardware>
133 <plugin>test_actuator</plugin>
134 </hardware>
135 <joint name="joint1">
136 <command_interface name="position"/>
137 <state_interface name="position"/>
138 <state_interface name="velocity"/>
139 </joint>
140 </ros2_control>
141 <ros2_control name="TestSensorHardware" type="sensor">
142 <hardware>
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>
146 </hardware>
147 <sensor name="sensor1">
148 <state_interface name="velocity"/>
149 </sensor>
150 </ros2_control>
151 <ros2_control name="TestSystemHardware" type="system">
152 <hardware>
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>
156 </hardware>
157 <joint name="joint2">
158 <command_interface name="velocity"/>
159 <state_interface name="position"/>
160 </joint>
161 <joint name="joint3">
162 <command_interface name="velocity"/>
163 <state_interface name="position"/>
164 </joint>
165 </ros2_control>
166)";
167
168const auto hardware_resources_missing_state_keys =
169 R"(
170 <ros2_control name="TestActuatorHardware" type="actuator">
171 <hardware>
172 <plugin>test_actuator</plugin>
173 </hardware>
174 <joint name="joint1">
175 <command_interface name="position"/>
176 <state_interface name="position"/>
177 <state_interface name="velocity"/>
178 </joint>
179 </ros2_control>
180 <ros2_control name="TestSensorHardware" type="sensor">
181 <hardware>
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>
185 </hardware>
186 <sensor name="sensor1">
187 <state_interface name="velocity"/>
188 <state_interface name="does_not_exist"/>
189 </sensor>
190 </ros2_control>
191 <ros2_control name="TestSystemHardware" type="system">
192 <hardware>
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>
196 </hardware>
197 <joint name="joint2">
198 <command_interface name="velocity"/>
199 <state_interface name="position"/>
200 <state_interface name="does_not_exist"/>
201 </joint>
202 <joint name="joint3">
203 <command_interface name="velocity"/>
204 <state_interface name="position"/>
205 <state_interface name="does_not_exist"/>
206 </joint>
207 </ros2_control>
208)";
209
210const auto hardware_resources_missing_command_keys =
211 R"(
212 <ros2_control name="TestActuatorHardware" type="actuator">
213 <hardware>
214 <plugin>test_actuator</plugin>
215 </hardware>
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"/>
221 </joint>
222 </ros2_control>
223 <ros2_control name="TestSensorHardware" type="sensor">
224 <hardware>
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>
228 </hardware>
229 <sensor name="sensor1">
230 <state_interface name="velocity"/>
231 </sensor>
232 </ros2_control>
233 <ros2_control name="TestSystemHardware" type="system">
234 <hardware>
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>
238 </hardware>
239 <joint name="joint2">
240 <command_interface name="velocity"/>
241 <command_interface name="does_not_exist"/>
242 <state_interface name="position"/>
243 </joint>
244 <joint name="joint3">
245 <command_interface name="velocity"/>
246 <command_interface name="does_not_exist"/>
247 <state_interface name="position"/>
248 </joint>
249 </ros2_control>
250)";
251
252const auto diffbot_urdf =
253 R"(
254<?xml version="1.0" ?>
255<robot name="robot">
256 <!-- Space btw top of beam and the each joint -->
257 <!-- Links: inertial,visual,collision -->
258 <link name="base_link">
259 <inertial>
260 <!-- origin is relative -->
261 <origin rpy="0 0 0" xyz="0 0 0"/>
262 <mass value="5"/>
263 <inertia ixx="5" ixy="0" ixz="0" iyy="5" iyz="0" izz="5"/>
264 </inertial>
265 <visual>
266 <geometry>
267 <box size="0.5 0.1 0.1"/>
268 </geometry>
269 </visual>
270 <collision>
271 <!-- origin is relative -->
272 <origin xyz="0 0 0"/>
273 <geometry>
274 <box size="0.5 0.1 0.1"/>
275 </geometry>
276 </collision>
277 </link>
278 <link name="base_footprint">
279 <visual>
280 <geometry>
281 <sphere radius="0.01"/>
282 </geometry>
283 </visual>
284 <collision>
285 <origin xyz="0 0 0"/>
286 <geometry>
287 <sphere radius="0.00000001"/>
288 </geometry>
289 </collision>
290 </link>
291 <joint name="base_footprint_joint" type="fixed">
292 <origin rpy="0 0 0" xyz="0 0 0.11"/>
293 <child link="base_link"/>
294 <parent link="base_footprint"/>
295 </joint>
296 <link name="wheel_0_link">
297 <inertial>
298 <origin rpy="0 0 0" xyz="0 0 0"/>
299 <mass value="1"/>
300 <inertia ixx="0.2" ixy="0" ixz="0" iyy="0.2" iyz="0" izz="0.2"/>
301 </inertial>
302 <visual>
303 <origin rpy="0 0 0" xyz="0 0 0"/>
304 <geometry>
305 <cylinder length="0.086" radius="0.11"/>
306 </geometry>
307 </visual>
308 <collision>
309 <origin rpy="0 0 0" xyz="0 0 0"/>
310 <geometry>
311 <cylinder length="0.086" radius="0.11"/>
312 </geometry>
313 </collision>
314 </link>
315 <joint name="wheel_0_joint" type="continuous">
316 <parent link="base_link"/>
317 <child link="wheel_0_link"/>
318 <origin rpy="-1.5707963267948966 0 0" xyz="0.3 0 0"/>
319 <axis xyz="0 0 1"/>
320 </joint>
321 <!-- Transmission is important to link the joints and the controller -->
322 <transmission name="wheel_0_joint_trans" type="SimpleTransmission">
323 <actuator name="wheel_0_joint_motor"/>
324 <joint name="wheel_0_joint"/>
325 <mechanicalReduction>1</mechanicalReduction>
326 <motorTorqueConstant>1</motorTorqueConstant>
327 </transmission>
328 <gazebo reference="wheel_0_link">
329 <material>Gazebo/Red</material>
330 </gazebo>
331 <link name="wheel_1_link">
332 <inertial>
333 <origin rpy="0 0 0" xyz="0 0 0"/>
334 <mass value="1"/>
335 <inertia ixx="0.2" ixy="0" ixz="0" iyy="0.2" iyz="0" izz="0.2"/>
336 </inertial>
337 <visual>
338 <origin rpy="0 0 0" xyz="0 0 0"/>
339 <geometry>
340 <cylinder length="0.086" radius="0.11"/>
341 </geometry>
342 </visual>
343 <collision>
344 <origin rpy="0 0 0" xyz="0 0 0"/>
345 <geometry>
346 <cylinder length="0.086" radius="0.11"/>
347 </geometry>
348 </collision>
349 </link>
350 <joint name="wheel_1_joint" type="continuous">
351 <parent link="base_link"/>
352 <child link="wheel_1_link"/>
353 <origin rpy="-1.5707963267948966 0 0" xyz="-0.2 0 0"/>
354 <axis xyz="0 0 1"/>
355 </joint>
356 <!-- Transmission is important to link the joints and the controller -->
357 <transmission name="wheel_1_joint_trans" type="SimpleTransmission">
358 <actuator name="wheel_1_joint_motor"/>
359 <joint name="wheel_1_joint"/>
360 <mechanicalReduction>1</mechanicalReduction>
361 <motorTorqueConstant>1</motorTorqueConstant>
362 </transmission>
363 <gazebo reference="wheel_1_link">
364 <material>Gazebo/Red</material>
365 </gazebo>
366 <!-- Colour -->
367 <gazebo reference="base_link">
368 <material>Gazebo/Green</material>
369 </gazebo>
370 <gazebo reference="base_footprint">
371 <material>Gazebo/Purple</material>
372 </gazebo>
373 <ros2_control name="TestActuatorHardwareLeft" type="actuator">
374 <hardware>
375 <plugin>test_actuator</plugin>
376 </hardware>
377 <joint name="wheel_left">
378 <state_interface name="position"/>
379 <command_interface name="velocity"/>
380 <state_interface name="velocity"/>
381 </joint>
382 </ros2_control>
383 <ros2_control name="TestActuatorHardwareRight" type="actuator">
384 <hardware>
385 <plugin>test_actuator</plugin>
386 </hardware>
387 <joint name="wheel_right">
388 <state_interface name="position"/>
389 <command_interface name="velocity"/>
390 <state_interface name="velocity"/>
391 </joint>
392 </ros2_control>
393</robot>
394)";
395
396const auto minimal_robot_urdf =
397 std::string(urdf_head) + std::string(hardware_resources) + std::string(urdf_tail);
398
399const auto minimal_robot_missing_state_keys_urdf =
400 std::string(urdf_head) + std::string(hardware_resources_missing_state_keys) +
401 std::string(urdf_tail);
402
403const auto minimal_robot_missing_command_keys_urdf =
404 std::string(urdf_head) + std::string(hardware_resources_missing_command_keys) +
405 std::string(urdf_tail);
406} // namespace ros2_control_test_assets
407
408#endif // ROS2_CONTROL_TEST_ASSETS__DESCRIPTIONS_HPP_