-
Notifications
You must be signed in to change notification settings - Fork 12
/
jackal.urdf.xacro
227 lines (200 loc) · 7.6 KB
/
jackal.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
190
191
192
193
194
195
196
197
198
199
200
201
202
203
204
205
206
207
208
209
210
211
212
213
214
215
216
217
218
219
220
221
222
223
224
225
226
227
<?xml version="1.0"?>
<robot name="jackal" xmlns:xacro="http://www.ros.org/wiki/xacro">
<xacro:property name="PI" value="3.1415926535897931" />
<xacro:property name="wheelbase" value="0.262" />
<xacro:property name="track" value="0.37559" />
<xacro:property name="wheel_vertical_offset" value="0.0345" />
<xacro:property name="footprint_vertical_offset" value="-0.0655" />
<xacro:property name="wheel_radius" value="0.098" />
<xacro:property name="wheel_width" value="0.040" />
<xacro:property name="chassis_length" value="0.420" />
<xacro:property name="chassis_width" value="0.310" />
<xacro:property name="chassis_height" value="0.184" />
<xacro:property name="dummy_inertia" value="1e-09"/>
<xacro:property name="mount_spacing" value="0.120" />
<material name="dark_grey"><color rgba="0.2 0.2 0.2 1.0" /></material>
<material name="light_grey"><color rgba="0.4 0.4 0.4 1.0" /></material>
<material name="yellow"><color rgba="0.8 0.8 0.0 1.0" /></material>
<material name="black"><color rgba="0.15 0.15 0.15 1.0" /></material>
<xacro:macro name="wheel" params="prefix *joint_pose">
<link name="${prefix}_wheel_link">
<visual>
<origin xyz="0 0 0" rpy="${PI/2} 0 0"/>
<geometry>
<mesh filename="package://jackal_description/meshes/jackal-wheel.stl"/>
</geometry>
<material name="black" />
</visual>
<collision>
<origin xyz="0 0 0" rpy="${PI/2} 0 0"/>
<geometry>
<cylinder radius="${wheel_radius}" length="${wheel_width}"/>
</geometry>
</collision>
<inertial>
<origin xyz="0 0 0" rpy="0 0 0"/>
<mass value="0.477"/>
<inertia
ixx="0.0013" ixy="0" ixz="0"
iyy="0.0024" iyz="0"
izz="0.0013"/>
</inertial>
</link>
<gazebo reference="${prefix}_wheel_link">
<material>Gazebo/DarkGrey</material>
</gazebo>
<joint name="${prefix}_wheel" type="continuous">
<parent link="chassis_link"/>
<child link="${prefix}_wheel_link" />
<xacro:insert_block name="joint_pose" />
<axis xyz="0 1 0" />
</joint>
<!-- In reality, Jackal has only two motors, one per side. However, it's more
straightforward for Gazebo to simulate as if there's an actuator per wheel. -->
<transmission name="${prefix}_wheel_trans">
<type>transmission_interface/SimpleTransmission</type>
<joint name="${prefix}_wheel">
<hardwareInterface>VelocityJointInterface</hardwareInterface>
</joint>
<actuator name="${prefix}_actuator">
<mechanicalReduction>1</mechanicalReduction>
</actuator>
</transmission>
</xacro:macro>
<xacro:wheel prefix="front_left">
<origin xyz="${wheelbase/2} ${track/2} ${wheel_vertical_offset}" rpy="0 0 0" />
</xacro:wheel>
<xacro:wheel prefix="front_right">
<origin xyz="${wheelbase/2} ${-track/2} ${wheel_vertical_offset}" rpy="0 0 0" />
</xacro:wheel>
<xacro:wheel prefix="rear_left">
<origin xyz="${-wheelbase/2} ${track/2} ${wheel_vertical_offset}" rpy="0 0 0" />
</xacro:wheel>
<xacro:wheel prefix="rear_right">
<origin xyz="${-wheelbase/2} ${-track/2} ${wheel_vertical_offset}" rpy="0 0 0" />
</xacro:wheel>
<link name="base_link"></link>
<joint name="base_link_joint" type="fixed">
<origin xyz="0 0 0" rpy="0 0 0" />
<parent link="base_link"/>
<child link="chassis_link" />
</joint>
<link name="chassis_link">
<visual>
<origin xyz="0 0 ${footprint_vertical_offset}" rpy="${PI/2} 0 ${PI/2}"/>
<geometry>
<mesh filename="package://jackal_description/meshes/jackal-base.stl"/>
</geometry>
<material name="dark_grey" />
</visual>
<collision>
<origin xyz="0 0 ${chassis_height/2}"/>
<geometry>
<box size="${chassis_length} ${chassis_width} ${chassis_height}"/>
</geometry>
</collision>
<inertial>
<!-- Center of mass -->
<origin xyz="0.012 0.002 0.067" rpy="0 0 0"/>
<mass value="16.523"/>
<!-- Moments of inertia: ( chassis without wheels ) -->
<inertia
ixx="0.3136" ixy="-0.0008" ixz="0.0164"
iyy="0.3922" iyz="-0.0009"
izz="0.4485"/>
</inertial>
</link>
<link name="fenders_link">
<visual>
<origin xyz="0 0 ${footprint_vertical_offset}" rpy="${PI/2} 0 ${PI/2}"/>
<geometry>
<mesh filename="package://jackal_description/meshes/jackal-fenders.stl"/>
</geometry>
<material name="yellow" />
</visual>
</link>
<joint name="fenders_joint" type="fixed">
<parent link="chassis_link" />
<child link="fenders_link" />
</joint>
<!-- TODO: Make this internal_imu_link or something, and use a mixed-in xacro
to supply the joint between it and imu_link. This is important so that imu_link
always points to the "active" IMU. When an upgrade IMU is connected, the
internal_imu_link should remain, but imu_link should point to the upgrade one. -->
<link name="imu_link">
<inertial>
<mass value="0.001"/>
<origin xyz="0 0 0" rpy="0 0 0"/>
<inertia ixx="${dummy_inertia}" ixy="0.0" ixz="0.0" iyy="${dummy_inertia}" iyz="0.0" izz="${dummy_inertia}"/>
</inertial>
</link>
<joint name="imu_joint" type="fixed">
<parent link="chassis_link" />
<child link="imu_link" />
</joint>
<!-- TODO: Same note as applies to imu_link -->
<link name="navsat_link">
<visual>
<geometry>
<cylinder radius="0.026" length="0.016" />
</geometry>
<origin xyz="0 0 0.008" />
<material name="black" />
</visual>
</link>
<joint name="navsat_joint" type="fixed">
<parent link="chassis_link" />
<child link="navsat_link" />
<origin xyz="-0.180 0.126 0.1815" />
</joint>
<link name="mid_mount"></link>
<joint name="mid_mount_joint" type="fixed">
<parent link="chassis_link" />
<child link="mid_mount" />
<origin xyz="0 0 ${chassis_height}" />
</joint>
<link name="rear_mount"></link>
<joint name="rear_mount_joint" type="fixed">
<parent link="mid_mount" />
<child link="rear_mount" />
<origin xyz="${-mount_spacing} 0 0" />
</joint>
<link name="front_mount"></link>
<joint name="front_mount_joint" type="fixed">
<parent link="mid_mount" />
<child link="front_mount" />
<origin xyz="${mount_spacing} 0 0" />
</joint>
<!-- Bring in simulation data for Gazebo. -->
<xacro:include filename="$(find jackal_description)/urdf/jackal.gazebo" />
<!-- Optional standard accessories, including their simulation data. The rendering
of these into the final description is controlled by optenv variables, which
default each one to off.-->
<xacro:include filename="$(find jackal_description)/urdf/accessories.urdf.xacro" />
<!-- Velodyne URDF, plugin, etc -->
<xacro:include filename="$(find jackal_exploration)/urdf/VLP-16.urdf.xacro"/>
<VLP-16 parent="front_mount" name="velodyne" topic="/velodyne_points">
<origin xyz="0 0 0.052" rpy="0 0 0" />
</VLP-16>
<!-- Velodyne mount stuff -->
<link name="velodyne_mount">
<visual>
<origin xyz="0 0 0" rpy="0.0 0.0 0.0" />
<geometry>
<mesh filename="package://jackal_exploration/urdf/velodyne_mount.stl"/>
</geometry>
<material name="aluminum" >
<color rgba="0.45 0.45 0.45 1"/>
</material>
</visual>
</link>
<joint name="velodyne_mount_joint" type="fixed">
<parent link="velodyne_base_link" />
<child link="velodyne_mount" />
<origin xyz="0 0 0" />
</joint>
<!-- Optional custom includes. -->
<xacro:if value="$(optenv JACKAL_URDF_EXTRAS 0)">
<xacro:include filename="$(env JACKAL_URDF_EXTRAS)" />
</xacro:if>
</robot>