]> defiant.homedns.org Git - ros_wild_thumper.git/blob - urdf/wild_thumper.urdf.xacro
switch from xtion 3d camera to rplidar
[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         <link name="base_footprint">
6                 <visual>
7                         <geometry>
8                                 <box size="0.28 0.31 0.000001"/>
9                         </geometry>
10                         <material name="grey">
11                                 <color rgba="0.5 0.5 0.5 0.5"/>
12                         </material>
13                 </visual>
14         </link>
15
16         <link name="base_link">
17                 <collision>
18                         <geometry>
19                                 <box size="0.23 0.18 0.09"/>
20                         </geometry>
21                 </collision>
22                 <visual>
23                         <origin xyz="-0.00275 0 0" rpy="0 0 0"/>
24                         <geometry>
25                                 <mesh filename="package://wild_thumper/meshes/wild_thumper_4wd.stl" />
26                         </geometry>
27                 </visual>
28                 <inertial>
29                         <origin xyz="-0.00275 0 -0.02" rpy="0 0 0"/>
30                         <mass value="2.5"/>
31                         <inertia ixx="1.0" ixy="0.0" ixz="0.0" iyy="1.0" iyz="0.0" izz="1.0"/>
32                 </inertial>
33         </link>
34
35         <link name="base_imu_link">
36                 <visual>
37                         <geometry>
38                                 <box size="0.041 0.028 0.002"/>
39                         </geometry>
40                         <material name="red">
41                                 <color rgba="1 0 0 1"/>
42                         </material>
43                 </visual>
44         </link>
45
46         <link name="mounting_plate">
47                 <visual>
48                         <geometry>
49                                 <box size="0.23 0.12 0.001"/>
50                         </geometry>
51                 </visual>
52         </link>
53
54         <link name="lidar">
55                 <visual>
56                         <geometry>
57                                 <mesh filename="package://wild_thumper/meshes/rplidar_a2.stl" scale="0.001 0.001 0.001"/>
58                         </geometry>
59                         <origin xyz="0.0 0.0 ${0.0408/2}" rpy="0 0 0"/>
60                         <material name="black">
61                                 <color rgba="0 0 0 1"/>
62                         </material>
63                 </visual>
64         </link>
65
66         <link name="sonar_forward_left">
67                 <visual>
68                         <geometry>
69                                 <box size="0.016 0.044 0.02"/>
70                         </geometry>
71                         <origin xyz="${0.016/2} 0 0" rpy="0 0 0"/>
72                         <material name="green">
73                                 <color rgba="0 1 0 0.8"/>
74                         </material>
75                 </visual>
76         </link>
77
78         <link name="sonar_forward_right">
79                 <visual>
80                         <geometry>
81                                 <box size="0.016 0.044 0.02"/>
82                         </geometry>
83                         <origin xyz="${0.016/2} 0 0" rpy="0 0 0"/>
84                         <material name="green">
85                                 <color rgba="0 1 0 0.8"/>
86                         </material>
87                 </visual>
88         </link>
89
90         <link name="sonar_backward">
91                 <visual>
92                         <geometry>
93                                 <box size="0.016 0.044 0.02"/>
94                         </geometry>
95                         <origin xyz="${0.016/2} 0 0" rpy="0 0 0"/>
96                         <material name="green">
97                                 <color rgba="0 1 0 0.8"/>
98                         </material>
99                 </visual>
100         </link>
101
102         <joint name="base_link_joint" type="fixed">
103                 <parent link="base_footprint"/>
104                 <child link="base_link"/>
105                 <origin xyz="0.0 0.0 0.082" rpy="0 0 0"/>
106         </joint>
107
108         <joint name="mounting_plate_joint" type="fixed">
109                 <parent link="base_link"/>
110                 <child link="mounting_plate"/>
111                 <origin xyz="0.0 0.0 0.044" rpy="0 0 0"/>
112         </joint>
113
114         <joint name="imu_joint" type="fixed">
115                 <parent link="mounting_plate"/>
116                 <child link="base_imu_link"/>
117                 <origin xyz="0.06 -0.03 0.058" rpy="0 0 0"/>
118         </joint>
119
120         <joint name="sonar_forward_left_joint" type="fixed">
121                 <parent link="mounting_plate"/>
122                 <child link="sonar_forward_left"/>
123                 <origin xyz="0.115 0.05 -0.012" rpy="0 ${-5*PI/180} 0"/>
124         </joint>
125
126         <joint name="sonar_forward_right_joint" type="fixed">
127                 <parent link="mounting_plate"/>
128                 <child link="sonar_forward_right"/>
129                 <origin xyz="0.115 -0.05 -0.012" rpy="0 ${-5*PI/180} 0"/>
130         </joint>
131
132         <joint name="sonar_backward_joint" type="fixed">
133                 <parent link="mounting_plate"/>
134                 <child link="sonar_backward"/>
135                 <origin xyz="-0.115 0.0 -0.012" rpy="0 ${-175*PI/180} 0"/>
136         </joint>
137
138         <joint name="lidar_joint" type="fixed">
139                 <parent link="mounting_plate"/>
140                 <child link="lidar"/>
141                 <origin xyz="0.075 0.01 0.0" rpy="0 0 ${-110*PI/180}"/>
142         </joint>
143
144         <xacro:macro name="wheel" params="pos side xyz rpy">   
145                 <link name="${pos}_${side}_wheel">
146                         <visual>
147                                 <origin xyz="0 0 0" rpy="0 0 0"/>
148                                 <geometry>
149                                         <mesh filename="package://wild_thumper/meshes/wheel_${side}.stl" />
150                                 </geometry>
151                         </visual>
152                         <collision>
153                                 <origin xyz="0 0 0" rpy="${-PI/2} 0 0"/>
154                                 <geometry>
155                                         <cylinder radius="0.06" length="0.06"/>
156                                 </geometry>
157                         </collision>
158                         <inertial>
159                                 <origin xyz="0 0 0" rpy="0 0 0"/>
160                                 <mass value="0.1"/>
161                                 <inertia ixx="0.005" ixy="0" ixz="0" iyy="0.005" iyz="0" izz="0.005"/>
162                         </inertial>
163                 </link>
164
165                 <gazebo reference="${pos}_${side}_wheel">
166                         <mu1 value="1.0"/>
167                         <mu2 value="1.0"/>
168                         <kp value="1000000.0" />
169                         <kd value="1.0" />
170                         <fdir1 value="1 0 0"/>
171                 </gazebo>
172
173                 <joint name="${pos}_${side}_wheel_joint" type="continuous">
174                         <parent link="base_link"/>
175                         <child link="${pos}_${side}_wheel"/>
176                         <axis xyz="0 1 0"/>
177                         <origin xyz="${xyz}" rpy="${rpy}"/>
178                 </joint>
179
180                 <transmission name="${pos}_${side}_wheel_trans" type="SimpleTransmission">
181                         <type>transmission_interface/SimpleTransmission</type>
182                         <joint name="${pos}_${side}_wheel_joint">
183                                 <hardwareInterface>VelocityJointInterface</hardwareInterface>
184                         </joint>
185                         <actuator name="{pos}_${side}_wheel_motor">
186                                 <mechanicalReduction>1</mechanicalReduction>
187                         </actuator>
188                 </transmission>
189         </xacro:macro>
190
191         <xacro:wheel pos="rear" side="left"   xyz="-0.07525  0.12 -0.025" rpy="${-5*PI/180} 0 0" />
192         <xacro:wheel pos="rear" side="right"  xyz="-0.07525 -0.12 -0.025" rpy="${5*PI/180} 0 0" />
193         <xacro:wheel pos="front" side="left"  xyz=" 0.07525  0.12 -0.025" rpy="${-5*PI/180} 0 0" />
194         <xacro:wheel pos="front" side="right" xyz=" 0.07525 -0.12 -0.025" rpy="${5*PI/180} 0 0" />
195
196         <gazebo>
197                 <plugin name="gazebo_ros_control" filename="libgazebo_ros_control.so">
198                         <robotNamespace>/</robotNamespace>
199                         <robotSimType>gazebo_ros_control/DefaultRobotHWSim</robotSimType>
200                 </plugin>
201
202                 <plugin name="imu_controller" filename="libgazebo_ros_imu.so">
203                         <alwaysOn>true</alwaysOn>
204                         <updateRate>20.0</updateRate>
205                         <bodyName>base_imu_link</bodyName>
206                         <topicName>imu</topicName>
207                         <gaussianNoise>0.05</gaussianNoise>
208                         <frameName>base_imu_link</frameName>
209                         <xyzOffsets>0 0 0</xyzOffsets>
210                         <rpyOffset>0 0 0</rpyOffset>
211                         <serviceName>/default_imu</serviceName>
212                 </plugin>
213         </gazebo>
214
215         <xacro:macro name="range_sensor" params="name ros_topic update_rate minRange maxRange fov radiation">
216                 <gazebo reference="${name}">
217                         <sensor type="ray" name="${name}_sensor">
218                                 <pose>0 0 0 0 0 0</pose>
219                                 <update_rate>${update_rate}</update_rate>
220                                 <visualize>false</visualize>
221                                 <ray>
222                                         <scan>
223                                                 <horizontal>
224                                                         <samples>5</samples>
225                                                         <resolution>1</resolution>
226                                                         <min_angle>-${fov/2}</min_angle>
227                                                         <max_angle>${fov/2}</max_angle>
228                                                 </horizontal>
229                                                 <vertical>
230                                                         <samples>5</samples>
231                                                         <resolution>1</resolution>
232                                                         <min_angle>-${fov/2}</min_angle>
233                                                         <max_angle>${fov/2}</max_angle>
234                                                 </vertical>
235                                         </scan>
236                                         <range>
237                                                 <min>${minRange}</min>
238                                                 <max>${maxRange}</max>
239                                                 <resolution>0.01</resolution>
240                                         </range>
241                                 </ray>
242                                 <plugin filename="libgazebo_ros_range.so" name="gazebo_ros_range">
243                                         <gaussianNoise>0.005</gaussianNoise>
244                                         <alwaysOn>true</alwaysOn>
245                                         <updateRate>${update_rate}</updateRate>
246                                         <topicName>${ros_topic}</topicName>
247                                         <frameName>${name}</frameName>
248                                         <fov>${fov}</fov>
249                                         <radiation>${radiation}</radiation>
250                                 </plugin>
251                         </sensor>
252                 </gazebo>
253         </xacro:macro>
254
255         <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" />
256         <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" />
257         <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" />
258         <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" />
259 </robot>