3
<world name="quadrotor">
5
<physics name="1ms" type="ode">
6
<max_step_size>0.001</max_step_size>
7
<real_time_factor>0</real_time_factor>
10
filename="ignition-gazebo-physics-system"
11
name="ignition::gazebo::systems::Physics">
14
<light type="directional" name="sun">
15
<cast_shadows>true</cast_shadows>
16
<pose>0 0 10 0 0 0</pose>
17
<diffuse>1 1 1 1</diffuse>
18
<specular>0.5 0.5 0.5 1</specular>
21
<constant>0.9</constant>
23
<quadratic>0.001</quadratic>
25
<direction>-0.5 0.1 -0.9</direction>
28
<model name="ground_plane">
31
<collision name="collision">
34
<normal>0 0 1</normal>
38
<visual name="visual">
41
<normal>0 0 1</normal>
46
<ambient>0.8 0.8 0.8 1</ambient>
47
<diffuse>0.8 0.8 0.8 1</diffuse>
48
<specular>0.8 0.8 0.8 1</specular>
55
<pose>0 0 0.053302 0 0 0</pose>
56
<link name="base_link">
68
<collision name="base_link_inertia_collision">
71
<size>0.30 0.42 0.11</size>
75
<visual name="base_link_inertia_visual">
78
<size>0.15 0.21 0.11</size>
84
<pose frame="">0.13 -0.22 0.023 0 -0 0</pose>
91
<iyy>4.17041e-05</iyy>
93
<izz>4.26041e-05</izz>
96
<collision name="rotor_0_collision">
99
<length>0.005</length>
104
<visual name="rotor_0_visual">
105
<pose>0 0 0 1.57 0 0</pose>
109
<radius>0.01</radius>
113
<diffuse>0 0 1 1</diffuse>
117
<joint name="rotor_0_joint" type="revolute">
118
<child>rotor_0</child>
119
<parent>base_link</parent>
123
<lower>-1e+16</lower>
128
<link name="rotor_1">
129
<pose>-0.13 0.2 0.023 0 -0 0</pose>
136
<iyy>4.17041e-05</iyy>
138
<izz>4.26041e-05</izz>
141
<collision name="rotor_1_collision">
144
<length>0.005</length>
149
<visual name="rotor_1_visual">
150
<pose>0 0 0 1.57 0 0</pose>
154
<radius>0.01</radius>
158
<diffuse>1 0 0 1</diffuse>
162
<joint name="rotor_1_joint" type="revolute">
163
<child>rotor_1</child>
164
<parent>base_link</parent>
168
<lower>-1e+16</lower>
173
<link name="rotor_2">
174
<pose>0.13 0.22 0.023 0 -0 0</pose>
181
<iyy>4.17041e-05</iyy>
183
<izz>4.26041e-05</izz>
186
<collision name="rotor_2_collision">
189
<length>0.005</length>
194
<visual name="rotor_2_visual">
195
<pose>0 0 0 1.57 0 0</pose>
199
<radius>0.01</radius>
203
<diffuse>0 0 1 1</diffuse>
207
<joint name="rotor_2_joint" type="revolute">
208
<child>rotor_2</child>
209
<parent>base_link</parent>
213
<lower>-1e+16</lower>
218
<link name="rotor_3">
219
<pose>-0.13 -0.2 0.023 0 -0 0</pose>
226
<iyy>4.17041e-05</iyy>
228
<izz>4.26041e-05</izz>
231
<collision name="rotor_3_collision">
234
<length>0.005</length>
239
<visual name="rotor_3_visual">
240
<pose>0 0 0 1.57 0 0</pose>
244
<radius>0.01</radius>
248
<diffuse>1 0 0 1</diffuse>
252
<joint name="rotor_3_joint" type="revolute">
253
<child>rotor_3</child>
254
<parent>base_link</parent>
258
<lower>-1e+16</lower>
264
filename="ignition-gazebo-multicopter-motor-model-system"
265
name="ignition::gazebo::systems::MulticopterMotorModel">
266
<robotNamespace>X3</robotNamespace>
267
<jointName>rotor_0_joint</jointName>
268
<linkName>rotor_0</linkName>
269
<turningDirection>ccw</turningDirection>
270
<timeConstantUp>0.0125</timeConstantUp>
271
<timeConstantDown>0.025</timeConstantDown>
272
<maxRotVelocity>8000.0</maxRotVelocity>
273
<motorConstant>8.54858e-06</motorConstant>
274
<momentConstant>0.016</momentConstant>
275
<commandSubTopic>gazebo/command/motor_speed</commandSubTopic>
276
<motorNumber>0</motorNumber>
277
<rotorDragCoefficient>8.06428e-05</rotorDragCoefficient>
278
<rollingMomentCoefficient>1e-06</rollingMomentCoefficient>
279
<motorSpeedPubTopic>motor_speed/0</motorSpeedPubTopic>
280
<rotorVelocitySlowdownSim>1</rotorVelocitySlowdownSim>
281
<motorType>velocity</motorType>
284
filename="ignition-gazebo-multicopter-motor-model-system"
285
name="ignition::gazebo::systems::MulticopterMotorModel">
286
<robotNamespace>X3</robotNamespace>
287
<jointName>rotor_1_joint</jointName>
288
<linkName>rotor_1</linkName>
289
<turningDirection>ccw</turningDirection>
290
<timeConstantUp>0.0125</timeConstantUp>
291
<timeConstantDown>0.025</timeConstantDown>
292
<maxRotVelocity>8000.0</maxRotVelocity>
293
<motorConstant>8.54858e-06</motorConstant>
294
<momentConstant>0.016</momentConstant>
295
<commandSubTopic>gazebo/command/motor_speed</commandSubTopic>
296
<motorNumber>1</motorNumber>
297
<rotorDragCoefficient>8.06428e-05</rotorDragCoefficient>
298
<rollingMomentCoefficient>1e-06</rollingMomentCoefficient>
299
<motorSpeedPubTopic>motor_speed/1</motorSpeedPubTopic>
300
<rotorVelocitySlowdownSim>1</rotorVelocitySlowdownSim>
301
<motorType>velocity</motorType>
304
filename="ignition-gazebo-multicopter-motor-model-system"
305
name="ignition::gazebo::systems::MulticopterMotorModel">
306
<robotNamespace>X3</robotNamespace>
307
<jointName>rotor_2_joint</jointName>
308
<linkName>rotor_2</linkName>
309
<turningDirection>cw</turningDirection>
310
<timeConstantUp>0.0125</timeConstantUp>
311
<timeConstantDown>0.025</timeConstantDown>
312
<maxRotVelocity>8000.0</maxRotVelocity>
313
<motorConstant>8.54858e-06</motorConstant>
314
<momentConstant>0.016</momentConstant>
315
<commandSubTopic>gazebo/command/motor_speed</commandSubTopic>
316
<motorNumber>2</motorNumber>
317
<rotorDragCoefficient>8.06428e-05</rotorDragCoefficient>
318
<rollingMomentCoefficient>1e-06</rollingMomentCoefficient>
319
<motorSpeedPubTopic>motor_speed/2</motorSpeedPubTopic>
320
<rotorVelocitySlowdownSim>1</rotorVelocitySlowdownSim>
321
<motorType>velocity</motorType>
324
filename="ignition-gazebo-multicopter-motor-model-system"
325
name="ignition::gazebo::systems::MulticopterMotorModel">
326
<robotNamespace>X3</robotNamespace>
327
<jointName>rotor_3_joint</jointName>
328
<linkName>rotor_3</linkName>
329
<turningDirection>cw</turningDirection>
330
<timeConstantUp>0.0125</timeConstantUp>
331
<timeConstantDown>0.025</timeConstantDown>
332
<maxRotVelocity>8000.0</maxRotVelocity>
333
<motorConstant>8.54858e-06</motorConstant>
334
<momentConstant>0.016</momentConstant>
335
<commandSubTopic>gazebo/command/motor_speed</commandSubTopic>
336
<motorNumber>3</motorNumber>
337
<rotorDragCoefficient>8.06428e-05</rotorDragCoefficient>
338
<rollingMomentCoefficient>1e-06</rollingMomentCoefficient>
339
<motorSpeedPubTopic>motor_speed/3</motorSpeedPubTopic>
340
<rotorVelocitySlowdownSim>1</rotorVelocitySlowdownSim>
341
<motorType>velocity</motorType>
344
filename="ignition-gazebo-multicopter-control-system"
345
name="ignition::gazebo::systems::MulticopterVelocityControl">
346
<robotNamespace>X3</robotNamespace>
347
<commandSubTopic>gazebo/command/twist</commandSubTopic>
348
<enableSubTopic>enable</enableSubTopic>
349
<comLinkName>base_link</comLinkName>
350
<velocityGain>2.7 2.7 2.7</velocityGain>
351
<attitudeGain>2 3 0.15</attitudeGain>
352
<angularRateGain>0.4 0.52 0.18</angularRateGain>
353
<maximumLinearAcceleration>2 2 2</maximumLinearAcceleration>
357
<jointName>rotor_0_joint</jointName>
358
<forceConstant>8.54858e-06</forceConstant>
359
<momentConstant>0.016</momentConstant>
360
<direction>1</direction>
363
<jointName>rotor_1_joint</jointName>
364
<forceConstant>8.54858e-06</forceConstant>
365
<momentConstant>0.016</momentConstant>
366
<direction>1</direction>
369
<jointName>rotor_2_joint</jointName>
370
<forceConstant>8.54858e-06</forceConstant>
371
<momentConstant>0.016</momentConstant>
372
<direction>-1</direction>
375
<jointName>rotor_3_joint</jointName>
376
<forceConstant>8.54858e-06</forceConstant>
377
<momentConstant>0.016</momentConstant>
378
<direction>-1</direction>
380
</rotorConfiguration>
383
filename="ignition-gazebo-odometry-publisher-system"
384
name="ignition::gazebo::systems::OdometryPublisher">
385
<dimensions>3</dimensions>