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" />
6 <link name="base_footprint">
9 <box size="0.28 0.31 0.000001"/>
11 <material name="grey">
12 <color rgba="0.5 0.5 0.5 0.5"/>
17 <link name="base_link">
20 <box size="0.23 0.18 0.09"/>
24 <origin xyz="-0.00275 0 0" rpy="0 0 0"/>
26 <mesh filename="package://wild_thumper/meshes/wild_thumper_4wd.stl" />
30 <origin xyz="-0.00275 0 -0.02" rpy="0 0 0"/>
32 <inertia ixx="1.0" ixy="0.0" ixz="0.0" iyy="1.0" iyz="0.0" izz="1.0"/>
36 <link name="base_imu_link">
39 <box size="0.041 0.028 0.002"/>
42 <color rgba="1 0 0 1"/>
47 <link name="mounting_plate">
50 <box size="0.23 0.12 0.001"/>
55 <xacro:asus_camera name="camera" parent="mounting_plate">
56 <origin xyz="0.107 0.0 0.04" rpy="0 0 0"/>
59 <link name="sonar_forward">
62 <box size="0.016 0.044 0.02"/>
64 <origin xyz="${0.016/2} 0 0" rpy="0 0 0"/>
65 <material name="green">
66 <color rgba="0 1 0 0.8"/>
71 <link name="sonar_backward">
74 <box size="0.016 0.044 0.02"/>
76 <origin xyz="${0.016/2} 0 0" rpy="0 0 0"/>
77 <material name="green">
78 <color rgba="0 1 0 0.8"/>
86 <box size="0.015 0.015 0.046"/>
88 <origin xyz="${-0.015/2} 0 0" rpy="0 0 0"/>
89 <material name="black">
90 <color rgba="0 0 0 1"/>
95 <link name="ir_right">
98 <box size="0.015 0.015 0.046"/>
100 <origin xyz="${-0.015/2} 0 0" rpy="0 0 0"/>
101 <material name="black">
102 <color rgba="0 0 0 1"/>
107 <joint name="base_link_joint" type="fixed">
108 <parent link="base_footprint"/>
109 <child link="base_link"/>
110 <origin xyz="0.0 0.0 0.082" rpy="0 0 0"/>
113 <joint name="mounting_plate_joint" type="fixed">
114 <parent link="base_link"/>
115 <child link="mounting_plate"/>
116 <origin xyz="0.0 0.0 0.044" rpy="0 0 0"/>
119 <joint name="imu_joint" type="fixed">
120 <parent link="mounting_plate"/>
121 <child link="base_imu_link"/>
122 <origin xyz="0.06 -0.03 0.058" rpy="0 0 0"/>
125 <joint name="sonar_forward_joint" type="fixed">
126 <parent link="mounting_plate"/>
127 <child link="sonar_forward"/>
128 <origin xyz="0.115 0.0 -0.012" rpy="0 0 0"/>
131 <joint name="sonar_backward_joint" type="fixed">
132 <parent link="mounting_plate"/>
133 <child link="sonar_backward"/>
134 <origin xyz="-0.115 0.0 -0.012" rpy="0 ${PI} 0"/>
137 <joint name="ir_left_joint" type="fixed">
138 <parent link="mounting_plate"/>
139 <child link="ir_left"/>
140 <origin xyz="0.0 ${0.072+0.015} -0.045" rpy="0 0 ${PI/2}"/>
143 <joint name="ir_right_joint" type="fixed">
144 <parent link="mounting_plate"/>
145 <child link="ir_right"/>
146 <origin xyz="0.0 ${-0.072-0.015} -0.045" rpy="0 0 ${-PI/2}"/>
149 <xacro:macro name="wheel" params="pos side xyz rpy">
150 <link name="${pos}_${side}_wheel">
152 <origin xyz="0 0 0" rpy="0 0 0"/>
154 <mesh filename="package://wild_thumper/meshes/wheel_${side}.stl" />
158 <origin xyz="0 0 0" rpy="${-PI/2} 0 0"/>
160 <cylinder radius="0.06" length="0.06"/>
164 <origin xyz="0 0 0" rpy="0 0 0"/>
166 <inertia ixx="0.005" ixy="0" ixz="0" iyy="0.005" iyz="0" izz="0.005"/>
170 <gazebo reference="${pos}_${side}_wheel">
173 <kp value="1000000.0" />
175 <fdir1 value="1 0 0"/>
178 <joint name="${pos}_${side}_wheel_joint" type="continuous">
179 <parent link="base_link"/>
180 <child link="${pos}_${side}_wheel"/>
182 <origin xyz="${xyz}" rpy="${rpy}"/>
185 <transmission name="${pos}_${side}_wheel_trans" type="SimpleTransmission">
186 <type>transmission_interface/SimpleTransmission</type>
187 <joint name="${pos}_${side}_wheel_joint">
188 <hardwareInterface>VelocityJointInterface</hardwareInterface>
190 <actuator name="{pos}_${side}_wheel_motor">
191 <mechanicalReduction>1</mechanicalReduction>
196 <xacro:wheel pos="rear" side="left" xyz="-0.07525 0.12 -0.025" rpy="${-5*PI/180} 0 0" />
197 <xacro:wheel pos="rear" side="right" xyz="-0.07525 -0.12 -0.025" rpy="${5*PI/180} 0 0" />
198 <xacro:wheel pos="front" side="left" xyz=" 0.07525 0.12 -0.025" rpy="${-5*PI/180} 0 0" />
199 <xacro:wheel pos="front" side="right" xyz=" 0.07525 -0.12 -0.025" rpy="${5*PI/180} 0 0" />
202 <plugin name="gazebo_ros_control" filename="libgazebo_ros_control.so">
203 <robotNamespace>/</robotNamespace>
204 <robotSimType>gazebo_ros_control/DefaultRobotHWSim</robotSimType>
207 <plugin name="imu_controller" filename="libgazebo_ros_imu.so">
208 <alwaysOn>true</alwaysOn>
209 <updateRate>20.0</updateRate>
210 <bodyName>base_imu_link</bodyName>
211 <topicName>imu</topicName>
212 <gaussianNoise>0.05</gaussianNoise>
213 <frameName>base_imu_link</frameName>
214 <xyzOffsets>0 0 0</xyzOffsets>
215 <rpyOffset>0 0 0</rpyOffset>
216 <serviceName>/default_imu</serviceName>
220 <xacro:macro name="range_sensor" params="name ros_topic update_rate minRange maxRange fov radiation">
221 <gazebo reference="${name}">
222 <sensor type="ray" name="${name}_sensor">
223 <pose>0 0 0 0 0 0</pose>
224 <update_rate>${update_rate}</update_rate>
225 <visualize>false</visualize>
230 <resolution>1</resolution>
231 <min_angle>-${fov/2}</min_angle>
232 <max_angle>${fov/2}</max_angle>
236 <resolution>1</resolution>
237 <min_angle>-${fov/2}</min_angle>
238 <max_angle>${fov/2}</max_angle>
242 <min>${minRange}</min>
243 <max>${maxRange}</max>
244 <resolution>0.01</resolution>
247 <plugin filename="libgazebo_ros_range.so" name="gazebo_ros_range">
248 <gaussianNoise>0.005</gaussianNoise>
249 <alwaysOn>true</alwaysOn>
250 <updateRate>${update_rate}</updateRate>
251 <topicName>${ros_topic}</topicName>
252 <frameName>${name}</frameName>
254 <radiation>${radiation}</radiation>
260 <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" />
261 <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" />
262 <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" />
263 <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" />