2 <robot name="wild_thumper" xmlns:xacro="http://ros.org/wiki/xacro">
3 <xacro:property name="PI" value="3.1415926535897931" />
5 <material name="wtgrey">
6 <color rgba="0.5 0.5 0.5 0.5"/>
8 <material name="wtred">
9 <color rgba="1 0 0 1"/>
11 <material name="wtblack">
12 <color rgba="0 0 0 1"/>
14 <material name="wtgreen">
15 <color rgba="0 1 0 0.8"/>
18 <link name="base_footprint">
21 <box size="0.28 0.31 0.000001"/>
23 <material name="wtgrey"/>
27 <link name="base_link">
30 <box size="0.23 0.12 0.09"/>
34 <origin xyz="-0.00275 0 0" rpy="0 0 0"/>
36 <mesh filename="package://wild_thumper/meshes/wild_thumper_4wd.stl" />
40 <origin xyz="-0.00275 0 -0.02" rpy="0 0 0"/>
42 <inertia ixx="0.012708" ixy="0.0" ixz="0.0" iyy="0.0084375" iyz="0.0" izz="0.017771"/>
46 <link name="base_imu_link">
49 <box size="0.041 0.028 0.002"/>
51 <material name="wtred"/>
55 <link name="mounting_plate">
58 <box size="0.23 0.12 0.001"/>
66 <mesh filename="package://wild_thumper/meshes/rplidar_a2.stl" scale="0.001 0.001 0.001"/>
68 <origin xyz="0.0 0.0 0" rpy="0 0 0"/>
69 <material name="wtblack"/>
73 <link name="sonar_forward_left">
76 <box size="0.016 0.044 0.02"/>
78 <origin xyz="${0.016/2} 0 0" rpy="0 0 0"/>
79 <material name="wtgreen"/>
83 <link name="sonar_forward_right">
86 <box size="0.016 0.044 0.02"/>
88 <origin xyz="${0.016/2} 0 0" rpy="0 0 0"/>
89 <material name="wtgreen"/>
93 <link name="sonar_backward">
96 <box size="0.016 0.044 0.02"/>
98 <origin xyz="${0.016/2} 0 0" rpy="0 0 0"/>
99 <material name="wtgreen"/>
103 <link name="antenna">
106 <cylinder radius="0.006" length="0.165"/>
108 <origin xyz="0 0 0.0825" rpy="0 0 0"/>
109 <material name="wtblack"/>
113 <joint name="base_link_joint" type="fixed">
114 <parent link="base_footprint"/>
115 <child link="base_link"/>
116 <origin xyz="0.0 0.0 0.082" rpy="0 0 0"/>
119 <joint name="mounting_plate_joint" type="fixed">
120 <parent link="base_link"/>
121 <child link="mounting_plate"/>
122 <origin xyz="0.0 0.0 0.044" rpy="0 0 0"/>
125 <joint name="imu_joint" type="fixed">
126 <parent link="mounting_plate"/>
127 <child link="base_imu_link"/>
128 <origin xyz="0.06 -0.03 0.058" rpy="0 0 0"/>
131 <joint name="sonar_forward_left_joint" type="fixed">
132 <parent link="mounting_plate"/>
133 <child link="sonar_forward_left"/>
134 <origin xyz="0.115 0.05 -0.012" rpy="0 ${-5*PI/180} 0"/>
137 <joint name="sonar_forward_right_joint" type="fixed">
138 <parent link="mounting_plate"/>
139 <child link="sonar_forward_right"/>
140 <origin xyz="0.115 -0.05 -0.012" rpy="0 ${-5*PI/180} 0"/>
143 <joint name="sonar_backward_joint" type="fixed">
144 <parent link="mounting_plate"/>
145 <child link="sonar_backward"/>
146 <origin xyz="-0.115 0.0 -0.012" rpy="0 ${-175*PI/180} 0"/>
149 <joint name="antenna_joint" type="fixed">
150 <parent link="mounting_plate"/>
151 <child link="antenna"/>
152 <origin xyz="0.011 0.0588 0" rpy="0 0 0"/>
155 <joint name="lidar_joint" type="fixed">
156 <parent link="mounting_plate"/>
157 <child link="lidar"/>
158 <origin xyz="0.075 0.01 ${0.0408/2}" rpy="0 0 ${-110*PI/180}"/>
161 <xacro:macro name="wheel" params="pos side xyz rpy">
162 <link name="${pos}_${side}_wheel">
164 <origin xyz="0 0 0" rpy="0 0 0"/>
166 <mesh filename="package://wild_thumper/meshes/wheel_${side}.stl" />
170 <origin xyz="0 0 0" rpy="${PI/2} 0 0"/>
172 <cylinder radius="0.06" length="0.06"/>
176 <origin xyz="0 0 0" rpy="0 0 0"/>
178 <inertia ixx="0.00024" ixy="0" ixz="0" iyy="0.00036" iyz="0" izz="0.00024"/>
182 <gazebo reference="${pos}_${side}_wheel">
185 <kp value="1000000000000.0" />
187 <fdir1 value="0 1 0"/>
188 <minDepth>0.005</minDepth>
191 <joint name="${pos}_${side}_wheel_joint" type="continuous">
192 <parent link="base_link"/>
193 <child link="${pos}_${side}_wheel"/>
195 <origin xyz="${xyz}" rpy="${rpy}"/>
198 <transmission name="${pos}_${side}_wheel_trans" type="SimpleTransmission">
199 <type>transmission_interface/SimpleTransmission</type>
200 <joint name="${pos}_${side}_wheel_joint">
201 <hardwareInterface>VelocityJointInterface</hardwareInterface>
203 <actuator name="{pos}_${side}_wheel_motor">
204 <mechanicalReduction>1</mechanicalReduction>
209 <xacro:wheel pos="rear" side="left" xyz="-0.07525 0.12 -0.025" rpy="${-5*PI/180} 0 0" />
210 <xacro:wheel pos="rear" side="right" xyz="-0.07525 -0.12 -0.025" rpy="${5*PI/180} 0 0" />
211 <xacro:wheel pos="front" side="left" xyz=" 0.07525 0.12 -0.025" rpy="${-5*PI/180} 0 0" />
212 <xacro:wheel pos="front" side="right" xyz=" 0.07525 -0.12 -0.025" rpy="${5*PI/180} 0 0" />
215 <plugin name="gazebo_ros_control" filename="libgazebo_ros_control.so">
216 <robotNamespace>/</robotNamespace>
217 <robotSimType>gazebo_ros_control/DefaultRobotHWSim</robotSimType>
220 <plugin name="imu_controller" filename="libgazebo_ros_imu.so">
221 <alwaysOn>true</alwaysOn>
222 <updateRate>20.0</updateRate>
223 <bodyName>base_imu_link</bodyName>
224 <topicName>imu</topicName>
225 <gaussianNoise>0.05</gaussianNoise>
226 <frameName>base_imu_link</frameName>
227 <xyzOffsets>0 0 0</xyzOffsets>
228 <rpyOffset>0 0 0</rpyOffset>
229 <serviceName>/default_imu</serviceName>
233 <xacro:macro name="range_sensor" params="name ros_topic update_rate minRange maxRange fov radiation">
234 <gazebo reference="${name}">
235 <sensor type="ray" name="${name}_sensor">
236 <pose>0 0 0 0 0 0</pose>
237 <update_rate>${update_rate}</update_rate>
238 <visualize>false</visualize>
243 <resolution>1</resolution>
244 <min_angle>-${fov/2}</min_angle>
245 <max_angle>${fov/2}</max_angle>
249 <resolution>1</resolution>
250 <min_angle>-${fov/2}</min_angle>
251 <max_angle>${fov/2}</max_angle>
255 <min>${minRange}</min>
256 <max>${maxRange}</max>
257 <resolution>0.01</resolution>
260 <plugin filename="libgazebo_ros_range.so" name="gazebo_ros_range">
261 <gaussianNoise>0.005</gaussianNoise>
262 <alwaysOn>true</alwaysOn>
263 <updateRate>${update_rate}</updateRate>
264 <topicName>${ros_topic}</topicName>
265 <frameName>${name}</frameName>
267 <radiation>${radiation}</radiation>
273 <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" />
274 <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" />
275 <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" />
276 <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" />
277 <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" />
279 <gazebo reference="lidar">
280 <sensor type="ray" name="head_rplidar_a2_sensor">
281 <pose>0 0 0 0 0 0</pose>
282 <visualize>false</visualize>
283 <update_rate>12</update_rate>
287 <samples>360</samples>
288 <resolution>1</resolution>
289 <min_angle>-3.12413907051</min_angle>
290 <max_angle>3.14159274101</max_angle>
296 <resolution>0.01</resolution>
299 <type>gaussian</type>
301 <stddev>0.01</stddev>
304 <plugin name="gazebo_ros_head_rplidar_a2_controller" filename="libgazebo_ros_laser.so">
305 <topicName>/scan</topicName>
306 <frameName>lidar</frameName>