forked from RobotLocomotion/drake
-
Notifications
You must be signed in to change notification settings - Fork 0
/
drakeURDF.xsd
1013 lines (938 loc) · 51.6 KB
/
drakeURDF.xsd
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
258
259
260
261
262
263
264
265
266
267
268
269
270
271
272
273
274
275
276
277
278
279
280
281
282
283
284
285
286
287
288
289
290
291
292
293
294
295
296
297
298
299
300
301
302
303
304
305
306
307
308
309
310
311
312
313
314
315
316
317
318
319
320
321
322
323
324
325
326
327
328
329
330
331
332
333
334
335
336
337
338
339
340
341
342
343
344
345
346
347
348
349
350
351
352
353
354
355
356
357
358
359
360
361
362
363
364
365
366
367
368
369
370
371
372
373
374
375
376
377
378
379
380
381
382
383
384
385
386
387
388
389
390
391
392
393
394
395
396
397
398
399
400
401
402
403
404
405
406
407
408
409
410
411
412
413
414
415
416
417
418
419
420
421
422
423
424
425
426
427
428
429
430
431
432
433
434
435
436
437
438
439
440
441
442
443
444
445
446
447
448
449
450
451
452
453
454
455
456
457
458
459
460
461
462
463
464
465
466
467
468
469
470
471
472
473
474
475
476
477
478
479
480
481
482
483
484
485
486
487
488
489
490
491
492
493
494
495
496
497
498
499
500
501
502
503
504
505
506
507
508
509
510
511
512
513
514
515
516
517
518
519
520
521
522
523
524
525
526
527
528
529
530
531
532
533
534
535
536
537
538
539
540
541
542
543
544
545
546
547
548
549
550
551
552
553
554
555
556
557
558
559
560
561
562
563
564
565
566
567
568
569
570
571
572
573
574
575
576
577
578
579
580
581
582
583
584
585
586
587
588
589
590
591
592
593
594
595
596
597
598
599
600
601
602
603
604
605
606
607
608
609
610
611
612
613
614
615
616
617
618
619
620
621
622
623
624
625
626
627
628
629
630
631
632
633
634
635
636
637
638
639
640
641
642
643
644
645
646
647
648
649
650
651
652
653
654
655
656
657
658
659
660
661
662
663
664
665
666
667
668
669
670
671
672
673
674
675
676
677
678
679
680
681
682
683
684
685
686
687
688
689
690
691
692
693
694
695
696
697
698
699
700
701
702
703
704
705
706
707
708
709
710
711
712
713
714
715
716
717
718
719
720
721
722
723
724
725
726
727
728
729
730
731
732
733
734
735
736
737
738
739
740
741
742
743
744
745
746
747
748
749
750
751
752
753
754
755
756
757
758
759
760
761
762
763
764
765
766
767
768
769
770
771
772
773
774
775
776
777
778
779
780
781
782
783
784
785
786
787
788
789
790
791
792
793
794
795
796
797
798
799
800
801
802
803
804
805
806
807
808
809
810
811
812
813
814
815
816
817
818
819
820
821
822
823
824
825
826
827
828
829
830
831
832
833
834
835
836
837
838
839
840
841
842
843
844
845
846
847
848
849
850
851
852
853
854
855
856
857
858
859
860
861
862
863
864
865
866
867
868
869
870
871
872
873
874
875
876
877
878
879
880
881
882
883
884
885
886
887
888
889
890
891
892
893
894
895
896
897
898
899
900
901
902
903
904
905
906
907
908
909
910
911
912
913
914
915
916
917
918
919
920
921
922
923
924
925
926
927
928
929
930
931
932
933
934
935
936
937
938
939
940
941
942
943
944
945
946
947
948
949
950
951
952
953
954
955
956
957
958
959
960
961
962
963
964
965
966
967
968
969
970
971
972
973
974
975
976
977
978
979
980
981
982
983
984
985
986
987
988
989
990
991
992
993
994
995
996
997
998
999
1000
<?xml version="1.0" encoding="UTF-8"?>
<xs:schema xmlns:xs="http://www.w3.org/2001/XMLSchema" targetNamespace="http://drake.mit.edu"
xmlns="http://drake.mit.edu" elementFormDefault="qualified">
<xs:annotation>
<xs:documentation>XML Schema for DrakeURDF v1.0
Documents URDF support for Drake, which implements much of the ROS URDF specification, but also adds a number of new elements.
</xs:documentation>
</xs:annotation>
<xs:simpleType name="matlab_parameter_expression">
<xs:annotation>
<xs:documentation>Can be any string that will evaluate as a polynomial using "eval" in the matlab environment, where parameters are referenced with $param_name.
Example:
"$m * $l^2"
or
"$m2 * ($lc2 - $l1)"
</xs:documentation>
</xs:annotation>
<xs:restriction base="xs:string"/>
</xs:simpleType>
<xs:complexType name="parameter">
<xs:attribute name="name" type="xs:string" use="required"/>
<xs:attribute name="value" type="xs:double" use="required"/>
<xs:attribute default="-INF" name="lb" type="xs:double" use="optional">
<xs:annotation>
<xs:documentation>lower bound</xs:documentation>
</xs:annotation>
</xs:attribute>
<xs:attribute default="INF" name="ub" type="xs:double" use="optional">
<xs:annotation>
<xs:documentation>upper bound
</xs:documentation>
</xs:annotation>
</xs:attribute>
</xs:complexType>
<xs:complexType name="loop_joint">
<xs:annotation>
<xs:documentation>You can add a loop joint if you have a kinematic loop (e.g. four-bar linkage, or even something more complicated) in your robot. To use this interface, you must first describe every link in your robot as part of a kinematic tree (no loops). You should be able to take a path through the linkages that touches everything without any loops. Then add the remaining loops by referencing existing links from the tree.
The loop joint is a one-degree of freedom joint oriented along the specified axis of the body frame in each link. Use the rpy fields of the link references to rotate that axis in the coordinate frame of the links.
There are a few limitations with the current implementation. We do not currently support joint limits nor actuators at the new joint created by the loop_joint tag. For all of the systems we have modeled so far, there has always been at least one of these "simple" joints in each kinematic loop; and we are simply careful to write down the initial kinematic tree so that it includes all of the more complex joints, leaving the simple joint as the loop joint.
</xs:documentation>
</xs:annotation>
<xs:all>
<xs:element name="link1" type="link_reference_w_pose" maxOccurs="1" minOccurs="1">
<xs:annotation>
<xs:documentation>String naming the link on one side of
the joint.</xs:documentation>
</xs:annotation>
</xs:element>
<xs:element name="link2" type="link_reference_w_pose" maxOccurs="1" minOccurs="1">
<xs:annotation>
<xs:documentation>String naming the link on the other side of
the joint.</xs:documentation>
</xs:annotation>
</xs:element>
<xs:element minOccurs="0" name="axis" type="axis" maxOccurs="1"/>
</xs:all>
<xs:attribute name="name" type="xs:string" use="required"/>
<xs:attribute fixed="continuous" name="type" type="xs:string" use="optional">
<xs:annotation>
<xs:documentation>Currently must be ’continuous’. The intent is to
eventually support all of the same types as a 'joint' element. See the joint element documentation.</xs:documentation>
</xs:annotation>
</xs:attribute>
</xs:complexType>
<xs:complexType name="force_element">
<xs:choice>
<xs:element name="linear_spring_damper" type="linear_spring_damper"/>
<xs:element name="wing" type="wing">
<xs:annotation>
<xs:documentation>Wing element supporting flat plates, airfoils. See wing_with_control_surface for a wing with a control surface attached.</xs:documentation>
</xs:annotation>
</xs:element>
<xs:element name="thrust" type="thrust">
<xs:annotation>
<xs:documentation>Thrust elements produce a force on a point on the parent body in a
specified direction. The magnitude of the force is scaled from an input
to the system. Possible applications are the throttle input and force
produced by a propeller on an airplane, or thrusters on the hands and
feet of an Atlas robot to make Iron Man.</xs:documentation>
</xs:annotation>
</xs:element>
<xs:element name="propellor" type="propellor">
<xs:annotation>
<xs:documentation>Propellor elements produce both a thrust at a point on the parent body in a
specified direction, along with a moment whose axis is the same as the thrust axis. This is useful for modelling propellors,
which typically produce both a thrust and a moment due to aerodynamic drag. The magnitude of the force and torque are scaled
from an input to the system, with different scalings for each.</xs:documentation>
</xs:annotation>
</xs:element>
<xs:element name="bluff_body" type="bluff_body">
<xs:annotation>
<xs:documentation>A bluff body that provides only drag force in xyz.</xs:documentation>
</xs:annotation>
</xs:element>
<xs:element name="added_mass" type="added_mass">
<xs:annotation>
<xs:documentation> Places added-mass coefficients on a point on the parent body. Added-mass forces act like a 'drag' that is proportional to the acceleration of the body, rather than the velocity. Important when the body is comparable in mass to the surrounding fluid, or if rapid motions are needed.
These forces are represented by a 6x6 matrix 'Ma' similar to a mass matrix, where the force is F=-Ma*a (+coriolis terms). Each matrix element is refered as 'mij', where 'i' and 'j' are the rows and columns of the matrix. As is standard in the oceanographic literature, rows 123 are the linear accelerations, and 456 are the angular accelerations [note this is opposite of Featherstone's notation] </xs:documentation>
</xs:annotation>
</xs:element>
<xs:element name="buoyancy" type="buoyancy">
<xs:annotation>
<xs:documentation> Adds a buoyancy force to the parent body, placed at a defined center of buoyancy. </xs:documentation>
</xs:annotation>
</xs:element>
<xs:element name="torsional_spring" type="torsional_spring"/>
</xs:choice>
<xs:attribute name="name" type="xs:string"/>
</xs:complexType>
<xs:complexType name="pose">
<xs:attribute name="xyz" type="xs:string" default="0 0 0">
<xs:annotation>
<xs:documentation>Represents the Cartesian offset</xs:documentation>
</xs:annotation>
</xs:attribute>
<xs:attribute name="rpy" type="xs:string" default="0 0 0">
<xs:annotation>
<xs:documentation>Represents the fixed-axis (aka extrinsic) roll, pitch and yaw angles in radians. </xs:documentation>
</xs:annotation>
</xs:attribute>
</xs:complexType>
<xs:complexType name="linear_spring_damper">
<xs:all>
<xs:element name="link1" type="link_reference_w_pose">
<xs:annotation>
<xs:documentation>String naming the link on one side
of the spring/damper with an (optional) pose specified relative to the coordinate system on the link</xs:documentation>
</xs:annotation>
</xs:element>
<xs:element name="link2" type="link_reference_w_pose">
<xs:annotation>
<xs:documentation>String naming the link on the other side
of the spring/damper with an (optional) pose specified relative to the coordinate system on the link</xs:documentation>
</xs:annotation>
</xs:element>
</xs:all>
<xs:attribute default="0" name="rest_length" type="xs:double"/>
<xs:attribute default="0" name="stiffness" type="xs:double">
<xs:annotation>
<xs:documentation>in Newtons per meter
</xs:documentation>
</xs:annotation>
</xs:attribute>
<xs:attribute default="0" name="damping" type="xs:double">
<xs:annotation>
<xs:documentation>in Newton seconds per meter. positive values resist motion.</xs:documentation>
</xs:annotation>
</xs:attribute>
</xs:complexType>
<xs:complexType name="torsional_spring">
<xs:annotation>
<xs:documentation>currently only supported for continuous and rotational joints. </xs:documentation>
</xs:annotation>
<xs:all>
<xs:element name="joint" type="joint_reference">
<xs:annotation>
<xs:documentation>String naming the joint of the spring/damper</xs:documentation>
</xs:annotation>
</xs:element>
</xs:all>
<xs:attribute default="0" name="rest_angle" type="xs:double">
<xs:annotation>
<xs:documentation>in radians</xs:documentation>
</xs:annotation>
</xs:attribute>
<xs:attribute default="0" name="stiffness" type="xs:double">
<xs:annotation>
<xs:documentation>in Newton-meters per radian
</xs:documentation>
</xs:annotation>
</xs:attribute>
</xs:complexType>
<xs:complexType name="wing">
<xs:all>
<xs:element name="parent" type="link_reference">
<xs:annotation>
<xs:documentation>String naming the link on which
this wing is attached.</xs:documentation>
</xs:annotation>
</xs:element>
<xs:element name="origin" type="pose" minOccurs="0">
<xs:annotation>
<xs:documentation>This defines the position of
the quarter-chord point of the airfoil, since that is the reference point
used for the moment coefficient. RPY support has been excluded, requiring
the axes of the airfoil to line up with those of its parent body.</xs:documentation>
</xs:annotation>
</xs:element>
</xs:all>
<xs:attribute name="profile" type="xs:string">
<xs:annotation>
<xs:documentation>one of the following
strings:
· The path to a .mat file that can be loaded and contains the three
variables ”CLSpline, CDSpline, CMSpline”
· The string, ’flat plate’
39
· File location of a .dat file generated by Xfoil
· A NACA airfoil designation: ’NACA0012’</xs:documentation>
</xs:annotation>
</xs:attribute>
<xs:attribute name="chord" type="xs:double">
<xs:annotation>
<xs:documentation>the chord length in
meters.</xs:documentation>
</xs:annotation>
</xs:attribute>
<xs:attribute name="span" type="xs:double">
<xs:annotation>
<xs:documentation>the span of the wing
in meters.</xs:documentation>
</xs:annotation>
</xs:attribute>
<xs:attribute name="stall_angle" type="xs:double">
<xs:annotation>
<xs:documentation>the angle
in degrees upon which the lift and drag performance returns to that of
a flat plate. (this value is ignored if the profile is set to a flat plate).</xs:documentation>
</xs:annotation>
</xs:attribute>
<xs:attribute name="nominal_speed" type="xs:double">
<xs:annotation>
<xs:documentation>an approximate
nominal speed in meters per second used to calculate the
Reynolds number around which we design the aerodynamic coefficients.</xs:documentation>
</xs:annotation>
</xs:attribute>
<xs:attribute name="visual_geometry" type="xs:boolean" default="true">
<xs:annotation>
<xs:documentation>enable or disable automatic drawing of the wing</xs:documentation>
</xs:annotation>
</xs:attribute>
</xs:complexType>
<xs:complexType name="wing_with_control_surface">
<xs:all>
<xs:element name="parent" type="link_reference">
<xs:annotation>
<xs:documentation>String naming the link on which
this wing is attached.</xs:documentation>
</xs:annotation>
</xs:element>
<xs:element name="origin" type="pose" minOccurs="0">
<xs:annotation>
<xs:documentation>This defines the position of
the quarter-chord point of the airfoil, since that is the reference point
used for the moment coefficient. RPY support has been excluded, requiring
the axes of the airfoil to line up with those of its parent body.</xs:documentation>
</xs:annotation>
</xs:element>
</xs:all>
<xs:attribute name="profile" type="xs:string">
<xs:annotation>
<xs:documentation>Only "flat plate" supported right now.</xs:documentation>
</xs:annotation>
</xs:attribute>
<xs:attribute name="chord" type="xs:double">
<xs:annotation>
<xs:documentation>the chord length in
meters.</xs:documentation>
</xs:annotation>
</xs:attribute>
<xs:attribute name="span" type="xs:double">
<xs:annotation>
<xs:documentation>the span of the wing
in meters.</xs:documentation>
</xs:annotation>
</xs:attribute>
<xs:attribute name="stall_angle" type="xs:double">
<xs:annotation>
<xs:documentation>the angle
in degrees upon which the lift and drag performance returns to that of
a flat plate. (this value is ignored if the profile is set to a flat plate).</xs:documentation>
</xs:annotation>
</xs:attribute>
<xs:attribute name="nominal_speed" type="xs:double">
<xs:annotation>
<xs:documentation>an approximate
nominal speed in meters per second used to calculate the
Reynolds number around which we design the aerodynamic coefficients.</xs:documentation>
</xs:annotation>
</xs:attribute>
<xs:attribute name="visual_geometry" type="xs:boolean" default="true">
<xs:annotation>
<xs:documentation>enable or disable automatic drawing of the wing</xs:documentation>
</xs:annotation>
</xs:attribute>
<xs:attribute name="control_surface_chord" type="xs:double" use="required">
<xs:annotation>
<xs:documentation>Length of the control surface.</xs:documentation>
</xs:annotation>
</xs:attribute>
<xs:attribute name="control_surface_min_deflection" type="xs:double" use="required">
<xs:annotation>
<xs:documentation>Minimum control surface deflection in radians. Typical is around -0.90</xs:documentation>
</xs:annotation>
</xs:attribute>
<xs:attribute name="control_surface_max_deflection" type="xs:double" use="required">
<xs:annotation>
<xs:documentation>Maximum control surface deflection in radians. Typical is around 0.90</xs:documentation>
</xs:annotation>
</xs:attribute>
</xs:complexType>
<xs:complexType name="bluff_body">
<xs:all>
<xs:element name="origin" type="pose" minOccurs="0">
<xs:annotation>
<xs:documentation>Position of the thrust element. Example: xyz="0 0 0" rpy="0 0 0".</xs:documentation>
</xs:annotation>
</xs:element>
</xs:all>
<xs:attribute name="name" type="xs:string" use="required"/>
<xs:attribute name="coefficient_drag_x" type="xs:double" use="required">
<xs:annotation>
<xs:documentation>coefficient of drag in the X dimension.</xs:documentation>
</xs:annotation>
</xs:attribute>
<xs:attribute name="coefficient_drag_y" type="xs:double" use="required">
<xs:annotation>
<xs:documentation>coefficient of drag in the Y dimension.</xs:documentation>
</xs:annotation>
</xs:attribute>
<xs:attribute name="coefficient_drag_z" type="xs:double" use="required">
<xs:annotation>
<xs:documentation>coefficient of drag in the Z dimension.</xs:documentation>
</xs:annotation>
</xs:attribute>
<xs:attribute name="area_x" type="xs:double" use="required">
<xs:annotation>
<xs:documentation>area of the bluff body for computing drag on the X axis.</xs:documentation>
</xs:annotation>
</xs:attribute>
<xs:attribute name="area_y" type="xs:double" use="required">
<xs:annotation>
<xs:documentation>area of the bluff body for computing drag on the Y axis.</xs:documentation>
</xs:annotation>
</xs:attribute>
<xs:attribute name="area_z" type="xs:double" use="required">
<xs:annotation>
<xs:documentation>area of the bluff body for computing drag on the Z axis.</xs:documentation>
</xs:annotation>
</xs:attribute>
<xs:attribute name="visual_geometry" type="xs:boolean" default="true">
<xs:annotation>
<xs:documentation>true to enable automatic drawing of the bluff_body as a red cube.</xs:documentation>
</xs:annotation>
</xs:attribute>
</xs:complexType>
<xs:complexType name="propellor">
<xs:all>
<xs:element name="parent" type="link_reference">
<xs:annotation>
<xs:documentation>String naming the link on which
this propellor is attached.</xs:documentation>
</xs:annotation>
</xs:element>
<xs:element name="axis" type="axis" minOccurs="0" maxOccurs="1">
<xs:annotation>
<xs:documentation>Axis the thrust element acts on. For example a propellor facing forward would point in the X-axis and you'd use: xyz="1 0 0". </xs:documentation>
</xs:annotation>
</xs:element>
<xs:element name="origin" type="pose" minOccurs="0">
<xs:annotation>
<xs:documentation>Position of the thrust element. Example: xyz="0 0 0" rpy="0 0 0".</xs:documentation>
</xs:annotation>
</xs:element>
</xs:all>
<xs:attribute name="name" type="xs:string" use="required"/>
<xs:attribute default="-INF" name="lower_limit" type="xs:double">
<xs:annotation>
<xs:documentation>input minimum.</xs:documentation>
</xs:annotation>
</xs:attribute>
<xs:attribute default="INF" name="upper_limit" type="xs:double">
<xs:annotation>
<xs:documentation>input maximum.</xs:documentation>
</xs:annotation>
</xs:attribute>
<xs:attribute default="1" name="scale_factor_thrust" type="xs:double">
<xs:annotation>
<xs:documentation>scales the dimensionless input to Newtons of force.</xs:documentation>
</xs:annotation>
</xs:attribute>
<xs:attribute default="1" name="scale_factor_moment" type="xs:double">
<xs:annotation>
<xs:documentation>scales the dimensionless input to newton-meters of torque.</xs:documentation>
</xs:annotation>
</xs:attribute>
<xs:attribute name="visual_geometry" type="xs:boolean" default="true">
<xs:annotation>
<xs:documentation>true to enable automatic drawing of the propellor.</xs:documentation>
</xs:annotation>
</xs:attribute>
<xs:attribute name="visual_diameter" type="xs:boolean" default="0.2">
<xs:annotation>
<xs:documentation>diameter of the propllor when drawn.</xs:documentation>
</xs:annotation>
</xs:attribute>
</xs:complexType>
<xs:complexType name="thrust">
<xs:all>
<xs:element name="parent" type="link_reference">
<xs:annotation>
<xs:documentation>String naming the link on
which the force will be applied.</xs:documentation>
</xs:annotation>
</xs:element>
<xs:element name="axis" type="axis" minOccurs="0" maxOccurs="1">
<xs:annotation>
<xs:documentation>Axis the thrust element acts on. For example a propellor facing forward would point in the X-axis and you'd use: xyz="1 0 0". </xs:documentation>
</xs:annotation>
</xs:element>
<xs:element name="origin" type="pose" minOccurs="0">
<xs:annotation>
<xs:documentation>Position of the thrust element. Example: xyz="0 0 0" rpy="0 0 0".</xs:documentation>
</xs:annotation>
</xs:element>
</xs:all>
<xs:attribute default="-INF" name="lower_limit" type="xs:double"/>
<xs:attribute default="INF" name="upper_limit" type="xs:double"/>
<xs:attribute default="1" name="scale_factor" type="xs:double">
<xs:annotation>
<xs:documentation>scales the dimensionless
input to Newtons of force.</xs:documentation>
</xs:annotation>
</xs:attribute>
</xs:complexType>
<xs:complexType name="added_mass">
<xs:all>
<xs:element name="parent" type="link_reference">
<xs:annotation>
<xs:documentation>String naming the link on which
this added-mass is attached.</xs:documentation>
</xs:annotation>
</xs:element>
<xs:element name="origin" type="pose" minOccurs="0">
<xs:annotation>
<xs:documentation>This defines the position where the added-mass matrix is defined, acting similar to a center-of-mass offset from the parent joint location. RPY is not supported. </xs:documentation>
</xs:annotation>
</xs:element>
</xs:all>
<xs:attribute name="m11" type="xs:double" default="0"/>
<xs:attribute name="m12" type="xs:double" default="0"/>
<xs:attribute name="m13" type="xs:double" default="0"/>
<xs:attribute name="m14" type="xs:double" default="0"/>
<xs:attribute name="m15" type="xs:double" default="0"/>
<xs:attribute name="m16" type="xs:double" default="0"/>
<xs:attribute name="m21" type="xs:double" default="0"/>
<xs:attribute name="m22" type="xs:double" default="0"/>
<xs:attribute name="m23" type="xs:double" default="0"/>
<xs:attribute name="m24" type="xs:double" default="0"/>
<xs:attribute name="m25" type="xs:double" default="0"/>
<xs:attribute name="m26" type="xs:double" default="0"/>
<xs:attribute name="m31" type="xs:double" default="0"/>
<xs:attribute name="m32" type="xs:double" default="0"/>
<xs:attribute name="m33" type="xs:double" default="0"/>
<xs:attribute name="m34" type="xs:double" default="0"/>
<xs:attribute name="m35" type="xs:double" default="0"/>
<xs:attribute name="m36" type="xs:double" default="0"/>
<xs:attribute name="m41" type="xs:double" default="0"/>
<xs:attribute name="m42" type="xs:double" default="0"/>
<xs:attribute name="m43" type="xs:double" default="0"/>
<xs:attribute name="m44" type="xs:double" default="0"/>
<xs:attribute name="m45" type="xs:double" default="0"/>
<xs:attribute name="m46" type="xs:double" default="0"/>
<xs:attribute name="m51" type="xs:double" default="0"/>
<xs:attribute name="m52" type="xs:double" default="0"/>
<xs:attribute name="m53" type="xs:double" default="0"/>
<xs:attribute name="m54" type="xs:double" default="0"/>
<xs:attribute name="m55" type="xs:double" default="0"/>
<xs:attribute name="m56" type="xs:double" default="0"/>
<xs:attribute name="m61" type="xs:double" default="0"/>
<xs:attribute name="m62" type="xs:double" default="0"/>
<xs:attribute name="m63" type="xs:double" default="0"/>
<xs:attribute name="m64" type="xs:double" default="0"/>
<xs:attribute name="m65" type="xs:double" default="0"/>
<xs:attribute name="m66" type="xs:double" default="0"/>
</xs:complexType>
<xs:complexType name="buoyancy">
<xs:all>
<xs:element name="parent" type="link_reference">
<xs:annotation>
<xs:documentation>String naming the link on which
this buoyancy is attached.</xs:documentation>
</xs:annotation>
</xs:element>
<xs:element name="origin" type="pose" minOccurs="0">
<xs:annotation>
<xs:documentation>This defines the position of the center of buoyancy. RPY is not supported. </xs:documentation>
</xs:annotation>
</xs:element>
</xs:all>
<xs:attribute name="volume" type="xs:double" default="0">
<xs:annotation>
<xs:documentation>Volume of the body</xs:documentation>
</xs:annotation>
</xs:attribute>
<xs:attribute name="rho" type="xs:double" default="1">
<xs:annotation>
<xs:documentation>Density of the fluid</xs:documentation>
</xs:annotation>
</xs:attribute>
</xs:complexType>
<xs:complexType name="cable">
<xs:all>
<xs:annotation>
<xs:documentation>Note: the order of the terminator, pulleys, and crossovers DOES MATTER - they specific the kinematic path of the cable.
e.g. terminator - pulley - pulley - crossover - pulley - terminator
</xs:documentation>
</xs:annotation>
<xs:element maxOccurs="2" minOccurs="2" name="terminator" type="link_reference_w_pose"/>
<xs:element form="qualified" maxOccurs="unbounded" minOccurs="0" name="pulley"
type="pulley">
<xs:annotation>
<xs:documentation>provides a radius about which the cable slides (as if it were frictionless - the actual motion of the pulley is not simulated)</xs:documentation>
</xs:annotation>
</xs:element>
</xs:all>
<xs:attribute default="cable" name="name"/>
<xs:attribute name="min_length" use="required"/>
<xs:attribute name="max_length" use="required"/>
</xs:complexType>
<xs:complexType name="pulley">
<xs:attribute name="link" type="xs:string" use="required"/>
<xs:attribute default="0 0 0" name="xyz" type="matlab_parameter_expression"/>
<xs:attribute default="0 0 0" name="axis" type="matlab_parameter_expression">
<xs:annotation>
<xs:documentation>the cable wraps counter-clockwise (right-hand rule) around the pulley axis</xs:documentation>
</xs:annotation>
</xs:attribute>
<xs:attribute default="0" name="radius" type="matlab_parameter_expression">
<xs:annotation>
<xs:documentation>All attachments are implemented as (frictionless) pulleys. Simple attachments are pulleys of radius zero.</xs:documentation>
</xs:annotation>
</xs:attribute>
<xs:attribute name="number_of_wraps" type="xs:int">
<xs:annotation>
<xs:documentation>Number of times that the cable is wrapped completely around a pulley. Adds additional 2*pi*radius*number_of_wraps to the computed length of the cable.</xs:documentation>
</xs:annotation>
</xs:attribute>
</xs:complexType>
<xs:simpleType name="joint_type">
<xs:restriction base="xs:string">
<xs:enumeration value="revolute"/>
<xs:enumeration value="continuous"/>
<xs:enumeration value="prismatic"/>
<xs:enumeration value="fixed"/>
<xs:enumeration value="floating"/>
<xs:enumeration value="planar"/>
<xs:enumeration value="ball"/>
</xs:restriction>
</xs:simpleType>
<xs:complexType name="color">
<xs:attribute name="rgba" type="xs:string" default="0 0 0 0">
<xs:annotation>
<xs:documentation>The color of a material specified by set of four numbers representing red/green/blue/alpha, each in the range of [0,1]. </xs:documentation>
</xs:annotation>
</xs:attribute>
</xs:complexType>
<xs:complexType name="mass">
<xs:attribute name="value" type="xs:double" default="0"/>
</xs:complexType>
<xs:complexType name="inertia">
<xs:attribute name="ixx" type="matlab_parameter_expression" default="0"/>
<xs:attribute name="ixy" type="matlab_parameter_expression" default="0"/>
<xs:attribute name="ixz" type="matlab_parameter_expression" default="0"/>
<xs:attribute name="iyy" type="matlab_parameter_expression" default="0"/>
<xs:attribute name="iyz" type="matlab_parameter_expression" default="0"/>
<xs:attribute name="izz" type="matlab_parameter_expression" default="0"/>
</xs:complexType>
<xs:complexType name="inertial">
<xs:all>
<xs:element name="origin" type="pose" minOccurs="0" maxOccurs="1">
<xs:annotation>
<xs:documentation>This is the pose of the inertial reference frame, relative to the link reference frame. The origin of the inertial reference frame needs to be at the center of gravity. The axes of the inertial reference frame do not need to be aligned with the principal axes of the inertia. </xs:documentation>
</xs:annotation>
</xs:element>
<xs:element name="mass" type="mass" minOccurs="0" maxOccurs="1">
<xs:annotation>
<xs:documentation>The mass of the link is represented by the value attribute of this element </xs:documentation>
</xs:annotation>
</xs:element>
<xs:element name="inertia" type="inertia" minOccurs="0" maxOccurs="1">
<xs:annotation>
<xs:documentation>The 3x3 rotational inertia matrix, represented in the inertia frame (as defined by the origin tag, e.g., about the center of mass of this link). Because the rotational inertia matrix is symmetric, only 6 above-diagonal elements of this matrix are specified here, using the attributes ixx, ixy, ixz, iyy, iyz, izz. </xs:documentation>
</xs:annotation>
</xs:element>
</xs:all>
</xs:complexType>
<xs:complexType name="box">
<xs:attribute name="size" type="xs:string" default="0 0 0"/>
</xs:complexType>
<xs:complexType name="cylinder">
<xs:attribute name="radius" type="xs:double" use="required"/>
<xs:attribute name="length" type="xs:double" use="required"/>
</xs:complexType>
<xs:complexType name="sphere">
<xs:attribute name="radius" type="xs:double" use="required"/>
</xs:complexType>
<xs:complexType name="mesh">
<xs:attribute name="filename" type="xs:anyURI" use="required"/>
<xs:attribute name="scale" type="xs:string" default="1 1 1"/>
</xs:complexType>
<xs:complexType name="capsule">
<xs:attribute name="radius" type="xs:double" use="required"/>
<xs:attribute name="length" type="xs:double" use="required"/>
</xs:complexType>
<xs:complexType name="geometry">
<xs:choice>
<xs:element name="box" type="box">
<xs:annotation>
<xs:documentation>size attribute contains the three side lengths of the box. The origin of the box is in its center. </xs:documentation>
</xs:annotation>
</xs:element>
<xs:element name="cylinder" type="cylinder">
<xs:annotation>
<xs:documentation>Specify the radius and length. The origin of the cylinder is in its center.</xs:documentation>
</xs:annotation>
</xs:element>
<xs:element name="sphere" type="sphere">
<xs:annotation>
<xs:documentation>Specify the radius. The origin of the sphere is in its center. </xs:documentation>
</xs:annotation>
</xs:element>
<xs:element name="mesh" type="mesh">
<xs:annotation>
<xs:documentation>A trimesh element specified by a filename, and an optional scale that scales the mesh's axis-aligned-bounding-box. The recommended format for best texture and color support is Collada .dae files, though .stl files are also supported. The mesh file is not transferred between machines referencing the same model. It must be a local file. </xs:documentation>
</xs:annotation>
</xs:element>
<xs:element name="superellipsoid">
<xs:complexType>
<xs:attribute default="1 1 1" name="size" type="xs:string">
<xs:annotation>
<xs:documentation>3 element double semi-diameter of the ellipse in x,y, and z</xs:documentation>
</xs:annotation>
</xs:attribute>
<xs:attribute default="1 1" name="shape" type="xs:string">
<xs:annotation>
<xs:documentation>2 element double "squareness" of the ellipsoid in the xy-plane and then the z-plane http://paulbourke.net/geometry/superellipse/ </xs:documentation>
</xs:annotation>
</xs:attribute>
</xs:complexType>
</xs:element>
</xs:choice>
</xs:complexType>
<xs:complexType name="material">
<xs:sequence>
<xs:element name="color" type="color" minOccurs="0" maxOccurs="1"/>
</xs:sequence>
<xs:attribute name="name" type="xs:string"/>
</xs:complexType>
<xs:complexType name="visual">
<xs:all>
<xs:element name="origin" type="pose" minOccurs="0" maxOccurs="1"/>
<xs:element name="geometry" type="geometry" minOccurs="1" maxOccurs="1">
<xs:annotation>
<xs:documentation>The shape of the visual object.</xs:documentation>
</xs:annotation>
</xs:element>
<xs:element name="material" type="material" minOccurs="0" maxOccurs="1">
<xs:annotation>
<xs:documentation>The material of the visual element. It is allowed to specify a material element outside of the 'link' object, in the top level 'robot' element. From within a link element you can then reference the material by name. </xs:documentation>
</xs:annotation>
</xs:element>
</xs:all>
</xs:complexType>
<xs:complexType name="collision">
<xs:all>
<xs:element name="origin" type="pose" minOccurs="0" maxOccurs="1"/>
<xs:element name="geometry" type="geometry" minOccurs="1" maxOccurs="1"/>
</xs:all>
<xs:attribute name="name" type="xs:string"/>
<xs:attribute name="group" type="xs:string"/>
</xs:complexType>
<xs:complexType name="link">
<xs:sequence>
<xs:element name="inertial" type="inertial" minOccurs="0" maxOccurs="1">
<xs:annotation>
<xs:documentation>The inertial properties of the link. </xs:documentation>
</xs:annotation>
</xs:element>
<xs:element name="visual" type="visual" minOccurs="0" maxOccurs="unbounded">
<xs:annotation>
<xs:documentation>The visual properties of the link. This element specifies the shape of the object (box, cylinder, etc.) for visualization purposes. Note: multiple instances of visual tags can exist for the same link. The union of the geometry they define forms the visual representation of the link. </xs:documentation>
</xs:annotation>
</xs:element>
<xs:element name="collision" type="collision" minOccurs="0" maxOccurs="unbounded">
<xs:annotation>
<xs:documentation>The collision properties of a link. Note that this can be different from the visual properties of a link, for example, simpler collision models are often used to reduce computation time. Note: multiple instances of collision tags can exist for the same link. The union of the geometry they define forms the collision representation of the link. </xs:documentation>
</xs:annotation>
</xs:element>
<xs:element maxOccurs="unbounded" minOccurs="0" name="sensor" type="sensor"/>
</xs:sequence>
<xs:attribute name="name" type="xs:string" use="required">
<xs:annotation>
<xs:documentation>The name of the link itself </xs:documentation>
</xs:annotation>
</xs:attribute>
<xs:attribute default="false" name="drake_ignore" type="xs:boolean">
<xs:annotation>
<xs:documentation>set to true to instruct the drake parser to skip this link</xs:documentation>
</xs:annotation>
</xs:attribute>
</xs:complexType>
<xs:complexType name="link_reference">
<xs:attribute name="link" type="xs:string" use="required"/>
</xs:complexType>
<xs:complexType name="link_reference_w_pose">
<xs:attribute name="link" type="xs:string" use="required"/>
<xs:attribute default="0 0 0" name="xyz" type="matlab_parameter_expression"/>
<xs:attribute default="0 0 0" name="rpy" type="matlab_parameter_expression"/>
</xs:complexType>
<xs:complexType name="axis">
<xs:attribute name="xyz" type="matlab_parameter_expression" default="1 0 0"/>
</xs:complexType>
<xs:complexType name="dynamics">
<xs:attribute name="damping" type="matlab_parameter_expression" default="0">
<xs:annotation>
<xs:documentation>The physical damping value of the joint</xs:documentation>
</xs:annotation>
</xs:attribute>
<xs:attribute name="friction" type="matlab_parameter_expression">
<xs:annotation>
<xs:documentation>coulomb friction coefficient.
total friction force is a piecewise linear approximation of sgn(qd)*Fc + qd*Fd:
f_friction = min(1,max(-1,qd./m.coulomb_window')).*m.coulomb_friction' + m.damping'.*qd;
</xs:documentation>
</xs:annotation>
</xs:attribute>
<xs:attribute name="coulomb_window" type="matlab_parameter_expression">
<xs:annotation>
<xs:documentation>determines the threshold in qd when the coulomb term saturates (F_c = sgn(qd)*coulomb_friction.
total friction force is a piecewise linear approximation of sgn(qd)*Fc + qd*Fd:
f_friction = min(1,max(-1,qd./m.coulomb_window')).*m.coulomb_friction' + m.damping'.*qd;
</xs:documentation>
</xs:annotation>
</xs:attribute>
</xs:complexType>
<xs:complexType name="limit">
<xs:attribute name="lower" type="matlab_parameter_expression" default="-inf">
<xs:annotation>
<xs:documentation>An attribute specifying the lower joint limit (radians for revolute joints, meters for prismatic joints). Omit if joint is continuous.</xs:documentation>
</xs:annotation>
</xs:attribute>
<xs:attribute name="upper" type="matlab_parameter_expression" default="inf">
<xs:annotation>
<xs:documentation>An attribute specifying the upper joint limit (radians for revolute joints, meters for prismatic joints). Omit if joint is continuous. </xs:documentation>
</xs:annotation>
</xs:attribute>
<xs:attribute name="effort" type="matlab_parameter_expression" default="inf">
<xs:annotation>
<xs:documentation>An attribute for enforcing the maximum joint effort</xs:documentation>
</xs:annotation>
</xs:attribute>
<xs:attribute default="-inf" name="effort_min" type="matlab_parameter_expression">
<xs:annotation>
<xs:documentation>maximum joint effort. If both 'effort' and 'effort_min' are specified, then effort_min takes priority.</xs:documentation>
</xs:annotation>
</xs:attribute>
<xs:attribute default="inf" name="effort_max" type="matlab_parameter_expression">
<xs:annotation>
<xs:documentation>maximum joint effort. If both 'effort' and 'effort_max' are specified, then effort_max takes priority.</xs:documentation>
</xs:annotation>
</xs:attribute>
</xs:complexType>
<xs:complexType name="joint">
<xs:all>
<xs:element name="origin" type="pose" minOccurs="0" maxOccurs="1">
<xs:annotation>
<xs:documentation>This is the transform from the parent link to the child link. The joint is located at the origin of the child link, as shown in the figure above. </xs:documentation>
</xs:annotation>
</xs:element>
<xs:element name="parent" type="link_reference" minOccurs="1" maxOccurs="1">
<xs:annotation>
<xs:documentation>Parent link name</xs:documentation>
</xs:annotation>
</xs:element>
<xs:element name="child" type="link_reference" minOccurs="1" maxOccurs="1">
<xs:annotation>
<xs:documentation>Child link name</xs:documentation>
</xs:annotation>
</xs:element>
<xs:element name="axis" type="axis" minOccurs="0" maxOccurs="1">
<xs:annotation>
<xs:documentation>The joint axis specified in the joint frame. This is the axis of rotation for revolute joints, the axis of translation for prismatic joints, and the surface normal for planar joints. The axis is specified in the joint frame of reference. Fixed and floating joints do not use the axis field. </xs:documentation>
</xs:annotation>
</xs:element>
<xs:element name="dynamics" type="dynamics" minOccurs="0" maxOccurs="1">
<xs:annotation>
<xs:documentation>An element specifying physical properties of the joint. These values are used to specify modeling properties of the joint, particularly useful for simulation. </xs:documentation>
</xs:annotation>
</xs:element>
<xs:element name="limit" type="limit" minOccurs="0" maxOccurs="1"/>
</xs:all>
<xs:attribute name="name" type="xs:string" use="required"/>
<xs:attribute name="type" type="joint_type" use="required">
<xs:annotation>
<xs:documentation>Specifies the type of joint, where type can be one of the following:
revolute - a hinge joint that rotates along the axis and has a limited range specified by the upper and lower limits.
continuous - a continuous hinge joint that rotates around the axis and has no upper and lower limits
prismatic - a sliding joint that slides along the axis, and has a limited range specified by the upper and lower limits.
fixed - This is not really a joint because it cannot move. All degrees of freedom are locked. This type of joint does not require the axis, calibration, dynamics, limits or safety_controller.
floating - This joint allows motion for all 6 degrees of freedom.
planar - This joint allows motion in a plane perpendicular to the axis.
ball - This joint allows free rotation in all directions with no upper or lower limits. </xs:documentation>
</xs:annotation>
</xs:attribute>
<xs:attribute default="1" name="has_position_sensor" type="xs:boolean" use="optional"/>
<xs:attribute default="false" name="drake_ignore" type="xs:boolean">
<xs:annotation>
<xs:documentation>set to true to instruct the drake parser to skip this link</xs:documentation>
</xs:annotation>
</xs:attribute>
</xs:complexType>
<xs:complexType name="joint_reference">
<xs:attribute name="name" type="xs:string"/>
</xs:complexType>
<xs:complexType name="gazebo_sensor">
<xs:sequence>
<xs:element name="pose" type="matlab_parameter_expression"/>
</xs:sequence>
<xs:attribute name="name" type="xs:string"/>
<xs:attribute name="type" type="sensor_type"/>
</xs:complexType>
<xs:complexType name="gazebo">
<xs:sequence>
<xs:element maxOccurs="unbounded" minOccurs="0" name="sensor" type="gazebo_sensor"/>
</xs:sequence>
<xs:attribute name="reference" type="xs:string"/>
</xs:complexType>
<xs:complexType name="sensor">
<xs:all>
<xs:element maxOccurs="1" minOccurs="0" name="pose" type="pose"/>
</xs:all>
<xs:attribute name="name" type="xs:string"/>
<xs:attribute name="type" type="sensor_type"/>
</xs:complexType>
<xs:simpleType name="sensor_type">
<xs:restriction base="xs:string">
<xs:enumeration value="imu"/>
<xs:enumeration value="contact"/>
</xs:restriction>
</xs:simpleType>
<xs:complexType name="transmission">
<xs:all>
<xs:element maxOccurs="1" minOccurs="1" name="joint" type="joint_reference"/>
<xs:element maxOccurs="1" minOccurs="1" name="actuator" type="actuator"/>
<xs:element default="1" maxOccurs="1" minOccurs="0" name="mechanicalReduction"
type="xs:double"/>
</xs:all>
<xs:attribute name="name" type="xs:string"/>
<xs:attribute name="type" type="transmission_type"/>
</xs:complexType>
<xs:complexType name="actuator">
<xs:attribute name="name" type="xs:string"/>
</xs:complexType>
<xs:simpleType name="transmission_type">
<xs:restriction base="xs:string">
<xs:enumeration value="SimpleTransmission"/>
</xs:restriction>
</xs:simpleType>
<xs:element name="robot">
<xs:complexType>
<xs:sequence minOccurs="0" maxOccurs="unbounded">
<xs:element name="joint" type="joint" minOccurs="0" maxOccurs="unbounded">
<xs:annotation>
<xs:documentation>The joint element describes the kinematics and dynamics of the joint and also specifies the safety limits of the joint. </xs:documentation>
</xs:annotation>
</xs:element>
<xs:element name="link" type="link" minOccurs="0" maxOccurs="unbounded">
<xs:annotation>
<xs:documentation>The link element describes a rigid body with an inertia, visual features, ...</xs:documentation>
</xs:annotation>
</xs:element>
<xs:element maxOccurs="unbounded" minOccurs="0" name="transmission"
type="transmission"/>
<xs:element name="material" type="material" minOccurs="0" maxOccurs="unbounded">
<xs:annotation>
<xs:documentation>The material of the visual element. It is allowed to specify a material element outside of the 'link' object, in the top level 'robot' element. From within a link element you can then reference the material by name. </xs:documentation>
</xs:annotation>
</xs:element>
<xs:element maxOccurs="unbounded" minOccurs="0" name="parameter" type="parameter">
<xs:annotation>
<xs:documentation>A robot parameter, which can be referenced in matlab_parameter_expression types. For example, a parameter with name="m1" could be references in mass value="$m1". </xs:documentation>
</xs:annotation>
</xs:element>
<xs:element maxOccurs="unbounded" minOccurs="0" name="loop_joint" type="loop_joint">
<xs:annotation>
<xs:documentation>Adds support for simple closed-loop kinematic chains. For an example, see
examples/simple_four_bar/FourBar.urdf
Note: We do not support dynamics or torque at the loop_joint
yet. (see bug 921)</xs:documentation>
</xs:annotation>
</xs:element>
<xs:element name="force_element" type="force_element" maxOccurs="unbounded"
minOccurs="0">
<xs:annotation>
<xs:documentation>Adds dynamic, force-producing elements like springs and aerodynamics</xs:documentation>
</xs:annotation>
</xs:element>
<xs:element maxOccurs="unbounded" minOccurs="0" name="collision_filter_group"
type="collision_filter_group"/>
<xs:element maxOccurs="unbounded" minOccurs="0" name="frame">
<xs:complexType>
<xs:complexContent>
<xs:extension base="link_reference_w_pose">
<xs:attribute name="name"/>
</xs:extension>
</xs:complexContent>
</xs:complexType>
</xs:element>
</xs:sequence>
<xs:attribute name="name" type="xs:string" use="required"/>
<xs:attribute name="version" type="xs:string" default="1.0"/>
</xs:complexType>
</xs:element>
<xs:complexType name="collision_filter_group_reference">
<xs:attribute name="collision_filter_group"/>
</xs:complexType>
<xs:complexType name="collision_filter_group">
<xs:annotation>
<xs:documentation>Provides a means to exclude certain pairs of bodies from collision detection and closest distance computations. A collision filter group can contain one or more links, and a link may belong to any number of collision filter groups. Given two links A and B by default they are specified to be checked for collision. If they are adjacent in the kinematic tree, then they are not checked for collision unless one is the world link and the jointing connecting them is a floating base joint. If link A is in a collision filter group Alpha and link B is in a collision filter group Beta and Beta is in Alpha.ignored_collision_filter group then A and B are not checked for collision. The same also holds in reverse, i.e. if Alpha is in Beta.ignored_collision_filter_group then links A and B are not in collision. However only one of the two conditions is necessary for excluding the pair of bodies from collision detection.</xs:documentation>
</xs:annotation>
<xs:sequence>
<xs:element name="member" type="link_reference" maxOccurs="unbounded" minOccurs="0">
<xs:annotation>