-
Notifications
You must be signed in to change notification settings - Fork 173
/
rrbot_system_with_sensor.ros2_control.xacro
48 lines (42 loc) · 1.79 KB
/
rrbot_system_with_sensor.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
<?xml version="1.0"?>
<robot xmlns:xacro="http://www.ros.org/wiki/xacro">
<xacro:macro name="rrbot_system_with_sensor" params="name prefix use_mock_hardware:=^|true mock_sensor_commands:=^|false slowdown:=2.0">
<ros2_control name="${name}" type="system">
<hardware>
<xacro:if value="${use_mock_hardware}">
<plugin>mock_components/GenericSystem</plugin>
<param name="mock_sensor_commands">${mock_sensor_commands}</param>
<param name="position_state_following_offset">0.0</param>
</xacro:if>
<xacro:unless value="${use_mock_hardware}">
<plugin>ros2_control_demo_example_4/RRBotSystemWithSensorHardware</plugin>
<param name="example_param_hw_start_duration_sec">0.0</param>
<param name="example_param_hw_stop_duration_sec">3.0</param>
<param name="example_param_hw_slowdown">${slowdown}</param>
<param name="example_param_max_sensor_change">5.0</param>
</xacro:unless>
</hardware>
<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>
<sensor name="${prefix}tcp_fts_sensor">
<state_interface name="force.x"/>
<state_interface name="torque.z"/>
<param name="frame_id">tool_link</param>
<param name="fx_range">100</param>
<param name="tz_range">15</param>
</sensor>
</ros2_control>
</xacro:macro>
</robot>