]> defiant.homedns.org Git - ros_wild_thumper.git/blob - urdf/wild_thumper.urdf.xacro
added gazebo simulation
[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.0"/>
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                         <geometry>
25                                 <mesh filename="package://wild_thumper/meshes/wild_thumper_4wd.stl" />
26                         </geometry>
27                 </visual>
28                 <inertial>
29                         <mass value="1.9"/>
30                         <inertia ixx="1.0" ixy="0.0" ixz="0.0" iyy="1.0" iyz="0.0" izz="1.0"/>
31                 </inertial>
32         </link>
33
34         <link name="base_imu_link">
35                 <visual>
36                         <geometry>
37                                 <box size="0.041 0.028 0.002"/>
38                         </geometry>
39                         <material name="red">
40                                 <color rgba="1 0 0 1"/>
41                         </material>
42                 </visual>
43         </link>
44
45         <link name="mounting_plate">
46                 <visual>
47                         <geometry>
48                                 <box size="0.23 0.12 0.001"/>
49                         </geometry>
50                 </visual>
51         </link>
52
53         <xacro:asus_camera name="camera" parent="mounting_plate">
54                 <origin xyz="0.107 0.0 0.04" rpy="0 0 0"/>
55         </xacro:asus_camera>
56
57         <link name="sonar_forward">
58                 <visual>
59                         <geometry>
60                                 <box size="0.016 0.044 0.02"/>
61                         </geometry>
62                         <origin xyz="${0.016/2} 0 0" rpy="0 0 0"/>
63                         <material name="green">
64                                 <color rgba="0 1 0 0.8"/>
65                         </material>
66                 </visual>
67         </link>
68
69         <link name="sonar_backward">
70                 <visual>
71                         <geometry>
72                                 <box size="0.016 0.044 0.02"/>
73                         </geometry>
74                         <origin xyz="${0.016/2} 0 0" rpy="0 0 0"/>
75                         <material name="green">
76                                 <color rgba="0 1 0 0.8"/>
77                         </material>
78                 </visual>
79         </link>
80
81         <link name="ir_left">
82                 <visual>
83                         <geometry>
84                                 <box size="0.015 0.015 0.046"/>
85                         </geometry>
86                         <origin xyz="${-0.015/2} 0 0" rpy="0 0 0"/>
87                         <material name="black">
88                                 <color rgba="0 0 0 1"/>
89                         </material>
90                 </visual>
91         </link>
92
93         <link name="ir_right">
94                 <visual>
95                         <geometry>
96                                 <box size="0.015 0.015 0.046"/>
97                         </geometry>
98                         <origin xyz="${-0.015/2} 0 0" rpy="0 0 0"/>
99                         <material name="black">
100                                 <color rgba="0 0 0 1"/>
101                         </material>
102                 </visual>
103         </link>
104
105         <joint name="base_link_joint" type="fixed">
106                 <parent link="base_footprint"/>
107                 <child link="base_link"/>
108                 <origin xyz="0.0 0.0 0.082" rpy="0 0 0"/>
109         </joint>
110
111         <joint name="mounting_plate_joint" type="fixed">
112                 <parent link="base_link"/>
113                 <child link="mounting_plate"/>
114                 <origin xyz="0.0 0.0 0.044" rpy="0 0 0"/>
115         </joint>
116
117         <joint name="imu_joint" type="fixed">
118                 <parent link="mounting_plate"/>
119                 <child link="base_imu_link"/>
120                 <origin xyz="0.06 -0.03 0.058" rpy="0 0 0"/>
121         </joint>
122
123         <joint name="sonar_forward_joint" type="fixed">
124                 <parent link="mounting_plate"/>
125                 <child link="sonar_forward"/>
126                 <origin xyz="0.115 0.0 -0.012" rpy="0 0 0"/>
127         </joint>
128
129         <joint name="sonar_backward_joint" type="fixed">
130                 <parent link="mounting_plate"/>
131                 <child link="sonar_backward"/>
132                 <origin xyz="-0.115 0.0 -0.012" rpy="0 ${PI} 0"/>
133         </joint>
134
135         <joint name="ir_left_joint" type="fixed">
136                 <parent link="mounting_plate"/>
137                 <child link="ir_left"/>
138                 <origin xyz="0.0 ${0.072+0.015} -0.045" rpy="0 0 ${PI/2}"/>
139         </joint>
140
141         <joint name="ir_right_joint" type="fixed">
142                 <parent link="mounting_plate"/>
143                 <child link="ir_right"/>
144                 <origin xyz="0.0 ${-0.072-0.015} -0.045" rpy="0 0 ${-PI/2}"/>
145         </joint>
146
147         <xacro:macro name="wheel" params="pos side xyz rpy">   
148                 <link name="${pos}_${side}_wheel">
149                         <visual>
150                                 <origin xyz="0 0 0" rpy="0 0 0"/>
151                                 <geometry>
152                                         <mesh filename="package://wild_thumper/meshes/wheel_${side}.stl" />
153                                 </geometry>
154                         </visual>
155                         <collision>
156                                 <origin xyz="0 0 0" rpy="${-PI/2} 0 0"/>
157                                 <geometry>
158                                         <cylinder radius="0.06" length="0.06"/>
159                                 </geometry>
160                         </collision>
161                         <inertial>
162                                 <origin xyz="0 0 0" rpy="0 0 0"/>
163                                 <mass value="0.1"/>
164                                 <inertia ixx="0.01" ixy="0" ixz="0" iyy="0.01" iyz="0" izz="0.01"/>
165                         </inertial>
166                 </link>
167                 <joint name="${pos}_${side}_wheel_joint" type="continuous">
168                         <parent link="base_link"/>
169                         <child link="${pos}_${side}_wheel"/>
170                         <axis xyz="0 1 0"/>
171                         <origin xyz="${xyz}" rpy="${rpy}"/>
172                 </joint>
173         </xacro:macro>
174
175         <gazebo reference="front_left_wheel">
176                 <dampingFactor>0.001</dampingFactor>
177         </gazebo>
178         <gazebo reference="front_right_wheel">
179                 <dampingFactor>0.001</dampingFactor>
180         </gazebo>
181
182         <xacro:wheel pos="aft" side="left"  xyz="-0.06398 0.11407 -0.022446" rpy="0 0 0" />
183         <xacro:wheel pos="aft" side="right" xyz="-0.07397 -0.11408 -0.022446" rpy="0 0 0" />
184         <xacro:wheel pos="front" side="left"  xyz="0.07602 0.11407 -0.022446" rpy="0 0 0" />
185         <xacro:wheel pos="front" side="right" xyz="0.07397 -0.11408 -0.022446" rpy="0 0 0" />
186
187         <gazebo>
188                 <plugin name="joint_state_publisher" filename="libgazebo_ros_joint_state_publisher.so">
189                         <robotNamespace>/</robotNamespace>
190                         <jointName>aft_left_wheel_joint, aft_right_wheel_joint, front_left_wheel_joint, front_right_wheel_joint</jointName>
191                         <updateRate>10.0</updateRate>
192                         <alwaysOn>true</alwaysOn>
193                 </plugin>
194
195                 <plugin name="differential_drive_controller" filename="libgazebo_ros_diff_drive.so">
196                         <robotNamespace>/</robotNamespace>
197                         <alwaysOn>true</alwaysOn>
198                         <updateRate>10.0</updateRate>
199                         <leftJoint>aft_right_wheel_joint</leftJoint>
200                         <rightJoint>aft_left_wheel_joint</rightJoint>
201                         <wheelSeparation>0.252</wheelSeparation>
202                         <wheelDiameter>0.12</wheelDiameter>
203                         <wheelTorque>5.0</wheelTorque>
204                         <commandTopic>cmd_vel</commandTopic>
205                         <odometryTopic>odom</odometryTopic>
206                         <odometryFrame>odom</odometryFrame>
207                         <robotBaseFrame>base_footprint</robotBaseFrame>
208                         <rosDebugLevel>Info</rosDebugLevel>
209                         <publishWheelTF>false</publishWheelTF>
210                         <publishWheelJointState>true</publishWheelJointState>
211                         <wheelAcceleration>0.0</wheelAcceleration>
212                         <odometrySource>world</odometrySource>
213                         <publishTf>true</publishTf>
214                 </plugin>
215         </gazebo>
216 </robot>