-
Notifications
You must be signed in to change notification settings - Fork 212
/
Copy pathrrbot.ros2_control.xacro
53 lines (48 loc) · 2.01 KB
/
rrbot.ros2_control.xacro
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
<?xml version="1.0"?>
<robot xmlns:xacro="http://www.ros.org/wiki/xacro">
<xacro:macro name="rrbot_ros2_control" params="name prefix use_mock_hardware">
<ros2_control name="${name}" type="system">
<xacro:unless value="${use_mock_hardware}">
<hardware>
<plugin>ros2_control_demo_example_10/RRBotSystemWithGPIOHardware</plugin>
<param name="example_param_hw_start_duration_sec">0</param>
<param name="example_param_hw_stop_duration_sec">3.0</param>
<param name="example_param_hw_slowdown">100</param>
</hardware>
</xacro:unless>
<xacro:if value="${use_mock_hardware}">
<hardware>
<plugin>mock_components/GenericSystem</plugin>
<param name="calculate_dynamics">true</param>
</hardware>
</xacro:if>
<joint name="${prefix}joint1">
<command_interface name="position">
<param name="min">-1</param>
<param name="max">1</param>
</command_interface>
<state_interface name="position"/>
</joint>
<joint name="${prefix}joint2">
<command_interface name="position">
<param name="min">-1</param>
<param name="max">1</param>
</command_interface>
<state_interface name="position"/>
</joint>
<!-- from https://github.com/ros-controls/ros2_control/blob/f58d4072dbd1c3fd4e1f64cd10a19a2b60f59049/ros2_control_test_assets/include/ros2_control_test_assets/components_urdfs.hpp#L344 -->
<gpio name="flange_analog_IOs">
<command_interface name="analog_output1"/>
<state_interface name="analog_output1"/> <!-- Needed to know current state of the output -->
<state_interface name="analog_input1"/>
<state_interface name="analog_input2"/>
</gpio>
<gpio name="flange_vacuum">
<command_interface name="vacuum"/>
<state_interface name="vacuum">
<param name="initial_value">1.0</param>
</state_interface>
</gpio>
</ros2_control>
</xacro:macro>
</robot>