]> defiant.homedns.org Git - ros_wild_thumper.git/blob - urdf/wild_thumper.urdf.xacro
Set sonar angle to 5° degree
[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         <xacro:include filename="$(find hector_sensors_description)/urdf/asus_camera.urdf.xacro" />
5
6         <link name="base_footprint">
7                 <visual>
8                         <geometry>
9                                 <box size="0.28 0.31 0.000001"/>
10                         </geometry>
11                         <material name="grey">
12                                 <color rgba="0.5 0.5 0.5 0.5"/>
13                         </material>
14                 </visual>
15         </link>
16
17         <link name="base_link">
18                 <collision>
19                         <geometry>
20                                 <box size="0.23 0.18 0.09"/>
21                         </geometry>
22                 </collision>
23                 <visual>
24                         <origin xyz="-0.00275 0 0" rpy="0 0 0"/>
25                         <geometry>
26                                 <mesh filename="package://wild_thumper/meshes/wild_thumper_4wd.stl" />
27                         </geometry>
28                 </visual>
29                 <inertial>
30                         <origin xyz="-0.00275 0 -0.02" rpy="0 0 0"/>
31                         <mass value="2.5"/>
32                         <inertia ixx="1.0" ixy="0.0" ixz="0.0" iyy="1.0" iyz="0.0" izz="1.0"/>
33                 </inertial>
34         </link>
35
36         <link name="base_imu_link">
37                 <visual>
38                         <geometry>
39                                 <box size="0.041 0.028 0.002"/>
40                         </geometry>
41                         <material name="red">
42                                 <color rgba="1 0 0 1"/>
43                         </material>
44                 </visual>
45         </link>
46
47         <link name="mounting_plate">
48                 <visual>
49                         <geometry>
50                                 <box size="0.23 0.12 0.001"/>
51                         </geometry>
52                 </visual>
53         </link>
54
55         <xacro:asus_camera name="camera" parent="mounting_plate">
56                 <origin xyz="0.107 0.0 0.04" rpy="0 0 0"/>
57         </xacro:asus_camera>
58
59         <link name="sonar_forward_left">
60                 <visual>
61                         <geometry>
62                                 <box size="0.016 0.044 0.02"/>
63                         </geometry>
64                         <origin xyz="${0.016/2} 0 0" rpy="0 0 0"/>
65                         <material name="green">
66                                 <color rgba="0 1 0 0.8"/>
67                         </material>
68                 </visual>
69         </link>
70
71         <link name="sonar_forward_right">
72                 <visual>
73                         <geometry>
74                                 <box size="0.016 0.044 0.02"/>
75                         </geometry>
76                         <origin xyz="${0.016/2} 0 0" rpy="0 0 0"/>
77                         <material name="green">
78                                 <color rgba="0 1 0 0.8"/>
79                         </material>
80                 </visual>
81         </link>
82
83         <link name="sonar_backward">
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="green">
90                                 <color rgba="0 1 0 0.8"/>
91                         </material>
92                 </visual>
93         </link>
94
95         <link name="ir_left">
96                 <visual>
97                         <geometry>
98                                 <box size="0.015 0.015 0.046"/>
99                         </geometry>
100                         <origin xyz="${-0.015/2} 0 0" rpy="0 0 0"/>
101                         <material name="black">
102                                 <color rgba="0 0 0 1"/>
103                         </material>
104                 </visual>
105         </link>
106
107         <link name="ir_right">
108                 <visual>
109                         <geometry>
110                                 <box size="0.015 0.015 0.046"/>
111                         </geometry>
112                         <origin xyz="${-0.015/2} 0 0" rpy="0 0 0"/>
113                         <material name="black">
114                                 <color rgba="0 0 0 1"/>
115                         </material>
116                 </visual>
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="ir_left_joint" type="fixed">
156                 <parent link="mounting_plate"/>
157                 <child link="ir_left"/>
158                 <origin xyz="0.0 ${0.072+0.015} -0.045" rpy="0 0 ${PI/2}"/>
159         </joint>
160
161         <joint name="ir_right_joint" type="fixed">
162                 <parent link="mounting_plate"/>
163                 <child link="ir_right"/>
164                 <origin xyz="0.0 ${-0.072-0.015} -0.045" rpy="0 0 ${-PI/2}"/>
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.1"/>
184                                 <inertia ixx="0.005" ixy="0" ixz="0" iyy="0.005" iyz="0" izz="0.005"/>
185                         </inertial>
186                 </link>
187
188                 <gazebo reference="${pos}_${side}_wheel">
189                         <mu1 value="1.0"/>
190                         <mu2 value="1.0"/>
191                         <kp value="1000000.0" />
192                         <kd value="1.0" />
193                         <fdir1 value="1 0 0"/>
194                 </gazebo>
195
196                 <joint name="${pos}_${side}_wheel_joint" type="continuous">
197                         <parent link="base_link"/>
198                         <child link="${pos}_${side}_wheel"/>
199                         <axis xyz="0 1 0"/>
200                         <origin xyz="${xyz}" rpy="${rpy}"/>
201                 </joint>
202
203                 <transmission name="${pos}_${side}_wheel_trans" type="SimpleTransmission">
204                         <type>transmission_interface/SimpleTransmission</type>
205                         <joint name="${pos}_${side}_wheel_joint">
206                                 <hardwareInterface>VelocityJointInterface</hardwareInterface>
207                         </joint>
208                         <actuator name="{pos}_${side}_wheel_motor">
209                                 <mechanicalReduction>1</mechanicalReduction>
210                         </actuator>
211                 </transmission>
212         </xacro:macro>
213
214         <xacro:wheel pos="rear" side="left"   xyz="-0.07525  0.12 -0.025" rpy="${-5*PI/180} 0 0" />
215         <xacro:wheel pos="rear" side="right"  xyz="-0.07525 -0.12 -0.025" rpy="${5*PI/180} 0 0" />
216         <xacro:wheel pos="front" side="left"  xyz=" 0.07525  0.12 -0.025" rpy="${-5*PI/180} 0 0" />
217         <xacro:wheel pos="front" side="right" xyz=" 0.07525 -0.12 -0.025" rpy="${5*PI/180} 0 0" />
218
219         <gazebo>
220                 <plugin name="gazebo_ros_control" filename="libgazebo_ros_control.so">
221                         <robotNamespace>/</robotNamespace>
222                         <robotSimType>gazebo_ros_control/DefaultRobotHWSim</robotSimType>
223                 </plugin>
224
225                 <plugin name="imu_controller" filename="libgazebo_ros_imu.so">
226                         <alwaysOn>true</alwaysOn>
227                         <updateRate>20.0</updateRate>
228                         <bodyName>base_imu_link</bodyName>
229                         <topicName>imu</topicName>
230                         <gaussianNoise>0.05</gaussianNoise>
231                         <frameName>base_imu_link</frameName>
232                         <xyzOffsets>0 0 0</xyzOffsets>
233                         <rpyOffset>0 0 0</rpyOffset>
234                         <serviceName>/default_imu</serviceName>
235                 </plugin>
236         </gazebo>
237
238         <xacro:macro name="range_sensor" params="name ros_topic update_rate minRange maxRange fov radiation">
239                 <gazebo reference="${name}">
240                         <sensor type="ray" name="${name}_sensor">
241                                 <pose>0 0 0 0 0 0</pose>
242                                 <update_rate>${update_rate}</update_rate>
243                                 <visualize>false</visualize>
244                                 <ray>
245                                         <scan>
246                                                 <horizontal>
247                                                         <samples>5</samples>
248                                                         <resolution>1</resolution>
249                                                         <min_angle>-${fov/2}</min_angle>
250                                                         <max_angle>${fov/2}</max_angle>
251                                                 </horizontal>
252                                                 <vertical>
253                                                         <samples>5</samples>
254                                                         <resolution>1</resolution>
255                                                         <min_angle>-${fov/2}</min_angle>
256                                                         <max_angle>${fov/2}</max_angle>
257                                                 </vertical>
258                                         </scan>
259                                         <range>
260                                                 <min>${minRange}</min>
261                                                 <max>${maxRange}</max>
262                                                 <resolution>0.01</resolution>
263                                         </range>
264                                 </ray>
265                                 <plugin filename="libgazebo_ros_range.so" name="gazebo_ros_range">
266                                         <gaussianNoise>0.005</gaussianNoise>
267                                         <alwaysOn>true</alwaysOn>
268                                         <updateRate>${update_rate}</updateRate>
269                                         <topicName>${ros_topic}</topicName>
270                                         <frameName>${name}</frameName>
271                                         <fov>${fov}</fov>
272                                         <radiation>${radiation}</radiation>
273                                 </plugin>
274                         </sensor>
275                 </gazebo>
276         </xacro:macro>
277
278         <xacro:range_sensor name="sonar_forward" ros_topic="range_forward" update_rate="10" minRange="0.04" maxRange="0.5" fov="${20*PI/180}" radiation="ultrasound" />
279         <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" />
280         <xacro:range_sensor name="ir_left" ros_topic="range_left" update_rate="10" minRange="0.04" maxRange="0.3" fov="${5*PI/180}" radiation="infrared" />
281         <xacro:range_sensor name="ir_right" ros_topic="range_right" update_rate="10" minRange="0.04" maxRange="0.3" fov="${5*PI/180}" radiation="infrared" />
282 </robot>