|
79 | 79 | </link>
|
80 | 80 | <link name="rotor_0_blade_2_cp">
|
81 | 81 | <gravity>0</gravity>
|
82 |
| - <pose>0.13 -0.22 0.216 0 -0 0</pose> |
| 82 | + <pose>0.13 -0.22 0.216 0 0 0</pose> |
83 | 83 | <visual name='rotor_0_visual_root'>
|
84 |
| - <pose>0 0 0 0 -0 0</pose> |
| 84 | + <pose>0 0 0 0 0 0</pose> |
85 | 85 | <geometry>
|
86 | 86 | <sphere>
|
87 | 87 | <radius>0.01</radius>
|
|
93 | 93 | </material>
|
94 | 94 | </visual>
|
95 | 95 | <visual name='rotor_0_visual_tip'>
|
96 |
| - <pose>-0.12 0 0 0 -0 0</pose> |
| 96 | + <pose>-0.12 0 0 0 0 0</pose> |
97 | 97 | <geometry>
|
98 | 98 | <sphere>
|
99 | 99 | <radius>0.01</radius>
|
|
105 | 105 | </material>
|
106 | 106 | </visual>
|
107 | 107 | <visual name='rotor_0_visual_cp'>
|
108 |
| - <pose>-0.084 0 0 0 -0 0</pose> |
| 108 | + <pose>-0.084 0 0 0 0 0</pose> |
109 | 109 | <geometry>
|
110 | 110 | <sphere>
|
111 | 111 | <radius>0.003</radius>
|
|
117 | 117 | </material>
|
118 | 118 | </visual>
|
119 | 119 | <visual name='rotor_0_visual_cp_forward'>
|
120 |
| - <pose>-0.084 -0.02 0 0 -0 0</pose> |
| 120 | + <pose>-0.084 -0.02 0 0 0 0</pose> |
121 | 121 | <geometry>
|
122 | 122 | <sphere>
|
123 | 123 | <radius>0.003</radius>
|
|
129 | 129 | </material>
|
130 | 130 | </visual>
|
131 | 131 | <visual name='rotor_0_visual_cp_upward'>
|
132 |
| - <pose>-0.084 0 0.02 0 -0 0</pose> |
| 132 | + <pose>-0.084 0 0.02 0 0 0</pose> |
133 | 133 | <geometry>
|
134 | 134 | <sphere>
|
135 | 135 | <radius>0.003</radius>
|
|
166 | 166 |
|
167 | 167 | <link name="rotor_1_blade_1_cp">
|
168 | 168 | <gravity>0</gravity>
|
169 |
| - <pose>-0.13 0.2 0.216 0 -0 0</pose> |
| 169 | + <pose>-0.13 0.2 0.216 0 0 0</pose> |
170 | 170 | <visual name='rotor_1_visual_root'>
|
171 |
| - <pose>0 0 0 0 -0 0</pose> |
| 171 | + <pose>0 0 0 0 0 0</pose> |
172 | 172 | <geometry>
|
173 | 173 | <sphere>
|
174 | 174 | <radius>0.01</radius>
|
|
180 | 180 | </material>
|
181 | 181 | </visual>
|
182 | 182 | <visual name='rotor_1_visual_tip'>
|
183 |
| - <pose>0.12 0 0 0 -0 0</pose> |
| 183 | + <pose>0.12 0 0 0 0 0</pose> |
184 | 184 | <geometry>
|
185 | 185 | <sphere>
|
186 | 186 | <radius>0.01</radius>
|
|
192 | 192 | </material>
|
193 | 193 | </visual>
|
194 | 194 | <visual name='rotor_1_visual_cp'>
|
195 |
| - <pose>0.084 0 0 0 -0 0</pose> |
| 195 | + <pose>0.084 0 0 0 0 0</pose> |
196 | 196 | <geometry>
|
197 | 197 | <sphere>
|
198 | 198 | <radius>0.003</radius>
|
|
204 | 204 | </material>
|
205 | 205 | </visual>
|
206 | 206 | <visual name='rotor_1_visual_cp_forward'>
|
207 |
| - <pose>0.084 0.02 0 0 -0 0</pose> |
| 207 | + <pose>0.084 0.02 0 0 0 0</pose> |
208 | 208 | <geometry>
|
209 | 209 | <sphere>
|
210 | 210 | <radius>0.003</radius>
|
|
216 | 216 | </material>
|
217 | 217 | </visual>
|
218 | 218 | <visual name='rotor_1_visual_cp_upward'>
|
219 |
| - <pose>0.084 0 0.02 0 -0 0</pose> |
| 219 | + <pose>0.084 0 0.02 0 0 0</pose> |
220 | 220 | <geometry>
|
221 | 221 | <sphere>
|
222 | 222 | <radius>0.003</radius>
|
|
230 | 230 | </link>
|
231 | 231 | <link name="rotor_1_blade_2_cp">
|
232 | 232 | <gravity>0</gravity>
|
233 |
| - <pose>-0.13 0.2 0.216 0 -0 0</pose> |
| 233 | + <pose>-0.13 0.2 0.216 0 0 0</pose> |
234 | 234 | <visual name='rotor_1_visual_root'>
|
235 |
| - <pose>0 0 0 0 -0 0</pose> |
| 235 | + <pose>0 0 0 0 0 0</pose> |
236 | 236 | <geometry>
|
237 | 237 | <sphere>
|
238 | 238 | <radius>0.01</radius>
|
|
244 | 244 | </material>
|
245 | 245 | </visual>
|
246 | 246 | <visual name='rotor_1_visual_tip'>
|
247 |
| - <pose>-0.12 0 0 0 -0 0</pose> |
| 247 | + <pose>-0.12 0 0 0 0 0</pose> |
248 | 248 | <geometry>
|
249 | 249 | <sphere>
|
250 | 250 | <radius>0.01</radius>
|
|
256 | 256 | </material>
|
257 | 257 | </visual>
|
258 | 258 | <visual name='rotor_1_visual_cp'>
|
259 |
| - <pose>-0.084 0 0 0 -0 0</pose> |
| 259 | + <pose>-0.084 0 0 0 0 0</pose> |
260 | 260 | <geometry>
|
261 | 261 | <sphere>
|
262 | 262 | <radius>0.003</radius>
|
|
268 | 268 | </material>
|
269 | 269 | </visual>
|
270 | 270 | <visual name='rotor_1_visual_cp_forward'>
|
271 |
| - <pose>-0.084 -0.02 0 0 -0 0</pose> |
| 271 | + <pose>-0.084 -0.02 0 0 0 0</pose> |
272 | 272 | <geometry>
|
273 | 273 | <sphere>
|
274 | 274 | <radius>0.003</radius>
|
|
280 | 280 | </material>
|
281 | 281 | </visual>
|
282 | 282 | <visual name='rotor_1_visual_cp_upward'>
|
283 |
| - <pose>-0.084 0 0.02 0 -0 0</pose> |
| 283 | + <pose>-0.084 0 0.02 0 0 0</pose> |
284 | 284 | <geometry>
|
285 | 285 | <sphere>
|
286 | 286 | <radius>0.003</radius>
|
|
317 | 317 |
|
318 | 318 | <link name="rotor_2_blade_1_cp">
|
319 | 319 | <gravity>0</gravity>
|
320 |
| - <pose>0.13 0.22 0.216 0 -0 0</pose> |
| 320 | + <pose>0.13 0.22 0.216 0 0 0</pose> |
321 | 321 | <visual name='rotor_2_visual_root'>
|
322 |
| - <pose>0 0 0 0 -0 0</pose> |
| 322 | + <pose>0 0 0 0 0 0</pose> |
323 | 323 | <geometry>
|
324 | 324 | <sphere>
|
325 | 325 | <radius>0.01</radius>
|
|
331 | 331 | </material>
|
332 | 332 | </visual>
|
333 | 333 | <visual name='rotor_2_visual_tip'>
|
334 |
| - <pose>0.12 0 0 0 -0 0</pose> |
| 334 | + <pose>0.12 0 0 0 0 0</pose> |
335 | 335 | <geometry>
|
336 | 336 | <sphere>
|
337 | 337 | <radius>0.01</radius>
|
|
343 | 343 | </material>
|
344 | 344 | </visual>
|
345 | 345 | <visual name='rotor_2_visual_cp'>
|
346 |
| - <pose>0.084 0 0 0 -0 0</pose> |
| 346 | + <pose>0.084 0 0 0 0 0</pose> |
347 | 347 | <geometry>
|
348 | 348 | <sphere>
|
349 | 349 | <radius>0.003</radius>
|
|
355 | 355 | </material>
|
356 | 356 | </visual>
|
357 | 357 | <visual name='rotor_2_visual_cp_forward'>
|
358 |
| - <pose>0.084 -0.02 0 0 -0 0</pose> |
| 358 | + <pose>0.084 -0.02 0 0 0 0</pose> |
359 | 359 | <geometry>
|
360 | 360 | <sphere>
|
361 | 361 | <radius>0.003</radius>
|
|
367 | 367 | </material>
|
368 | 368 | </visual>
|
369 | 369 | <visual name='rotor_2_visual_cp_upward'>
|
370 |
| - <pose>0.084 0 0.02 0 -0 0</pose> |
| 370 | + <pose>0.084 0 0.02 0 0 0</pose> |
371 | 371 | <geometry>
|
372 | 372 | <sphere>
|
373 | 373 | <radius>0.003</radius>
|
|
381 | 381 | </link>
|
382 | 382 | <link name="rotor_2_blade_2_cp">
|
383 | 383 | <gravity>0</gravity>
|
384 |
| - <pose>0.13 0.22 0.216 0 -0 0</pose> |
| 384 | + <pose>0.13 0.22 0.216 0 0 0</pose> |
385 | 385 | <visual name='rotor_2_visual_root'>
|
386 |
| - <pose>0 0 0 0 -0 0</pose> |
| 386 | + <pose>0 0 0 0 0 0</pose> |
387 | 387 | <geometry>
|
388 | 388 | <sphere>
|
389 | 389 | <radius>0.01</radius>
|
|
395 | 395 | </material>
|
396 | 396 | </visual>
|
397 | 397 | <visual name='rotor_2_visual_tip'>
|
398 |
| - <pose>-0.12 0 0 0 -0 0</pose> |
| 398 | + <pose>-0.12 0 0 0 0 0</pose> |
399 | 399 | <geometry>
|
400 | 400 | <sphere>
|
401 | 401 | <radius>0.01</radius>
|
|
407 | 407 | </material>
|
408 | 408 | </visual>
|
409 | 409 | <visual name='rotor_2_visual_cp'>
|
410 |
| - <pose>-0.084 0 0 0 -0 0</pose> |
| 410 | + <pose>-0.084 0 0 0 0 0</pose> |
411 | 411 | <geometry>
|
412 | 412 | <sphere>
|
413 | 413 | <radius>0.003</radius>
|
|
419 | 419 | </material>
|
420 | 420 | </visual>
|
421 | 421 | <visual name='rotor_2_visual_cp_forward'>
|
422 |
| - <pose>-0.084 0.02 0 0 -0 0</pose> |
| 422 | + <pose>-0.084 0.02 0 0 0 0</pose> |
423 | 423 | <geometry>
|
424 | 424 | <sphere>
|
425 | 425 | <radius>0.003</radius>
|
|
431 | 431 | </material>
|
432 | 432 | </visual>
|
433 | 433 | <visual name='rotor_2_visual_cp_upward'>
|
434 |
| - <pose>-0.084 0 0.02 0 -0 0</pose> |
| 434 | + <pose>-0.084 0 0.02 0 0 0</pose> |
435 | 435 | <geometry>
|
436 | 436 | <sphere>
|
437 | 437 | <radius>0.003</radius>
|
|
468 | 468 |
|
469 | 469 | <link name="rotor_3_blade_1_cp">
|
470 | 470 | <gravity>0</gravity>
|
471 |
| - <pose>-0.13 -0.2 0.216 0 -0 0</pose> |
| 471 | + <pose>-0.13 -0.2 0.216 0 0 0</pose> |
472 | 472 | <visual name='rotor_3_visual_root'>
|
473 |
| - <pose>0 0 0 0 -0 0</pose> |
| 473 | + <pose>0 0 0 0 0 0</pose> |
474 | 474 | <geometry>
|
475 | 475 | <sphere>
|
476 | 476 | <radius>0.01</radius>
|
|
482 | 482 | </material>
|
483 | 483 | </visual>
|
484 | 484 | <visual name='rotor_3_visual_tip'>
|
485 |
| - <pose>0.12 0 0 0 -0 0</pose> |
| 485 | + <pose>0.12 0 0 0 0 0</pose> |
486 | 486 | <geometry>
|
487 | 487 | <sphere>
|
488 | 488 | <radius>0.01</radius>
|
|
494 | 494 | </material>
|
495 | 495 | </visual>
|
496 | 496 | <visual name='rotor_3_visual_cp'>
|
497 |
| - <pose>0.084 0 0 0 -0 0</pose> |
| 497 | + <pose>0.084 0 0 0 0 0</pose> |
498 | 498 | <geometry>
|
499 | 499 | <sphere>
|
500 | 500 | <radius>0.003</radius>
|
|
506 | 506 | </material>
|
507 | 507 | </visual>
|
508 | 508 | <visual name='rotor_3_visual_cp_forward'>
|
509 |
| - <pose>0.084 -0.02 0 0 -0 0</pose> |
| 509 | + <pose>0.084 -0.02 0 0 0 0</pose> |
510 | 510 | <geometry>
|
511 | 511 | <sphere>
|
512 | 512 | <radius>0.003</radius>
|
|
518 | 518 | </material>
|
519 | 519 | </visual>
|
520 | 520 | <visual name='rotor_3_visual_cp_upward'>
|
521 |
| - <pose>0.084 0 0.02 0 -0 0</pose> |
| 521 | + <pose>0.084 0 0.02 0 0 0</pose> |
522 | 522 | <geometry>
|
523 | 523 | <sphere>
|
524 | 524 | <radius>0.003</radius>
|
|
532 | 532 | </link>
|
533 | 533 | <link name="rotor_3_blade_2_cp">
|
534 | 534 | <gravity>0</gravity>
|
535 |
| - <pose>-0.13 -0.2 0.216 0 -0 0</pose> |
| 535 | + <pose>-0.13 -0.2 0.216 0 0 0</pose> |
536 | 536 | <visual name='rotor_3_visual_root'>
|
537 |
| - <pose>0 0 0 0 -0 0</pose> |
| 537 | + <pose>0 0 0 0 0 0</pose> |
538 | 538 | <geometry>
|
539 | 539 | <sphere>
|
540 | 540 | <radius>0.01</radius>
|
|
546 | 546 | </material>
|
547 | 547 | </visual>
|
548 | 548 | <visual name='rotor_3_visual_tip'>
|
549 |
| - <pose>-0.12 0 0 0 -0 0</pose> |
| 549 | + <pose>-0.12 0 0 0 0 0</pose> |
550 | 550 | <geometry>
|
551 | 551 | <sphere>
|
552 | 552 | <radius>0.01</radius>
|
|
558 | 558 | </material>
|
559 | 559 | </visual>
|
560 | 560 | <visual name='rotor_3_visual_cp'>
|
561 |
| - <pose>-0.084 0 0 0 -0 0</pose> |
| 561 | + <pose>-0.084 0 0 0 0 0</pose> |
562 | 562 | <geometry>
|
563 | 563 | <sphere>
|
564 | 564 | <radius>0.003</radius>
|
|
570 | 570 | </material>
|
571 | 571 | </visual>
|
572 | 572 | <visual name='rotor_3_visual_cp_forward'>
|
573 |
| - <pose>-0.084 0.02 0 0 -0 0</pose> |
| 573 | + <pose>-0.084 0.02 0 0 0 0</pose> |
574 | 574 | <geometry>
|
575 | 575 | <sphere>
|
576 | 576 | <radius>0.003</radius>
|
|
582 | 582 | </material>
|
583 | 583 | </visual>
|
584 | 584 | <visual name='rotor_3_visual_cp_upward'>
|
585 |
| - <pose>-0.084 0 0.02 0 -0 0</pose> |
| 585 | + <pose>-0.084 0 0.02 0 0 0</pose> |
586 | 586 | <geometry>
|
587 | 587 | <sphere>
|
588 | 588 | <radius>0.003</radius>
|
|
791 | 791 | <!-- Frame conventions
|
792 | 792 | Require by ArduPilot: change model and gazebo from XYZ to XY-Z coordinates
|
793 | 793 | -->
|
794 |
| - <modelXYZToAirplaneXForwardZDown>0 0 0 3.141593 0 0</modelXYZToAirplaneXForwardZDown> |
795 |
| - <gazeboXYZToNED>0 0 0 3.141593 0 1.57079632</gazeboXYZToNED> |
| 794 | + <modelXYZToAirplaneXForwardZDown degrees="true">0 0 0 180 0 0</modelXYZToAirplaneXForwardZDown> |
| 795 | + <gazeboXYZToNED degrees="true">0 0 0 180 0 90</gazeboXYZToNED> |
796 | 796 |
|
797 | 797 | <!-- Sensors -->
|
798 | 798 | <imuName>iris_with_standoffs::imu_link::imu_sensor</imuName>
|
|
0 commit comments