-
-
Notifications
You must be signed in to change notification settings - Fork 95
/
Copy pathdiffbot.urdf.xacro
74 lines (55 loc) · 2.92 KB
/
diffbot.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
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
<?xml version="1.0"?>
<robot xmlns:xacro="http://www.ros.org/wiki/xacro" name="diffbot">
<xacro:property name="package_name" value="diffbot_description"/>
<xacro:property name="robot_name" value="diffbot"/>
<xacro:include filename="$(find ${package_name})/urdf/include/common_macros.urdf.xacro" />
<xacro:include filename="$(find ${package_name})/urdf/include/diffbot_caster_macro.urdf.xacro" />
<xacro:include filename="$(find ${package_name})/urdf/include/common_sensors.xacro" />
<xacro:include filename="$(find ${package_name})/urdf/include/robot.gazebo.xacro" />
<xacro:property name="caster_wheel_yaml" value="$(find ${package_name})/config/${robot_name}/caster_wheel.yaml" />
<xacro:property name="caster_wheel_props" value="${xacro.load_yaml(caster_wheel_yaml)}"/>
<xacro:property name="front_wheel_yaml" value="$(find ${package_name})/config/${robot_name}/front_wheel.yaml" />
<xacro:property name="front_wheel_props" value="${xacro.load_yaml(front_wheel_yaml)}"/>
<xacro:property name="motor_yaml" value="$(find ${package_name})/config/${robot_name}/motor.yaml" />
<xacro:property name="motor_props" value="${xacro.load_yaml(motor_yaml)}"/>
<xacro:property name="base_yaml" value="$(find ${package_name})/config/${robot_name}/base.yaml" />
<xacro:property name="base_props" value="${xacro.load_yaml(base_yaml)}"/>
<xacro:property name="sensor_yaml" value="$(find ${package_name})/config/${robot_name}/sensors.yaml" />
<xacro:property name="sensor_prop" value="${xacro.load_yaml(sensor_yaml)}"/>
<!-- Footprint link -->
<xacro:footprint wheel_props="${front_wheel_props}" />
<!-- Base link -->
<xacro:base base_prop="${base_props}" mesh="${base_props['base']['mesh']}" >
<origin xyz="0 0 0" rpy="0 0 0" />
</xacro:base>
<!-- Back Caster Wheel -->
<xacro:caster_wheel prefix="rear" reflect="-1"
wheel_props="${caster_wheel_props}">
</xacro:caster_wheel>
<!-- Front Wheels -->
<xacro:wheel prefix="front_right" reflect="-1"
wheel_props="${front_wheel_props}"
base_props="${base_props}" >
</xacro:wheel>
<xacro:wheel prefix="front_left" reflect="1"
wheel_props="${front_wheel_props}"
base_props="${base_props}" >
</xacro:wheel>
<!-- Motors -->
<xacro:motor prefix="right" reflect="-1"
motor_props="${motor_props}"
base_props="${base_props}" >
</xacro:motor>
<xacro:motor prefix="left" reflect="1"
motor_props="${motor_props}"
base_props="${base_props}" >
</xacro:motor>
<!-- Sensors -->
<xacro:laser prefix="rplidar" parent_link="base_link"
sensor_prop="${sensor_prop}"
enable_gpu="${sensor_prop['laser']['enable_gpu']}">
</xacro:laser>
<!-- Gazebo -->
<xacro:gazebo_ros_control robotNamespace="/diffbot">
</xacro:gazebo_ros_control>
</robot>