]> defiant.homedns.org Git - ros_wild_thumper.git/blob - urdf/wild_thumper.urdf.xacro
fix some urdf inertias
[ros_wild_thumper.git] / urdf / wild_thumper.urdf.xacro
1 <?xml version="1.0"?>
2 <robot name="wild_thumper" xmlns:xacro="http://ros.org/wiki/xacro">
3         <xacro:property name="PI" value="3.1415926535897931" />
4
5         <material name="wtgrey">
6                 <color rgba="0.5 0.5 0.5 0.5"/>
7         </material>
8         <material name="wtred">
9                 <color rgba="1 0 0 1"/>
10         </material>
11         <material name="wtblack">
12                 <color rgba="0 0 0 1"/>
13         </material>
14         <material name="wtgreen">
15                 <color rgba="0 1 0 0.8"/>
16         </material>
17
18         <link name="base_footprint">
19                 <visual>
20                         <geometry>
21                                 <box size="0.28 0.31 0.000001"/>
22                         </geometry>
23                         <material name="wtgrey"/>
24                 </visual>
25         </link>
26
27         <link name="base_link">
28                 <collision>
29                         <geometry>
30                                 <box size="0.23 0.12 0.09"/>
31                         </geometry>
32                 </collision>
33                 <visual>
34                         <origin xyz="-0.00275 0 0" rpy="0 0 0"/>
35                         <geometry>
36                                 <mesh filename="package://wild_thumper/meshes/wild_thumper_4wd.stl" />
37                         </geometry>
38                 </visual>
39                 <inertial>
40                         <origin xyz="-0.00275 0 0" rpy="0 0 0"/>
41                         <mass value="2.5"/>
42                         <inertia izz="0.014021" ixy="0.0" ixz="0.0" iyy="0.012708" iyz="0.0" ixx="0.0046875"/>
43                 </inertial>
44         </link>
45
46         <link name="base_imu_link">
47                 <visual>
48                         <geometry>
49                                 <box size="0.041 0.028 0.002"/>
50                         </geometry>
51                         <material name="wtred"/>
52                 </visual>
53         </link>
54
55         <link name="mounting_plate">
56                 <visual>
57                         <geometry>
58                                 <box size="0.23 0.12 0.001"/>
59                         </geometry>
60                 </visual>
61         </link>
62
63         <link name="lidar">
64                 <visual>
65                         <geometry>
66                                 <mesh filename="package://wild_thumper/meshes/rplidar_a2.stl" scale="0.001 0.001 0.001"/>
67                         </geometry>
68                         <origin xyz="0.0 0.0 0" rpy="0 0 0"/>
69                         <material name="wtblack"/>
70                 </visual>
71         </link>
72
73         <link name="sonar_forward_left">
74                 <visual>
75                         <geometry>
76                                 <box size="0.016 0.044 0.02"/>
77                         </geometry>
78                         <origin xyz="${0.016/2} 0 0" rpy="0 0 0"/>
79                         <material name="wtgreen"/>
80                 </visual>
81         </link>
82
83         <link name="sonar_forward_right">
84                 <visual>
85                         <geometry>
86                                 <box size="0.016 0.044 0.02"/>
87                         </geometry>
88                         <origin xyz="${0.016/2} 0 0" rpy="0 0 0"/>
89                         <material name="wtgreen"/>
90                 </visual>
91         </link>
92
93         <link name="sonar_backward">
94                 <visual>
95                         <geometry>
96                                 <box size="0.016 0.044 0.02"/>
97                         </geometry>
98                         <origin xyz="${0.016/2} 0 0" rpy="0 0 0"/>
99                         <material name="wtgreen"/>
100                 </visual>
101         </link>
102
103         <link name="antenna">
104                 <visual>
105                         <geometry>
106                                 <cylinder radius="0.006" length="0.165"/>
107                         </geometry>
108                         <origin xyz="0 0 0.0825" rpy="0 0 0"/>
109                         <material name="wtblack"/>
110                 </visual>
111                 <collision>
112                         <geometry>
113                                 <cylinder radius="0.008" length="0.17"/>
114                         </geometry>
115                         <origin xyz="0 0 0.085" rpy="0 0 0"/>
116                 </collision>
117         </link>
118
119         <joint name="base_link_joint" type="fixed">
120                 <parent link="base_footprint"/>
121                 <child link="base_link"/>
122                 <origin xyz="0.0 0.0 0.082" rpy="0 0 0"/>
123         </joint>
124
125         <joint name="mounting_plate_joint" type="fixed">
126                 <parent link="base_link"/>
127                 <child link="mounting_plate"/>
128                 <origin xyz="0.0 0.0 0.044" rpy="0 0 0"/>
129         </joint>
130
131         <joint name="imu_joint" type="fixed">
132                 <parent link="mounting_plate"/>
133                 <child link="base_imu_link"/>
134                 <origin xyz="0.06 -0.03 0.058" rpy="0 0 0"/>
135         </joint>
136
137         <joint name="sonar_forward_left_joint" type="fixed">
138                 <parent link="mounting_plate"/>
139                 <child link="sonar_forward_left"/>
140                 <origin xyz="0.115 0.05 -0.012" rpy="0 ${-5*PI/180} 0"/>
141         </joint>
142
143         <joint name="sonar_forward_right_joint" type="fixed">
144                 <parent link="mounting_plate"/>
145                 <child link="sonar_forward_right"/>
146                 <origin xyz="0.115 -0.05 -0.012" rpy="0 ${-5*PI/180} 0"/>
147         </joint>
148
149         <joint name="sonar_backward_joint" type="fixed">
150                 <parent link="mounting_plate"/>
151                 <child link="sonar_backward"/>
152                 <origin xyz="-0.115 0.0 -0.012" rpy="0 ${-175*PI/180} 0"/>
153         </joint>
154
155         <joint name="antenna_joint" type="fixed">
156                 <parent link="mounting_plate"/>
157                 <child link="antenna"/>
158                 <origin xyz="0.011 0.05 0" rpy="0 0 0"/>
159         </joint>
160
161         <joint name="lidar_joint" type="fixed">
162                 <parent link="mounting_plate"/>
163                 <child link="lidar"/>
164                 <origin xyz="0.075 0.01 ${0.0408/2}" rpy="0 0 ${-110*PI/180}"/>
165         </joint>
166
167         <xacro:macro name="wheel" params="pos side xyz rpy">   
168                 <link name="${pos}_${side}_wheel">
169                         <visual>
170                                 <origin xyz="0 0 0" rpy="0 0 0"/>
171                                 <geometry>
172                                         <mesh filename="package://wild_thumper/meshes/wheel_${side}.stl" />
173                                 </geometry>
174                         </visual>
175                         <collision>
176                                 <origin xyz="0 0 0" rpy="${PI/2} 0 0"/>
177                                 <geometry>
178                                         <cylinder radius="0.06" length="0.06"/>
179                                 </geometry>
180                         </collision>
181                         <inertial>
182                                 <origin xyz="0 0 0" rpy="0 0 0"/>
183                                 <mass value="0.2"/>
184                                 <inertia ixx="0.00024" ixy="0" ixz="0" iyy="0.00036" iyz="0" izz="0.00024"/>
185                         </inertial>
186                 </link>
187
188                 <gazebo reference="${pos}_${side}_wheel">
189                         <mu1 value="1.0"/>
190                         <mu2 value="0.2"/>
191                         <kp value="1000000000000.0" />
192                         <kd value="1.0" />
193                         <fdir1 value="0 1 0"/>
194                         <minDepth>0.005</minDepth>
195                 </gazebo>
196
197                 <joint name="${pos}_${side}_wheel_joint" type="continuous">
198                         <parent link="base_link"/>
199                         <child link="${pos}_${side}_wheel"/>
200                         <axis xyz="0 1 0"/>
201                         <origin xyz="${xyz}" rpy="${rpy}"/>
202                 </joint>
203
204                 <transmission name="${pos}_${side}_wheel_trans" type="SimpleTransmission">
205                         <type>transmission_interface/SimpleTransmission</type>
206                         <joint name="${pos}_${side}_wheel_joint">
207                                 <hardwareInterface>VelocityJointInterface</hardwareInterface>
208                         </joint>
209                         <actuator name="{pos}_${side}_wheel_motor">
210                                 <mechanicalReduction>1</mechanicalReduction>
211                         </actuator>
212                 </transmission>
213         </xacro:macro>
214
215         <xacro:wheel pos="rear" side="left"   xyz="-0.07525  0.12 -0.025" rpy="${-5*PI/180} 0 0" />
216         <xacro:wheel pos="rear" side="right"  xyz="-0.07525 -0.12 -0.025" rpy="${5*PI/180} 0 0" />
217         <xacro:wheel pos="front" side="left"  xyz=" 0.07525  0.12 -0.025" rpy="${-5*PI/180} 0 0" />
218         <xacro:wheel pos="front" side="right" xyz=" 0.07525 -0.12 -0.025" rpy="${5*PI/180} 0 0" />
219
220         <gazebo>
221                 <plugin name="gazebo_ros_control" filename="libgazebo_ros_control.so">
222                         <robotNamespace>/</robotNamespace>
223                         <robotSimType>gazebo_ros_control/DefaultRobotHWSim</robotSimType>
224                 </plugin>
225
226                 <plugin name="imu_controller" filename="libgazebo_ros_imu.so">
227                         <alwaysOn>true</alwaysOn>
228                         <updateRate>20.0</updateRate>
229                         <bodyName>base_imu_link</bodyName>
230                         <topicName>imu</topicName>
231                         <gaussianNoise>0.05</gaussianNoise>
232                         <frameName>base_imu_link</frameName>
233                         <xyzOffsets>0 0 0</xyzOffsets>
234                         <rpyOffset>0 0 0</rpyOffset>
235                         <serviceName>/default_imu</serviceName>
236                 </plugin>
237         </gazebo>
238
239         <xacro:macro name="range_sensor" params="name ros_topic update_rate minRange maxRange fov radiation">
240                 <gazebo reference="${name}">
241                         <sensor type="ray" name="${name}_sensor">
242                                 <pose>0 0 0 0 0 0</pose>
243                                 <update_rate>${update_rate}</update_rate>
244                                 <visualize>false</visualize>
245                                 <ray>
246                                         <scan>
247                                                 <horizontal>
248                                                         <samples>5</samples>
249                                                         <resolution>1</resolution>
250                                                         <min_angle>-${fov/2}</min_angle>
251                                                         <max_angle>${fov/2}</max_angle>
252                                                 </horizontal>
253                                                 <vertical>
254                                                         <samples>5</samples>
255                                                         <resolution>1</resolution>
256                                                         <min_angle>-${fov/2}</min_angle>
257                                                         <max_angle>${fov/2}</max_angle>
258                                                 </vertical>
259                                         </scan>
260                                         <range>
261                                                 <min>${minRange}</min>
262                                                 <max>${maxRange}</max>
263                                                 <resolution>0.01</resolution>
264                                         </range>
265                                 </ray>
266                                 <plugin filename="libgazebo_ros_range.so" name="gazebo_ros_range">
267                                         <gaussianNoise>0.005</gaussianNoise>
268                                         <alwaysOn>true</alwaysOn>
269                                         <updateRate>${update_rate}</updateRate>
270                                         <topicName>${ros_topic}</topicName>
271                                         <frameName>${name}</frameName>
272                                         <fov>${fov}</fov>
273                                         <radiation>${radiation}</radiation>
274                                 </plugin>
275                         </sensor>
276                 </gazebo>
277         </xacro:macro>
278
279         <xacro:range_sensor name="sonar_forward_left" ros_topic="range_forward_left" update_rate="10" minRange="0.04" maxRange="0.5" fov="${20*PI/180}" radiation="ultrasound" />
280         <xacro:range_sensor name="sonar_forward_right" ros_topic="range_forward_right" update_rate="10" minRange="0.04" maxRange="0.5" fov="${20*PI/180}" radiation="ultrasound" />
281         <xacro:range_sensor name="sonar_backward" ros_topic="range_backward" update_rate="10" minRange="0.04" maxRange="0.5" fov="${20*PI/180}" radiation="ultrasound" />
282
283         <gazebo reference="lidar">
284                 <sensor type="ray" name="head_rplidar_a2_sensor">
285                         <pose>0 0 0 0 0 0</pose>
286                         <visualize>false</visualize>
287                         <update_rate>12</update_rate>
288                         <ray>
289                                 <scan>
290                                         <horizontal>
291                                                 <samples>360</samples>
292                                                 <resolution>1</resolution>
293                                                 <min_angle>-3.12413907051</min_angle>
294                                                 <max_angle>3.14159274101</max_angle>
295                                         </horizontal>
296                                 </scan>
297                                 <range>
298                                         <min>0.20</min>
299                                         <max>16.0</max>
300                                         <resolution>0.01</resolution>
301                                 </range>
302                                 <noise>
303                                         <type>gaussian</type>
304                                         <mean>0.0</mean>
305                                         <stddev>0.01</stddev>
306                                 </noise>
307                         </ray>
308                         <plugin name="gazebo_ros_head_rplidar_a2_controller" filename="libgazebo_ros_laser.so">
309                                 <topicName>/scan</topicName>
310                                 <frameName>lidar</frameName>
311                         </plugin>
312                 </sensor>
313         </gazebo>
314 </robot>