-
Notifications
You must be signed in to change notification settings - Fork 51
/
andino_control.urdf.xacro
43 lines (37 loc) · 1.61 KB
/
andino_control.urdf.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
<?xml version="1.0"?>
<robot xmlns:xacro="http://www.ros.org/wiki/xacro">
<!-- ===================== Control xacro =========================================
params:
- hardware_props [dictionary]: hardware properties loaded from the YAML file.
-->
<xacro:macro name="control" params="hardware_props" >
<!-- TODO(francocipollone): This xacro should be part of andino_control package instead.-->
<ros2_control name="RealRobot" type="system">
<hardware>
<plugin>andino_base/DiffDriveAndino</plugin>
<param name="left_wheel_name">${hardware_props['left_wheel_name']}</param>
<param name="right_wheel_name">${hardware_props['right_wheel_name']}</param>
<param name="serial_device">${hardware_props['serial_device']}</param>
<param name="baud_rate">${hardware_props['baud_rate']}</param>
<param name="timeout">${hardware_props['timeout']}</param>
<param name="enc_ticks_per_rev">${hardware_props['enc_ticks_per_rev']}</param>
</hardware>
<joint name="left_wheel_joint">
<command_interface name="velocity">
<param name="min">-5</param>
<param name="max">5</param>
</command_interface>
<state_interface name="velocity"/>
<state_interface name="position"/>
</joint>
<joint name="right_wheel_joint">
<command_interface name="velocity">
<param name="min">-5</param>
<param name="max">5</param>
</command_interface>
<state_interface name="velocity"/>
<state_interface name="position"/>
</joint>
</ros2_control>
</xacro:macro>
</robot>