-
Notifications
You must be signed in to change notification settings - Fork 83
/
racecar.xacro
128 lines (107 loc) · 3.53 KB
/
racecar.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
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
<?xml version="1.0"?>
<!-- A simple model of the racecar for rviz -->
<robot xmlns:xacro="http://www.ros.org/wiki/xacro" name="racecar">
<xacro:property name="wheelbase" value="0.325" />
<xacro:property name="width" value="0.2" />
<xacro:property name="height" value="0.1" />
<xacro:property name="ground_offset" value="0.04" />
<xacro:property name="wheel_radius" value="0.05" />
<xacro:property name="wheel_length" value="0.045" />
<xacro:property name="laser_distance_from_base_link" value="0.275" />
<xacro:property name="laser_height" value="0.05" />
<xacro:property name="laser_radius" value="0.026" />
<material name="black">
<color rgba="0.2 0.2 0.2 1."/>
</material>
<material name="blue">
<color rgba="0.3 0.57 1. 1."/>
</material>
<link name="base_link">
<visual>
<origin xyz="${wheelbase/2} 0 ${ground_offset+height/2}"/>
<geometry>
<box size="${wheelbase} ${width} ${height}"/>
</geometry>
<material name="blue"/>
</visual>
</link>
<joint name="base_to_laser_model" type="fixed">
<parent link="base_link"/>
<child link="laser_model"/>
<origin xyz="${laser_distance_from_base_link} 0 ${ground_offset+height+(laser_height/2)}"/>
</joint>
<link name="laser_model">
<visual>
<geometry>
<cylinder radius="${laser_radius}" length="${laser_height}"/>
</geometry>
<material name="black"/>
</visual>
</link>
<joint name="base_to_back_left_wheel" type="fixed">
<parent link="base_link"/>
<child link="back_left_wheel"/>
<origin xyz="0 ${(wheel_length+width)/2} ${wheel_radius}"/>
</joint>
<link name="back_left_wheel">
<visual>
<geometry>
<cylinder radius="${wheel_radius}" length="${wheel_length}"/>
</geometry>
<material name="black"/>
<origin rpy="${pi/2} 0 0"/>
</visual>
</link>
<joint name="base_to_back_right_wheel" type="fixed">
<parent link="base_link"/>
<child link="back_right_wheel"/>
<origin xyz="0 ${-(wheel_length+width)/2} ${wheel_radius}"/>
</joint>
<link name="back_right_wheel">
<visual>
<geometry>
<cylinder radius="${wheel_radius}" length="${wheel_length}"/>
</geometry>
<material name="black"/>
<origin rpy="${pi/2} 0 0"/>
</visual>
</link>
<joint name="base_to_front_left_hinge" type="fixed">
<parent link="base_link"/>
<child link="front_left_hinge"/>
<origin xyz="${wheelbase} ${(wheel_length+width)/2} ${wheel_radius}"/>
</joint>
<link name="front_left_hinge"/>
<joint name="front_left_hinge_to_wheel" type="continuous">
<parent link="front_left_hinge"/>
<child link="front_left_wheel"/>
</joint>
<link name="front_left_wheel">
<visual>
<geometry>
<cylinder radius="${wheel_radius}" length="${wheel_length}"/>
</geometry>
<material name="black"/>
<origin rpy="${pi/2} 0 0"/>
</visual>
</link>
<joint name="base_to_front_right_hinge" type="fixed">
<parent link="base_link"/>
<child link="front_right_hinge"/>
<origin xyz="${wheelbase} ${-(wheel_length+width)/2} ${wheel_radius}"/>
</joint>
<link name="front_right_hinge"/>
<joint name="front_right_hinge_to_wheel" type="continuous">
<parent link="front_right_hinge"/>
<child link="front_right_wheel"/>
</joint>
<link name="front_right_wheel">
<visual>
<geometry>
<cylinder radius="${wheel_radius}" length="${wheel_length}"/>
</geometry>
<material name="black"/>
<origin rpy="${pi/2} 0 0"/>
</visual>
</link>
</robot>