forked from Ekumen-OS/andino
-
Notifications
You must be signed in to change notification settings - Fork 0
/
andino_control.urdf.xacro
34 lines (32 loc) · 1.32 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
<?xml version="1.0"?>
<robot xmlns:xacro="http://www.ros.org/wiki/xacro">
<!-- TODO(francocipollone): This xacro should be part of andino_control package instead.-->
<ros2_control name="RealRobot" type="system">
<hardware>
<plugin>andino_base/DiffDriveAndino</plugin>
<!-- TODO(francocipollone): Parameters like loop_rate, device, baud_rate, etc should be loaded from a file or passed via the launch file as xacro args -->
<param name="left_wheel_name">left_wheel_joint</param>
<param name="right_wheel_name">right_wheel_joint</param>
<param name="serial_device">/dev/ttyUSB_ARDUINO</param>
<param name="baud_rate">57600</param>
<param name="timeout">1000</param>
<param name="enc_ticks_per_rev">585</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>
</robot>