-
Notifications
You must be signed in to change notification settings - Fork 13
/
car.urdf.xacro
189 lines (150 loc) · 4.46 KB
/
car.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
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
129
130
131
132
133
134
135
136
137
138
139
140
141
142
143
144
145
146
147
148
149
150
151
152
153
154
155
156
157
158
159
160
161
162
163
164
165
166
167
168
169
170
171
172
173
174
175
176
177
178
179
180
181
182
183
184
185
186
187
188
189
<?xml version="1.0"?>
<robot name="car" xmlns:xacro="http://ros.org/wiki/xacro" >
<material name="blue">
<color rgba="0 0 0.8 1"/>
</material>
<material name="white">
<color rgba="1 1 1 1"/>
</material>
<xacro:property name="m" value="2" />
<xacro:property name="l1" value="0.5" />
<xacro:property name="b1" value="0.3" />
<xacro:property name="h1" value="0.07" />
<xacro:property name="r2" value="0.05" />
<link name="chassis">
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<box size="${l1} ${b1} ${h1}"/>
</geometry>
<material name="blue"/>
</visual>
<collision name="collision_chassis">
<geometry>
<box size="${l1} ${b1} ${h1}"/>
</geometry>
</collision>
<inertial>
<mass value="${m}"/>
<origin rpy="0 0 0" xyz="0 0 0"/>
<inertia ixx="${m*h1*b1/12.0}" ixy="0" ixz="0" iyy="${m*l1*h1/12.0}" iyz="0" izz="${m*l1*b1/12.0}"/>
</inertial>
<!-- caster wheel-->
<visual>
<origin rpy="0 0 0" xyz="${l1/2-r2} 0 -${r2}"/>
<geometry>
<sphere radius="${r2}"/>
</geometry>
</visual>
<collision name="caster_front_collision">
<origin rpy="0 0 0" xyz="${l1/2-r2} 0 -${r2}"/>
<geometry>
<sphere radius="${r2}"/>
</geometry>
<surface>
<friction>
<ode>
<mu>0</mu>
<mu2>0</mu2>
<slip1>1.0</slip1>
<slip2>1.0</slip2>
</ode>
</friction>
</surface>
</collision>
</link>
<xacro:property name="l3" value="0.04" />
<xacro:property name="r3" value="0.1" />
<xacro:property name="m3" value="0.2" />
<link name="right_wheel">
<visual>
<origin rpy="0 1.5707 1.5707" xyz="0 0 0"/>
<geometry>
<cylinder radius="${r3}" length="${l3}" />
</geometry>
<material name="white"/>
</visual>
<collision name="collision_right_wheel">
<origin rpy="0 1.5707 1.5707" xyz="0 0 0"/>
<geometry>
<cylinder radius="${r3}" length="${l3}" />
</geometry>
</collision>
<inertial>
<mass value="${m3}"/>
<origin rpy="0 1.5707 1.5707" xyz="0 0 0"/>
<inertia ixx="${m3*((3*r3*r3)+(l3*l3))/12.0}" ixy="0" ixz="0" iyy="${m3*((3*r3*r3)+(l3*l3))/12.0}" iyz="0" izz="${(m3*r3*r3)/2.0}"/>
</inertial>
</link>
<joint name="joint_right_wheel_chassis" type="continuous">
<origin rpy="0 0 0" xyz="-0.05 -${b1/2} 0"/>
<child link="right_wheel"/>
<parent link="chassis"/>
<axis xyz="0 1 0"/>
<limit effort="10000" velocity="1000"/>
<joint_properties damping="1.0" friction="1.0"/>
</joint>
<link name="left_wheel">
<visual>
<origin rpy="0 1.5707 1.5707" xyz="0 0 0"/>
<geometry>
<cylinder radius="${r3}" length="${l3}" />
</geometry>
<material name="white"/>
</visual>
<collision name="collision_left_wheel">
<origin rpy="0 1.5707 1.5707" xyz="0 0 0"/>
<geometry>
<cylinder radius="${r3}" length="${l3}" />
</geometry>
</collision>
<inertial>
<mass value="${m3}"/>
<origin rpy="0 1.5707 1.5707" xyz="0 0 0"/>
<inertia ixx="${m3*((3*r3*r3)+(l3*l3))/12.0}" ixy="0" ixz="0" iyy="${m3*((3*r3*r3)+(l3*l3))/12.0}" iyz="0" izz="${(m3*r3*r3)/2.0}"/>
</inertial>
</link>
<joint name="joint_left_wheel_chassis" type="continuous">
<origin rpy="0 0 0" xyz="-0.05 ${b1/2} 0"/>
<child link="left_wheel"/>
<parent link="chassis"/>
<axis xyz="0 1 0"/>
<limit effort="10000" velocity="1000"/>
<joint_properties damping="1.0" friction="1.0"/>
</joint>
<xacro:property name="mk" value="0.1" />
<xacro:property name="lk" value="0.05" />
<xacro:property name="bk" value="0.2" />
<xacro:property name="hk" value="0.05" />
<!-- Kinect Sensor -->
<link name="kinect">
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<box size="${lk} ${bk} ${hk}"/>
</geometry>
</visual>
<collision name="collision_kinect">
<geometry>
<box size="${lk} ${bk} ${hk}"/>
</geometry>
</collision>
<inertial>
<mass value="${mk}"/>
<origin rpy="0 0 0" xyz="0 0 0"/>
<inertia ixx="${mk*hk*bk/12.0}" ixy="0" ixz="0" iyy="${mk*lk*hk/12.0}" iyz="0" izz="${mk*lk*bk/12.0}"/>
</inertial>
</link>
<joint name="joint_kinect_chassis" type="fixed">
<origin rpy="0 0 0" xyz="${l1/2-lk/2} 0 ${h1/2+hk/2}"/>
<child link="kinect"/>
<parent link="chassis"/>
</joint>
<link name="kinect_link" />
<joint name="joint_kinect_link" type="fixed">
<origin rpy="-1.5707 0 -1.5707" xyz="${l1/2} 0 ${h1/2+hk/2}"/>
<child link="kinect_link"/>
<parent link="chassis"/>
</joint>
<xacro:include filename="$(find navros_pkg)/urdf/gazebo_plugins.urdf.xacro" />
</robot>