-
Notifications
You must be signed in to change notification settings - Fork 1
/
astro.gazebo.xacro
257 lines (244 loc) · 9.04 KB
/
astro.gazebo.xacro
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131
132
133
134
135
136
137
138
139
140
141
142
143
144
145
146
147
148
149
150
151
152
153
154
155
156
157
158
159
160
161
162
163
164
165
166
167
168
169
170
171
172
173
174
175
176
177
178
179
180
181
182
183
184
185
186
187
188
189
190
191
192
193
194
195
196
197
198
199
200
201
202
203
204
205
206
207
208
209
210
211
212
213
214
215
216
217
218
219
220
221
222
223
224
225
226
227
228
229
230
231
232
233
234
235
236
237
238
239
240
241
242
243
244
245
246
247
248
249
250
251
252
253
254
255
256
257
<robot xmlns:xacro="http://www.ros.org/wiki/xacro" name="fetch">
<xacro:include filename="$(find astro_description)/robots/astro.xacro"/>
<xacro:include filename="$(find uw_gazebo)/urdf/d415.gazebo.urdf.xacro"/>
<!-- Add four casters to the base -->
<xacro:macro name="caster" params="prefix joint_x joint_y">
<link name="${prefix}_caster_link">
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<sphere radius="0.0601"/> <!-- 0.06033 -->
</geometry>
<material name="">
<color rgba="0.086 0.506 0.767 1"/>
</material>
</visual>
<collision>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<sphere radius="0.0601"/>
</geometry>
</collision>
<inertial>
<inertia ixx="1" ixy="0" ixz="0" iyy="1" iyz="0" izz="1"/>
<origin rpy="0 0 0" xyz="0 0 0"/>
<mass value="0.01"/>
</inertial>
</link>
<gazebo reference="${prefix}_caster_link">
<mu1>0.1</mu1>
<mu2>0.1</mu2>
<kp>100000000</kp>
<kd>10.0</kd>
<maxVel>10</maxVel>
<minDepth>0.001</minDepth>
</gazebo>
<joint name="${prefix}_caster_joint" type="fixed">
<parent link="base_link"/>
<child link="${prefix}_caster_link"/>
<origin rpy="0 0 0" xyz="${joint_x} ${joint_y} 0.055325"/>
<axis xyz="0 1 0"/>
</joint>
</xacro:macro>
<xacro:caster prefix="fl" joint_x="0.15" joint_y="0.12"/>
<xacro:caster prefix="fr" joint_x="0.15" joint_y="-0.12"/>
<xacro:caster prefix="br" joint_x="-0.2" joint_y="0.12"/>
<xacro:caster prefix="bl" joint_x="-0.2" joint_y="-0.12"/>
<!-- Base is modeled as a big tub sitting on floor, with two wheels -->
<gazebo reference="base_link">
<kp>100000000.0</kp>
<kd>10.0</kd>
<mu1>0.1</mu1>
<mu2>0.1</mu2>
<fdir1>1 0 0</fdir1>
<maxVel>10.0</maxVel>
<minDepth>0.0005</minDepth>
</gazebo>
<gazebo reference="r_wheel_link">
<kp>1000000.0</kp>
<kd>100.0</kd>
<mu1>100000000000000.0</mu1>
<mu2>100000000000000.0</mu2>
<!-- <fdir1>1 0 0</fdir1 -->
<maxVel>1.0</maxVel>
<minDepth>0.01</minDepth>
<material>Gazebo/Black</material>
</gazebo>
<gazebo reference="l_wheel_link">
<kp>1000000.0</kp>
<kd>100.0</kd>
<mu1>100000000000000.0</mu1>
<mu2>100000000000000.0</mu2>
<!-- fdir1>1 0 0</fdir1 -->
<maxVel>1.0</maxVel>
<minDepth>0.01</minDepth>
<material>Gazebo/Black</material>
</gazebo>
<gazebo reference="l_wheel_joint">
<implicitSpringDamper>1</implicitSpringDamper>
</gazebo>
<gazebo reference="r_wheel_joint">
<implicitSpringDamper>1</implicitSpringDamper>
</gazebo>
<gazebo reference="forearm_roll_joint">
<implicitSpringDamper>1</implicitSpringDamper>
</gazebo>
<gazebo reference="wrist_roll_joint">
<implicitSpringDamper>1</implicitSpringDamper>
</gazebo>
<!-- Gripper is another fallacy of physics -->
<gazebo reference="r_gripper_finger_link">
<kp>1000000.0</kp>
<kd>100.0</kd>
<mu1>30.0</mu1>
<mu2>30.0</mu2>
<maxVel>1.0</maxVel>
<minDepth>0.001</minDepth>
<material>Gazebo/Grey</material>
</gazebo>
<gazebo reference="l_gripper_finger_link">
<kp>1000000.0</kp>
<kd>100.0</kd>
<mu1>30.0</mu1>
<mu2>30.0</mu2>
<maxVel>1.0</maxVel>
<minDepth>0.001</minDepth>
<material>Gazebo/Grey</material>
</gazebo>
<!-- SICK TIM561 (25m Range) -->
<gazebo reference="laser_link">
<sensor type="ray" name="base_laser">
<pose>0 0 0 0 0 0</pose>
<visualize>false</visualize>
<update_rate>15</update_rate>
<ray>
<scan>
<horizontal>
<samples>662</samples>
<resolution>1</resolution>
<min_angle>-1.91986</min_angle>
<max_angle>1.91986</max_angle>
</horizontal>
</scan>
<range>
<min>0.05</min>
<max>25.0</max>
<resolution>0.01</resolution>
</range>
<noise>
<!-- Noise parameters based on spec for SICK TIM561 (10m version) -->
<type>gaussian</type>
<mean>0.0</mean>
<stddev>0.02</stddev>
</noise>
</ray>
<plugin name="gazebo_ros_base_hokuyo_controller" filename="libgazebo_ros_laser.so">
<topicName>/base_scan</topicName>
<frameName>laser_link</frameName>
</plugin>
</sensor>
</gazebo>
<!-- Primesense Carmine 1.09 -->
<gazebo reference="head_camera_rgb_frame">
<sensor type="depth" name="camera">
<always_on>true</always_on>
<update_rate>15.0</update_rate>
<camera>
<horizontal_fov>1.047197</horizontal_fov>
<image>
<!-- openni_kinect plugin works only with BGR8 -->
<format>B8G8R8</format>
<width>640</width>
<height>480</height>
</image>
<clip>
<near>0.05</near>
<far>50</far>
</clip>
</camera>
<plugin name="head_camera_controller" filename="libgazebo_ros_openni_kinect.so">
<baseline>0.1</baseline>
<alwaysOn>true</alwaysOn>
<updateRate>15.0</updateRate>
<cameraName>head_camera</cameraName>
<imageTopicName>/head_camera/rgb/image_raw</imageTopicName>
<cameraInfoTopicName>/head_camera/rgb/camera_info</cameraInfoTopicName>
<depthImageTopicName>/head_camera/depth_registered/image_raw</depthImageTopicName>
<depthImageCameraInfoTopicName>/head_camera/depth_registered/camera_info</depthImageCameraInfoTopicName>
<pointCloudTopicName>/head_camera/depth_registered/points</pointCloudTopicName>
<frameName>head_camera_rgb_optical_frame</frameName>
<pointCloudCutoff>0.35</pointCloudCutoff>
<pointCloudCutoffMax>4.5</pointCloudCutoffMax>
<CxPrime>0</CxPrime>
<Cx>0</Cx>
<Cy>0</Cy>
<focalLength>0</focalLength>
<hackBaseline>0</hackBaseline>
</plugin>
</sensor>
</gazebo>
<sensor_d415_gazebo name="head_external_camera"></sensor_d415_gazebo>
<gazebo reference="head_display_screen">
<visual>
<plugin name="display_video_controller" filename="libgazebo_ros_video.so">
<topicName>/gazebo/head_display_image</topicName>
<height>720</height>
<width>1280</width>
</plugin>
</visual>
<material>Gazebo/Black</material>
</gazebo>
<!-- Color the bellows -->
<gazebo reference="bellows_link">
<material>Gazebo/Black</material>
</gazebo>
<gazebo reference="bellows_link2">
<material>Gazebo/Black</material>
</gazebo>
<!-- Color the estop -->
<gazebo reference="estop_link">
<material>Gazebo/Red</material>
</gazebo>
<!-- Color head components -->
<gazebo reference="xavier_mount">
<material>Gazebo/Black</material>
</gazebo>
<gazebo reference="xavier">
<material>Gazebo/Black</material>
</gazebo>
<gazebo reference="head_display">
<material>Gazebo/Black</material>
</gazebo>
<gazebo reference="head_display_mount">
<material>Gazebo/Black</material>
</gazebo>
<gazebo reference="head_external_camera_mount">
<material>Gazebo/Black</material>
</gazebo>
<gazebo reference="head_external_camera_link">
<material>Gazebo/Grey</material>
</gazebo>
<gazebo reference="head_mic">
<material>Gazebo/DarkGrey</material>
</gazebo>
<gazebo reference="head_mic_mount">
<material>Gazebo/Black</material>
</gazebo>
<gazebo reference="head_mic_shell">
<material>Gazebo/Grey</material>
</gazebo>
<!-- Load the plugin -->
<gazebo>
<plugin name="p3d_base_controller" filename="libgazebo_ros_p3d.so">
<alwaysOn>true</alwaysOn>
<updateRate>100.0</updateRate>
<bodyName>base_link</bodyName>
<topicName>odom_ground_truth</topicName>
<gaussianNoise>0.01</gaussianNoise>
<frameName>world</frameName>
<xyzOffsets>0 0 0</xyzOffsets>
<rpyOffsets>0 0 0</rpyOffsets>
</plugin>
<plugin name="fetch_gazebo_plugin" filename="libfetch_gazebo_plugin.so"/>
</gazebo>
</robot>