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" rpy="0 0 0"/>
42 <inertia izz="0.014021" ixy="0.0" ixz="0.0" iyy="0.012708" iyz="0.0" ixx="0.0046875"/>
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 <cylinder radius="0.008" length="0.17"/>
115 <origin xyz="0 0 0.085" rpy="0 0 0"/>
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"/>
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"/>
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"/>
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"/>
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"/>
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"/>
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"/>
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}"/>
167 <xacro:macro name="wheel" params="pos side xyz rpy">
168 <link name="${pos}_${side}_wheel">
170 <origin xyz="0 0 0" rpy="0 0 0"/>
172 <mesh filename="package://wild_thumper/meshes/wheel_${side}.stl" />
176 <origin xyz="0 0 0" rpy="${PI/2} 0 0"/>
178 <cylinder radius="0.06" length="0.06"/>
182 <origin xyz="0 0 0" rpy="0 0 0"/>
184 <inertia ixx="0.00024" ixy="0" ixz="0" iyy="0.00036" iyz="0" izz="0.00024"/>
188 <gazebo reference="${pos}_${side}_wheel">
191 <kp value="1000000000000.0" />
193 <fdir1 value="0 1 0"/>
194 <minDepth>0.005</minDepth>
197 <joint name="${pos}_${side}_wheel_joint" type="continuous">
198 <parent link="base_link"/>
199 <child link="${pos}_${side}_wheel"/>
201 <origin xyz="${xyz}" rpy="${rpy}"/>
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>
209 <actuator name="{pos}_${side}_wheel_motor">
210 <mechanicalReduction>1</mechanicalReduction>
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" />
221 <plugin name="gazebo_ros_control" filename="libgazebo_ros_control.so">
222 <robotNamespace>/</robotNamespace>
223 <robotSimType>gazebo_ros_control/DefaultRobotHWSim</robotSimType>
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>
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>
249 <resolution>1</resolution>
250 <min_angle>-${fov/2}</min_angle>
251 <max_angle>${fov/2}</max_angle>
255 <resolution>1</resolution>
256 <min_angle>-${fov/2}</min_angle>
257 <max_angle>${fov/2}</max_angle>
261 <min>${minRange}</min>
262 <max>${maxRange}</max>
263 <resolution>0.01</resolution>
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>
273 <radiation>${radiation}</radiation>
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" />
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>
291 <samples>360</samples>
292 <resolution>1</resolution>
293 <min_angle>-3.12413907051</min_angle>
294 <max_angle>3.14159274101</max_angle>
300 <resolution>0.01</resolution>
303 <type>gaussian</type>
305 <stddev>0.01</stddev>
308 <plugin name="gazebo_ros_head_rplidar_a2_controller" filename="libgazebo_ros_laser.so">
309 <topicName>/scan</topicName>
310 <frameName>lidar</frameName>