~j-rivero/+junk/ignition-gazebo

« back to all changes in this revision

Viewing changes to test/worlds/odometry_publisher_3d.sdf

  • Committer: Jose Luis Rivero
  • Date: 2022-02-15 17:35:59 UTC
  • Revision ID: jrivero@osrfoundation.org-20220215173559-qyu3wjmqnrby30k7
Initial import

Show diffs side-by-side

added added

removed removed

Lines of Context:
 
1
<?xml version="1.0" ?>
 
2
<sdf version="1.6">
 
3
  <world name="quadrotor">
 
4
 
 
5
    <physics name="1ms" type="ode">
 
6
      <max_step_size>0.001</max_step_size>
 
7
      <real_time_factor>0</real_time_factor>
 
8
    </physics>
 
9
    <plugin
 
10
      filename="ignition-gazebo-physics-system"
 
11
      name="ignition::gazebo::systems::Physics">
 
12
    </plugin>
 
13
 
 
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>
 
19
      <attenuation>
 
20
        <range>1000</range>
 
21
        <constant>0.9</constant>
 
22
        <linear>0.01</linear>
 
23
        <quadratic>0.001</quadratic>
 
24
      </attenuation>
 
25
      <direction>-0.5 0.1 -0.9</direction>
 
26
    </light>
 
27
 
 
28
    <model name="ground_plane">
 
29
      <static>true</static>
 
30
      <link name="link">
 
31
        <collision name="collision">
 
32
          <geometry>
 
33
            <plane>
 
34
              <normal>0 0 1</normal>
 
35
            </plane>
 
36
          </geometry>
 
37
        </collision>
 
38
        <visual name="visual">
 
39
          <geometry>
 
40
            <plane>
 
41
              <normal>0 0 1</normal>
 
42
              <size>100 100</size>
 
43
            </plane>
 
44
          </geometry>
 
45
          <material>
 
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>
 
49
          </material>
 
50
        </visual>
 
51
      </link>
 
52
    </model>
 
53
 
 
54
    <model name="X3">
 
55
      <pose>0 0 0.053302 0 0 0</pose>
 
56
      <link name="base_link">
 
57
        <inertial>
 
58
          <mass>1.5</mass>
 
59
          <inertia>
 
60
            <ixx>0.0347563</ixx>
 
61
            <ixy>0</ixy>
 
62
            <ixz>0</ixz>
 
63
            <iyy>0.07</iyy>
 
64
            <iyz>0</iyz>
 
65
            <izz>0.0977</izz>
 
66
          </inertia>
 
67
        </inertial>
 
68
        <collision name="base_link_inertia_collision">
 
69
          <geometry>
 
70
            <box>
 
71
              <size>0.30 0.42 0.11</size>
 
72
            </box>
 
73
          </geometry>
 
74
        </collision>
 
75
        <visual name="base_link_inertia_visual">
 
76
          <geometry>
 
77
            <box>
 
78
              <size>0.15 0.21 0.11</size>
 
79
            </box>
 
80
          </geometry>
 
81
        </visual>
 
82
      </link>
 
83
      <link name="rotor_0">
 
84
        <pose frame="">0.13 -0.22 0.023 0 -0 0</pose>
 
85
        <inertial>
 
86
          <mass>0.005</mass>
 
87
          <inertia>
 
88
            <ixx>9.75e-07</ixx>
 
89
            <ixy>0</ixy>
 
90
            <ixz>0</ixz>
 
91
            <iyy>4.17041e-05</iyy>
 
92
            <iyz>0</iyz>
 
93
            <izz>4.26041e-05</izz>
 
94
          </inertia>
 
95
        </inertial>
 
96
        <collision name="rotor_0_collision">
 
97
          <geometry>
 
98
            <cylinder>
 
99
              <length>0.005</length>
 
100
              <radius>0.1</radius>
 
101
            </cylinder>
 
102
          </geometry>
 
103
        </collision>
 
104
        <visual name="rotor_0_visual">
 
105
          <pose>0 0 0 1.57 0 0</pose>
 
106
          <geometry>
 
107
            <cylinder>
 
108
              <length>0.2</length>
 
109
              <radius>0.01</radius>
 
110
            </cylinder>
 
111
          </geometry>
 
112
          <material>
 
113
            <diffuse>0 0 1 1</diffuse>
 
114
          </material>
 
115
        </visual>
 
116
      </link>
 
117
      <joint name="rotor_0_joint" type="revolute">
 
118
        <child>rotor_0</child>
 
119
        <parent>base_link</parent>
 
120
        <axis>
 
121
          <xyz>0 0 1</xyz>
 
122
          <limit>
 
123
            <lower>-1e+16</lower>
 
124
            <upper>1e+16</upper>
 
125
          </limit>
 
126
        </axis>
 
127
      </joint>
 
128
      <link name="rotor_1">
 
129
        <pose>-0.13 0.2 0.023 0 -0 0</pose>
 
130
        <inertial>
 
131
          <mass>0.005</mass>
 
132
          <inertia>
 
133
            <ixx>9.75e-07</ixx>
 
134
            <ixy>0</ixy>
 
135
            <ixz>0</ixz>
 
136
            <iyy>4.17041e-05</iyy>
 
137
            <iyz>0</iyz>
 
138
            <izz>4.26041e-05</izz>
 
139
          </inertia>
 
140
        </inertial>
 
141
        <collision name="rotor_1_collision">
 
142
          <geometry>
 
143
            <cylinder>
 
144
              <length>0.005</length>
 
145
              <radius>0.1</radius>
 
146
            </cylinder>
 
147
          </geometry>
 
148
        </collision>
 
149
        <visual name="rotor_1_visual">
 
150
          <pose>0 0 0 1.57 0 0</pose>
 
151
          <geometry>
 
152
            <cylinder>
 
153
              <length>0.2</length>
 
154
              <radius>0.01</radius>
 
155
            </cylinder>
 
156
          </geometry>
 
157
          <material>
 
158
            <diffuse>1 0 0 1</diffuse>
 
159
          </material>
 
160
        </visual>
 
161
      </link>
 
162
      <joint name="rotor_1_joint" type="revolute">
 
163
        <child>rotor_1</child>
 
164
        <parent>base_link</parent>
 
165
        <axis>
 
166
          <xyz>0 0 1</xyz>
 
167
          <limit>
 
168
            <lower>-1e+16</lower>
 
169
            <upper>1e+16</upper>
 
170
          </limit>
 
171
        </axis>
 
172
      </joint>
 
173
      <link name="rotor_2">
 
174
        <pose>0.13 0.22 0.023 0 -0 0</pose>
 
175
        <inertial>
 
176
          <mass>0.005</mass>
 
177
          <inertia>
 
178
            <ixx>9.75e-07</ixx>
 
179
            <ixy>0</ixy>
 
180
            <ixz>0</ixz>
 
181
            <iyy>4.17041e-05</iyy>
 
182
            <iyz>0</iyz>
 
183
            <izz>4.26041e-05</izz>
 
184
          </inertia>
 
185
        </inertial>
 
186
        <collision name="rotor_2_collision">
 
187
          <geometry>
 
188
            <cylinder>
 
189
              <length>0.005</length>
 
190
              <radius>0.1</radius>
 
191
            </cylinder>
 
192
          </geometry>
 
193
        </collision>
 
194
        <visual name="rotor_2_visual">
 
195
          <pose>0 0 0 1.57 0 0</pose>
 
196
          <geometry>
 
197
            <cylinder>
 
198
              <length>0.2</length>
 
199
              <radius>0.01</radius>
 
200
            </cylinder>
 
201
          </geometry>
 
202
          <material>
 
203
            <diffuse>0 0 1 1</diffuse>
 
204
          </material>
 
205
        </visual>
 
206
      </link>
 
207
      <joint name="rotor_2_joint" type="revolute">
 
208
        <child>rotor_2</child>
 
209
        <parent>base_link</parent>
 
210
        <axis>
 
211
          <xyz>0 0 1</xyz>
 
212
          <limit>
 
213
            <lower>-1e+16</lower>
 
214
            <upper>1e+16</upper>
 
215
          </limit>
 
216
        </axis>
 
217
      </joint>
 
218
      <link name="rotor_3">
 
219
        <pose>-0.13 -0.2 0.023 0 -0 0</pose>
 
220
        <inertial>
 
221
          <mass>0.005</mass>
 
222
          <inertia>
 
223
            <ixx>9.75e-07</ixx>
 
224
            <ixy>0</ixy>
 
225
            <ixz>0</ixz>
 
226
            <iyy>4.17041e-05</iyy>
 
227
            <iyz>0</iyz>
 
228
            <izz>4.26041e-05</izz>
 
229
          </inertia>
 
230
        </inertial>
 
231
        <collision name="rotor_3_collision">
 
232
          <geometry>
 
233
            <cylinder>
 
234
              <length>0.005</length>
 
235
              <radius>0.1</radius>
 
236
            </cylinder>
 
237
          </geometry>
 
238
        </collision>
 
239
        <visual name="rotor_3_visual">
 
240
          <pose>0 0 0 1.57 0 0</pose>
 
241
          <geometry>
 
242
            <cylinder>
 
243
              <length>0.2</length>
 
244
              <radius>0.01</radius>
 
245
            </cylinder>
 
246
          </geometry>
 
247
          <material>
 
248
            <diffuse>1 0 0 1</diffuse>
 
249
          </material>
 
250
        </visual>
 
251
      </link>
 
252
      <joint name="rotor_3_joint" type="revolute">
 
253
        <child>rotor_3</child>
 
254
        <parent>base_link</parent>
 
255
        <axis>
 
256
          <xyz>0 0 1</xyz>
 
257
          <limit>
 
258
            <lower>-1e+16</lower>
 
259
            <upper>1e+16</upper>
 
260
          </limit>
 
261
        </axis>
 
262
      </joint>
 
263
      <plugin
 
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>
 
282
      </plugin>
 
283
      <plugin
 
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>
 
302
      </plugin>
 
303
      <plugin
 
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>
 
322
      </plugin>
 
323
      <plugin
 
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>
 
342
      </plugin>
 
343
      <plugin
 
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>
 
354
 
 
355
        <rotorConfiguration>
 
356
          <rotor>
 
357
            <jointName>rotor_0_joint</jointName>
 
358
            <forceConstant>8.54858e-06</forceConstant>
 
359
            <momentConstant>0.016</momentConstant>
 
360
            <direction>1</direction>
 
361
          </rotor>
 
362
          <rotor>
 
363
            <jointName>rotor_1_joint</jointName>
 
364
            <forceConstant>8.54858e-06</forceConstant>
 
365
            <momentConstant>0.016</momentConstant>
 
366
            <direction>1</direction>
 
367
          </rotor>
 
368
          <rotor>
 
369
            <jointName>rotor_2_joint</jointName>
 
370
            <forceConstant>8.54858e-06</forceConstant>
 
371
            <momentConstant>0.016</momentConstant>
 
372
            <direction>-1</direction>
 
373
          </rotor>
 
374
          <rotor>
 
375
            <jointName>rotor_3_joint</jointName>
 
376
            <forceConstant>8.54858e-06</forceConstant>
 
377
            <momentConstant>0.016</momentConstant>
 
378
            <direction>-1</direction>
 
379
          </rotor>
 
380
        </rotorConfiguration>
 
381
      </plugin>
 
382
      <plugin
 
383
        filename="ignition-gazebo-odometry-publisher-system"
 
384
        name="ignition::gazebo::systems::OdometryPublisher">
 
385
        <dimensions>3</dimensions>
 
386
      </plugin>
 
387
    </model>
 
388
 
 
389
  </world>
 
390
</sdf>