-
Notifications
You must be signed in to change notification settings - Fork 1.3k
/
Copy pathdetail_mujoco_parser.cc
1995 lines (1817 loc) · 77.7 KB
/
detail_mujoco_parser.cc
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
#include "drake/multibody/parsing/detail_mujoco_parser.h"
#include <algorithm>
#include <filesystem>
#include <limits>
#include <map>
#include <memory>
#include <set>
#include <string>
#include <tuple>
#include <utility>
#include <vector>
#include <fmt/format.h>
#include <tinyxml2.h>
#include "drake/common/text_logging.h"
#include "drake/geometry/proximity/obb.h"
#include "drake/geometry/proximity/obj_to_surface_mesh.h"
#include "drake/geometry/shape_specification.h"
#include "drake/math/rigid_transform.h"
#include "drake/math/rotation_matrix.h"
#include "drake/multibody/parsing/detail_make_model_name.h"
#include "drake/multibody/parsing/detail_tinyxml.h"
#include "drake/multibody/parsing/detail_tinyxml2_diagnostic.h"
#include "drake/multibody/tree/ball_rpy_joint.h"
#include "drake/multibody/tree/geometry_spatial_inertia.h"
#include "drake/multibody/tree/prismatic_joint.h"
#include "drake/multibody/tree/revolute_joint.h"
#include "drake/multibody/tree/scoped_name.h"
#include "drake/multibody/tree/weld_joint.h"
namespace drake {
namespace multibody {
namespace internal {
using drake::internal::DiagnosticPolicy;
using Eigen::Matrix3d;
using Eigen::Vector2d;
using Eigen::Vector3d;
using Eigen::Vector4d;
using geometry::GeometryId;
using geometry::GeometryInstance;
using math::RigidTransformd;
using math::RotationMatrixd;
using tinyxml2::XMLAttribute;
using tinyxml2::XMLDocument;
using tinyxml2::XMLElement;
using tinyxml2::XMLNode;
namespace {
constexpr std::array kOrientationAttributes = { // BR
"quat", "axisangle", "euler", "xyaxes", "zaxis"};
class MujocoParser {
public:
explicit MujocoParser(const ParsingWorkspace& workspace,
const DataSource& data_source)
: workspace_(workspace),
diagnostic_(&workspace.diagnostic, &data_source),
plant_(workspace.plant) {
// Clang complains that the workspace_ field is unused. Nerf the warning
// for now; it will be used soon.
unused(workspace_);
}
void ErrorIfMoreThanOneOrientation(const XMLElement& node) {
int num_orientation_attrs = 0;
for (const char* attr : kOrientationAttributes) {
if (node.Attribute(attr) != nullptr) {
++num_orientation_attrs;
}
}
if (num_orientation_attrs > 1) {
std::string attributes;
for (const XMLAttribute* attr = node.FirstAttribute(); attr;
attr = attr->Next()) {
attributes += fmt::format("{}={} ", attr->Name(),
fmt_debug_string(attr->Value()));
}
Error(node,
fmt::format(
"Element {} has more than one orientation attribute specified. "
"There must be no more than one instance of `quat`, "
"`axisangle`, `euler`, `xyaxes`, or `zaxis`. "
"Attributes: [{}]",
node.Name(), attributes));
}
}
// Any attributes from `default` that are not specified in `node` will be
// added to `node`. For orientation attributes, we do not apply orientation
// attribute defaults if the node already has an orientation attribute.
void ApplyDefaultAttributes(const XMLElement& default_node,
XMLElement* node) {
bool node_has_orientation_attr = false;
for (const char* attr : kOrientationAttributes) {
if (node->Attribute(attr) != nullptr) {
node_has_orientation_attr = true;
break;
}
}
for (const XMLAttribute* default_attr = default_node.FirstAttribute();
default_attr != nullptr; default_attr = default_attr->Next()) {
if (!node->Attribute(default_attr->Name())) {
if (node_has_orientation_attr &&
std::find_if(kOrientationAttributes.cbegin(),
kOrientationAttributes.cend(),
[&default_attr](const char* attr) {
return strcmp(attr, default_attr->Name()) == 0;
}) != kOrientationAttributes.cend()) {
// Don't apply default orientation attributes if the node already has
// an orientation attribute.
continue;
}
node->SetAttribute(default_attr->Name(), default_attr->Value());
}
}
}
RigidTransformd ParseTransform(
XMLElement* node, const RigidTransformd& X_default = RigidTransformd{}) {
Vector3d pos(X_default.translation());
ParseVectorAttribute(node, "pos", &pos);
ErrorIfMoreThanOneOrientation(*node);
if (node->Attribute("quat") != nullptr) {
Vector4d quat; // MuJoCo uses w,x,y,z order.
if (ParseVectorAttribute(node, "quat", &quat)) {
return RigidTransformd(
Eigen::Quaternion<double>(quat[0], quat[1], quat[2], quat[3]), pos);
}
}
Vector4d axisangle;
if (ParseVectorAttribute(node, "axisangle", &axisangle)) {
if (angle_ == kDegree) {
axisangle[3] *= (M_PI / 180.0);
}
return RigidTransformd(
Eigen::AngleAxis<double>(axisangle[3], axisangle.head<3>()), pos);
}
Vector3d euler;
if (ParseVectorAttribute(node, "euler", &euler)) {
if (angle_ == kDegree) {
euler *= (M_PI / 180.0);
}
Quaternion<double> quat(1, 0, 0, 0);
DRAKE_DEMAND(eulerseq_.size() == 3);
for (int i = 0; i < 3; ++i) {
Quaternion<double> this_quat(cos(euler[i] / 2.0), 0, 0, 0);
double sa = sin(euler[i] / 2.0);
if (eulerseq_[i] == 'x' || eulerseq_[i] == 'X') {
this_quat.x() = sa;
} else if (eulerseq_[i] == 'y' || eulerseq_[i] == 'Y') {
this_quat.y() = sa;
} else {
// We already confirmed that eulerseq_ only has 'xyzXYZ' when it was
// parsed.
DRAKE_DEMAND(eulerseq_[i] == 'z' || eulerseq_[i] == 'Z');
this_quat.z() = sa;
}
if (eulerseq_[i] == 'x' || eulerseq_[i] == 'y' || eulerseq_[i] == 'z') {
// moving axes: post-multiply
quat = quat * this_quat;
} else {
// fixed axes: pre-multiply
quat = this_quat * quat;
}
}
return RigidTransformd(RotationMatrixd(quat), pos);
}
Vector6d xyaxes;
if (ParseVectorAttribute(node, "xyaxes", &xyaxes)) {
if (xyaxes.head<3>().norm() < 1e-12) {
Error(*node,
fmt::format(
"The x axis in the 'xyaxes' attribute '{}' is too small.",
node->Attribute("xyaxes")));
return {};
}
if (xyaxes.tail<3>().norm() < 1e-12) {
Error(*node,
fmt::format(
"The y axis in the 'xyaxes' attribute '{}' is too small.",
node->Attribute("xyaxes")));
return {};
}
Matrix3d R;
// Normalize the x axis.
R.col(0) = xyaxes.head<3>().normalized();
// Make the y axis orthogonal to the x axis (and normalize).
double d = R.col(0).dot(xyaxes.tail<3>());
R.col(1) = (xyaxes.tail<3>() - d * R.col(0)).normalized();
// Make the z axis orthogonal to the x and y axes (and normalize).
R.col(2) = R.col(0).cross(R.col(1)).normalized();
return RigidTransformd(RotationMatrixd(R), pos);
}
Vector3d zaxis;
if (ParseVectorAttribute(node, "zaxis", &zaxis)) {
// Minimal rotation that maps the vector (0,0,1) into the vector specified
// here.
return RigidTransformd(
Eigen::Quaternion<double>::FromTwoVectors(Vector3d{0, 0, 1}, zaxis),
pos);
}
return RigidTransformd(X_default.rotation(), pos);
}
// Returns true if limits were parsed.
bool ParseLimits(XMLElement* node, const char* range_attr_name,
const char* limited_attr_name, Vector2d* limits) {
std::string limited_attr;
if (!ParseStringAttribute(node, limited_attr_name, &limited_attr)) {
limited_attr = "auto";
}
bool has_range = ParseVectorAttribute(node, range_attr_name, limits);
bool limited{false};
if (limited_attr == "true") {
limited = true;
} else if (limited_attr == "false") {
limited = false;
} else if (limited_attr == "auto") {
if (autolimits_) {
limited = has_range;
} else if (has_range) {
// From the mujoco docs: In this mode [autolimits == false], it is an
// error to specify a range without a limit.
Error(*node, fmt::format("The '{}' attribute was specified but "
"'autolimits' is disabled.",
range_attr_name));
}
} else {
Error(*node,
fmt::format("The '{}' attribute must be one of 'true', 'false', "
"or 'auto'.",
limited_attr_name));
}
return limited;
}
void ParseMotorOrPosition(XMLElement* node) {
std::string name;
if (!ParseStringAttribute(node, "name", &name)) {
// Use "motor#" as the default actuator name.
name = fmt::format("motor{}", plant_->num_actuators());
}
std::string joint_name;
if (!ParseStringAttribute(node, "joint", &joint_name)) {
Warning(*node, fmt::format(
"The motor '{}' does not use the 'joint' transmission "
"specification. Currently only the 'joint' attribute "
"is supported. This motor will be ignored.",
name));
return;
}
// Parse effort limits. For a motor, force limits are the same as control
// limits, so we take the min of the two.
double effort_limit = std::numeric_limits<double>::infinity();
Vector2d ctrl_range(0.0, 0.0), force_range(0.0, 0.0);
bool ctrl_limited =
ParseLimits(node, "ctrlrange", "ctrllimited", &ctrl_range);
bool force_limited =
ParseLimits(node, "forcerange", "forcelimited", &force_range);
if (ctrl_limited) {
if (ctrl_range[0] > ctrl_range[1]) {
Warning(
*node,
fmt::format(
"The motor '{}' specified a ctrlrange attribute where lower "
"limit > upper limit; these limits will be ignored.",
name));
} else {
effort_limit = std::max(ctrl_range[1], -ctrl_range[0]);
if (-ctrl_range[0] != ctrl_range[1]) {
Warning(*node,
fmt::format("The motor '{}' specified a ctrlrange attribute "
"where lower limit != -upper limit. Asymmetrical "
"effort limits are not supported yet, so the "
"larger of the values {} will be used.",
name, effort_limit));
}
}
}
if (force_limited) {
// For a motor, force limits are the same as control limits, so we take
// the min of the two.
if (force_range[0] > force_range[1]) {
Warning(
*node,
fmt::format(
"The motor '{}' specified a forcerange attribute where lower "
"limit > upper limit; these limits will be ignored.",
name));
} else {
effort_limit =
std::min(effort_limit, std::max(force_range[1], -force_range[0]));
if (-force_range[0] != force_range[1]) {
Warning(*node,
fmt::format("The motor '{}' specified a forcerange attribute "
"where lower limit != -upper limit. Asymmetrical "
"effort limits are not supported yet, so the "
"larger of the values {} will be used.",
name, std::max(force_range[1], -force_range[0])));
}
}
}
WarnUnsupportedAttribute(*node, "class");
WarnUnsupportedAttribute(*node, "group");
WarnUnsupportedAttribute(*node, "lengthrange");
WarnUnsupportedAttribute(*node, "cranklength");
WarnUnsupportedAttribute(*node, "jointinparent");
WarnUnsupportedAttribute(*node, "tendon");
WarnUnsupportedAttribute(*node, "cranksite");
WarnUnsupportedAttribute(*node, "slidersite");
WarnUnsupportedAttribute(*node, "site");
WarnUnsupportedAttribute(*node, "refsite");
WarnUnsupportedAttribute(*node, "user");
WarnUnsupportedAttribute(*node, "dyntype");
WarnUnsupportedAttribute(*node, "gaintype");
WarnUnsupportedAttribute(*node, "biastype");
WarnUnsupportedAttribute(*node, "dynprm");
WarnUnsupportedAttribute(*node, "gainprm");
WarnUnsupportedAttribute(*node, "biasprm");
const JointActuator<double>& actuator = plant_->AddJointActuator(
name, plant_->GetJointByName(joint_name, model_instance_),
effort_limit);
const char* gear_attr = node->Attribute("gear");
if (gear_attr) {
std::vector<double> vals = ConvertToVector<double>(gear_attr);
if (vals.size() != 1 && vals.size() != 6) {
Warning(*node, fmt::format("Expected either 1 value or 6 values for "
"'gear' attribute, but got {}.",
gear_attr));
}
if (vals.size() > 0) {
// Per the MuJoCo documentation: "For actuators with scalar
// transmission, only the first element of this vector is used."
plant_->get_mutable_joint_actuator(actuator.index())
.set_default_gear_ratio(vals[0]);
}
}
if (armature_.contains(actuator.joint().index())) {
const double gear_ratio =
plant_->get_joint_actuator(actuator.index()).default_gear_ratio();
plant_->get_mutable_joint_actuator(actuator.index())
.set_default_rotor_inertia(armature_.at(actuator.joint().index()) /
(gear_ratio * gear_ratio));
}
if (std::string_view(node->Name()) == "position") {
multibody::PdControllerGains gains{.p = 1, .d = 0}; // MuJoCo defaults.
double kp, kd;
if (ParseScalarAttribute(node, "kp", &kp)) {
gains.p = kp;
}
if (ParseScalarAttribute(node, "kd", &kd)) {
gains.d = kd;
}
plant_->get_mutable_joint_actuator(actuator.index())
.set_controller_gains(gains);
WarnUnsupportedAttribute(*node, "dampratio");
WarnUnsupportedAttribute(*node, "timeconst");
WarnUnsupportedAttribute(*node, "inheritrange");
}
}
void ParseActuator(XMLElement* node) {
for (XMLElement* motor_node = node->FirstChildElement("motor"); motor_node;
motor_node = motor_node->NextSiblingElement("motor")) {
ParseMotorOrPosition(motor_node);
}
for (XMLElement* position_node = node->FirstChildElement("position");
position_node;
position_node = position_node->NextSiblingElement("position")) {
ParseMotorOrPosition(position_node);
}
// Silently ignored: plugin.
WarnUnsupportedElement(*node, "general");
WarnUnsupportedElement(*node, "velocity");
WarnUnsupportedElement(*node, "intvelocity");
WarnUnsupportedElement(*node, "damper");
WarnUnsupportedElement(*node, "cylinder");
WarnUnsupportedElement(*node, "muscle");
WarnUnsupportedElement(*node, "adhesion");
}
void ParseJoint(XMLElement* node, const RigidBody<double>& parent,
const RigidBody<double>& child, const RigidTransformd& X_WC,
const RigidTransformd& X_PC,
const std::string& child_class = "") {
std::string name;
if (!ParseStringAttribute(node, "name", &name)) {
// Use "parent-body" as the default joint name.
name = fmt::format("{}-{}", parent.name(), child.name());
}
std::string class_name;
if (!ParseStringAttribute(node, "class", &class_name)) {
class_name = child_class.empty() ? "main" : child_class;
}
if (default_joint_.contains(class_name)) {
ApplyDefaultAttributes(*default_joint_.at(class_name), node);
}
Vector3d pos = Vector3d::Zero();
ParseVectorAttribute(node, "pos", &pos);
// Drake wants the joint position in the parent frame, but MuJoCo specifies
// it in the child body frame.
const RigidTransformd X_CJ(pos);
const RigidTransformd X_PJ = X_PC * X_CJ;
Vector3d axis = Vector3d::UnitZ();
ParseVectorAttribute(node, "axis", &axis);
// Drake wants the axis in the parent frame, but MuJoCo specifies it in the
// child body frame. But, by definition, these are always the same for
// revolute(hinge) joint and prismatic(slide) joint because the axis is the
// constraint that defines the joint. For ball joint and free joint, the
// axis attribute is ignored.
double damping{0.0};
ParseScalarAttribute(node, "damping", &damping);
std::string type;
if (!ParseStringAttribute(node, "type", &type)) {
type = "hinge";
}
Vector2d range(0.0, 0.0);
bool limited = ParseLimits(node, "range", "limited", &range);
JointIndex index;
if (type == "free") {
if (damping != 0.0) {
Warning(*node,
fmt::format(
"Damping was specified for the 'free' joint {}, but is not "
"supported for free bodies.",
name));
}
plant_->SetDefaultFreeBodyPose(child, X_WC);
} else if (type == "ball") {
index =
plant_
->AddJoint<BallRpyJoint>(name, parent, X_PJ, child, X_CJ, damping)
.index();
if (limited) {
WarnUnsupportedAttribute(*node, "range");
}
} else if (type == "slide") {
index = plant_
->AddJoint<PrismaticJoint>(
name, parent, X_PJ, child, X_CJ, axis,
-std::numeric_limits<double>::infinity(),
std::numeric_limits<double>::infinity(), damping)
.index();
if (limited) {
plant_->get_mutable_joint(index).set_position_limits(
Vector1d{range[0]}, Vector1d{range[1]});
// Note: MuJoCo does not clamp the reference position to stay inside
// the limits.
}
double ref{0.0};
ParseScalarAttribute(node, "ref", &ref);
plant_->get_mutable_joint(index).set_default_positions(Vector1d{ref});
} else if (type == "hinge") {
index = plant_
->AddJoint<RevoluteJoint>(name, parent, X_PJ, child, X_CJ,
axis, damping)
.index();
if (limited) {
if (angle_ == kDegree) {
range *= (M_PI / 180.0);
}
plant_->get_mutable_joint(index).set_position_limits(
Vector1d{range[0]}, Vector1d{range[1]});
// Note: MuJoCo does not clamp the reference position to stay inside
// the limits. This is important when the reference position defines
// constraints (as in the Cassie model in the menagerie.)
}
double ref{0.0};
if (ParseScalarAttribute(node, "ref", &ref) && angle_ == kDegree) {
ref *= (M_PI / 180.0);
}
plant_->get_mutable_joint(index).set_default_positions(Vector1d{ref});
} else {
Error(*node, "Unknown joint type " + type);
return;
}
// Note: The MuJoCo docs state that the armature is *always* added to all
// dofs of the inertia matrix: "Armature inertia (or rotor inertia, or
// reflected inertia) of all degrees of freedom created by this joint.
// These are constants added to the diagonal of the inertia matrix in
// generalized coordinates." But that is not what the rotor inertia of a
// motor actually does. In Drake we only add the rotor inertia through the
// joint actuator. This is a modeling difference.
double armature{0.0};
if (index.is_valid() && ParseScalarAttribute(node, "armature", &armature)) {
// Stash armature value to be used when parsing actuators.
armature_.emplace(index, armature);
}
WarnUnsupportedAttribute(*node, "group");
WarnUnsupportedAttribute(*node, "springdamper");
WarnUnsupportedAttribute(*node, "stiffness");
WarnUnsupportedAttribute(*node, "springref");
WarnUnsupportedAttribute(*node, "frictionloss");
WarnUnsupportedAttribute(*node, "user");
}
// Computes a shape's volume, centroid, and unit inertia. This calculator is
// used in a context where the calculation of mass needs to be deferred (e.g.,
// density is not yet determined or mass has been explicitly specified). The
// caller is responsible for defining the final value for mass, e.g., using a
// parser-specified mass or density (or a fallback default density).
class InertiaCalculator final : public geometry::ShapeReifier {
public:
DRAKE_NO_COPY_NO_MOVE_NO_ASSIGN(InertiaCalculator);
// The reifier aliases the pre-computed mesh spatial inertias. When looking
// up mesh inertias, it uses the mujoco geometry _name_ and not the
// mesh filename.
InertiaCalculator(
const DiagnosticPolicy& policy,
std::string name,
std::map<std::string, SpatialInertia<double>>* mesh_inertia)
: policy_(policy),
name_(std::move(name)),
mesh_inertia_(mesh_inertia) {
DRAKE_DEMAND(mesh_inertia != nullptr);
}
// Returns the tuple [volume, p_GoGcm_G, G_GGo_G], where for a geometry G,
// volume is G's volume, p_GoGcm_G is the position from G's origin point Go
// to its centroid Gcm expressed in the G frame, and G_GGo_G is G's unit
// inertia about Go expressed in the G frame.
// Note: if G has uniform density, Gcm is G's center of mass.
std::tuple<double, Vector3d, UnitInertia<double>> Calc(
const geometry::Shape& shape) {
shape.Reify(this);
// For unit density (1 kg/m³), the value of mass is equal to the value of
// volume.
const double& volume = M_GGo_G_unitDensity.get_mass();
const Vector3<double>& p_GoGcm_G = M_GGo_G_unitDensity.get_com();
const UnitInertia<double>& G_GGo_G =
M_GGo_G_unitDensity.get_unit_inertia();
return {volume, p_GoGcm_G, G_GGo_G};
}
bool used_convex_hull_fallback() const {
return used_convex_hull_fallback_;
}
using geometry::ShapeReifier::ImplementGeometry;
void ImplementGeometry(const geometry::Mesh& mesh, void*) final {
if (mesh_inertia_->contains(name_)) {
M_GGo_G_unitDensity = mesh_inertia_->at(name_);
} else {
CalcSpatialInertiaResult result =
CalcSpatialInertiaImpl(mesh, 1.0 /* density */);
if (std::holds_alternative<std::string>(result)) {
policy_.Warning(std::get<std::string>(result));
// As this calculator is only used for Mesh shapes that are specified
// in a mujoco file, the mesh *must* be on-disk.
DRAKE_DEMAND(mesh.source().is_path());
// As with mujoco, failure leads to using the convex hull.
// https://github.com/google-deepmind/mujoco/blob/df7ea3ed3350164d0f111c12870e46bc59439a96/src/user/user_mesh.cc#L1379-L1382
result = CalcSpatialInertiaImpl(
geometry::Convex(mesh.source().path(), mesh.scale()),
1.0 /* density */);
if (std::holds_alternative<std::string>(result)) {
policy_.Error(fmt::format(
"Failed to compute spatial inertia even for the convex hull of "
"{}.\n{}",
mesh.source().path().string(), std::get<std::string>(result)));
} else {
M_GGo_G_unitDensity = std::get<SpatialInertia<double>>(result);
}
used_convex_hull_fallback_ = true;
} else {
M_GGo_G_unitDensity = std::get<SpatialInertia<double>>(result);
}
}
mesh_inertia_->insert_or_assign(name_, M_GGo_G_unitDensity);
}
void ImplementGeometry(const geometry::HalfSpace&, void*) final {
// Do nothing; leave M_GGo_G_unitDensity default initialized.
}
void DefaultImplementGeometry(const geometry::Shape& shape) final {
M_GGo_G_unitDensity = CalcSpatialInertia(shape, 1.0 /* density */);
}
private:
const DiagnosticPolicy& policy_;
std::string name_;
std::map<std::string, SpatialInertia<double>>* mesh_inertia_{nullptr};
bool used_convex_hull_fallback_{false};
// Note: The spatial inertia below uses unit density so that the shape's
// volume value is equal to its mass value. To be clear, unit density is a
// mathematical trick to use CalcSpatialInertia() to report volume and not
// a reasonable *physical* default value; 1 kg/m³ is approximately air's
// density.
SpatialInertia<double> M_GGo_G_unitDensity{SpatialInertia<double>::NaN()};
};
SpatialInertia<double> ParseInertial(XMLElement* node) {
// We use F to denote the "inertial frame" in the MujoCo documentation. B
// is the body frame.
RigidTransformd X_BF = ParseTransform(node);
double mass;
if (!ParseScalarAttribute(node, "mass", &mass)) {
Error(*node, "The inertial tag must include the mass attribute.");
return SpatialInertia<double>::NaN();
}
// We interpret the MuJoCo XML documentation as saying that if a
// diaginertia is provided, it is I_BFo_F. If a full inertia is provided,
// then it must be I_BFo_B (since the inertia is always diagonal in F).
RotationalInertia<double> I_BFo_B;
Vector3d diag;
if (ParseVectorAttribute(node, "diaginertia", &diag)) {
I_BFo_B = RotationalInertia<double>(diag[0], diag[1], diag[2])
.ReExpress(X_BF.rotation());
} else {
// fullinertia is required if diaginertia is not specified.
Vector6d full;
if (ParseVectorAttribute(node, "fullinertia", &full)) {
I_BFo_B = RotationalInertia<double>(full[0], full[1], full[2], full[3],
full[4], full[5]);
} else {
Error(*node,
"The inertial tag must include either the diaginertia or "
"fullinertia attribute.");
return SpatialInertia<double>::NaN();
}
}
SpatialInertia<double> M_BBo_B =
SpatialInertia<double>::MakeFromCentralInertia(mass, X_BF.translation(),
I_BFo_B);
return M_BBo_B;
}
struct MujocoGeometry {
RigidTransformd X_BG{};
std::string name{};
std::unique_ptr<geometry::Shape> shape{};
Vector4d rgba{.5, .5, .5, 1};
CoulombFriction<double> friction{1.0, 1.0};
SpatialInertia<double> M_GBo_B{SpatialInertia<double>::NaN()};
bool register_collision{true};
bool register_visual{true};
};
MujocoGeometry ParseGeometry(XMLElement* node, int num_geom,
bool compute_inertia,
const std::string& child_class = "") {
MujocoGeometry geom;
std::string class_name;
if (!ParseStringAttribute(node, "class", &class_name)) {
class_name = child_class.empty() ? "main" : child_class;
}
if (default_geometry_.contains(class_name)) {
// TODO(russt): Add a test case covering childclass/default nesting once
// the body element is supported.
ApplyDefaultAttributes(*default_geometry_.at(class_name), node);
}
// Per the MuJoCo documentation, the name is not part of the defaults. This
// is consistent with Drake requiring that geometry names are unique.
if (!ParseStringAttribute(node, "name", &geom.name)) {
// Use "geom#" as the default body name.
geom.name = fmt::format("geom{}", num_geom);
}
geom.X_BG = ParseTransform(node);
std::string type;
if (!ParseStringAttribute(node, "type", &type)) {
type = "sphere";
}
// Note: The documentation says e.g. for sphere "only one size parameter is
// used", but it seems that in practice often more than one are specified.
// Demanding the correct number of size parameters is too restrictive.
std::vector<double> size;
{
std::string size_attr;
ParseStringAttribute(node, "size", &size_attr);
size = ConvertToVector<double>(size_attr);
}
Vector6d fromto;
bool has_fromto = ParseVectorAttribute(node, "fromto", &fromto);
if (has_fromto) {
// Set the pose to the midpoint of the from-to vector, with the
// orientation set according to the "zaxis" specification in
// ParseTransform.
const Vector3d from = fromto.head<3>();
const Vector3d to = fromto.tail<3>();
geom.X_BG = RigidTransformd(Eigen::Quaternion<double>::FromTwoVectors(
Vector3d{0, 0, 1}, to - from),
(from + to) / 2);
} else {
geom.X_BG = ParseTransform(node);
}
std::string mesh;
bool has_mesh_attribute = ParseStringAttribute(node, "mesh", &mesh);
if (has_mesh_attribute && type != "mesh") {
if (type == "sphere" || type == "capsule" || type == "cylinder" ||
type == "ellipsoid" || type == "box") {
Error(*node,
fmt::format(
"geom {} specified type '{}' but also has a mesh attribute. "
"The intended behavior is to compute the size of the shape "
"from the mesh, but this is not supported yet (#22372).",
geom.name, type));
return geom;
} else {
Error(*node, fmt::format("geom {} specified a 'mesh', but this is not "
"allowed for type '{}'.",
geom.name, type));
return geom;
}
}
if (type == "plane") {
// We interpret the MuJoCo infinite plane as a half-space.
geom.shape = std::make_unique<geometry::HalfSpace>();
compute_inertia = false;
} else if (type == "sphere") {
if (size.size() < 1) {
// Allow zero-radius spheres (the MJCF default size is 0 0 0).
geom.shape = std::make_unique<geometry::Sphere>(0.0);
compute_inertia = false;
} else {
geom.shape = std::make_unique<geometry::Sphere>(size[0]);
}
} else if (type == "capsule") {
if (has_fromto) {
if (size.size() < 1) {
Error(*node,
"The size attribute for capsule geom using fromto must have at "
"least one element.");
return geom;
}
double length = (fromto.head<3>() - fromto.tail<3>()).norm();
geom.shape = std::make_unique<geometry::Capsule>(size[0], length);
} else {
if (size.size() < 2) {
Error(*node,
"The size attribute for capsule geom must have at least two "
"elements.");
return geom;
}
geom.shape = std::make_unique<geometry::Capsule>(size[0], 2 * size[1]);
}
} else if (type == "ellipsoid") {
if (has_fromto) {
// The specification is not properly documented in the XML schema.
Warning(*node, fmt::format("The fromto tag for ellipsoid is currently "
"unsupported; geom {} will be ignored.",
geom.name));
return geom;
} else {
if (size.size() < 3) {
Error(
*node,
"The size attribute for ellipsoid geom must have at least three "
"elements.");
return geom;
}
geom.shape =
std::make_unique<geometry::Ellipsoid>(size[0], size[1], size[2]);
}
} else if (type == "cylinder") {
if (has_fromto) {
if (size.size() < 1) {
Error(*node,
"The size attribute for cylinder geom using fromto must have "
"at least one element.");
return geom;
}
double length = (fromto.head<3>() - fromto.tail<3>()).norm();
geom.shape = std::make_unique<geometry::Cylinder>(size[0], length);
} else {
if (size.size() < 2) {
Error(*node,
"The size attribute for cylinder geom must have at least two "
"elements.");
return geom;
}
geom.shape = std::make_unique<geometry::Cylinder>(size[0], 2 * size[1]);
}
} else if (type == "box") {
if (has_fromto) {
// The specification is not properly documented in the XML schema.
Warning(*node, fmt::format("The fromto tag for box is currently "
"unsupported; geom {} will be "
"ignored.",
geom.name));
return geom;
} else {
if (size.size() < 3) {
Error(*node,
"The size attribute for box geom must have at least three "
"elements.");
return geom;
}
geom.shape = std::make_unique<geometry::Box>(
size[0] * 2.0, size[1] * 2.0, size[2] * 2.0);
}
} else if (type == "mesh") {
if (!has_mesh_attribute) {
Error(*node, fmt::format("geom {} specified type 'mesh', but did not "
"set the mesh attribute",
geom.name));
return geom;
}
if (mesh_.contains(mesh)) {
geom.shape = mesh_.at(mesh)->Clone();
} else {
Warning(
*node,
fmt::format("geom {} specified unknown mesh {} and will be ignored",
geom.name, mesh));
return geom;
}
} else if (type == "hfield") {
Warning(*node, fmt::format("The geom type '{}' is currently unsupported "
"and will be ignored.",
type));
return geom;
} else {
Error(*node, fmt::format("Unrecognized geom type {}", type));
return geom;
}
int contype{1};
int conaffinity{1};
int condim{3};
ParseScalarAttribute(node, "contype", &contype);
ParseScalarAttribute(node, "conaffinity", &conaffinity);
ParseScalarAttribute(node, "condim", &condim);
if (contype == 0 && conaffinity == 0) {
// This is a common mechanism used by MJCF authors to specify visual-only
// geometry.
geom.register_collision = false;
} else if (contype != 1 || conaffinity != 1) {
Warning(
*node,
fmt::format(
"geom {} specified contype={} and conaffinity={}; but collision "
"filter groups are not yet implemented for the mujoco parser.",
geom.name, contype, conaffinity));
}
if (condim != 3) {
// TODO(russt): Can we support condim=1 inefficiently by setting friction
// coefficients to zero? This may be insufficient given the parallel
// resistor friction coefficient logic. condim=4 or 6 are likely out of
// scope for now.
Warning(*node, fmt::format("geom {} specified condim={}, which is not "
"supported. condim=3 will be used instead.",
geom.name, condim));
}
if (geom.register_collision && type == "sphere" && size.size() < 1) {
Warning(*node,
fmt::format(
"Using zero-radius spheres (MuJoCo's default geometry) for "
"collision geometry may not be supported by all features in "
"Drake. Consider specifying a non-zero size for geom {}.",
geom.name));
}
int group{0};
ParseScalarAttribute(node, "group", &group);
if (group > 2) {
// By default, the MuJoCo visualizer does not render geom with group > 2.
// Setting the group > 2 is a common mechanism that MuJoCo uses to
// register collision-only geometry.
geom.register_visual = false;
// TODO(russt): Consider adding a <drake::enable_visual_for_group> tag so
// that mjcf authors can configure this behavior.
}
std::string material;
if (ParseStringAttribute(node, "material", &material)) {
if (material_.contains(material)) {
XMLElement* material_node = material_.at(material);
// Note: there are many material attributes that we do not support yet,
// nor perhaps ever. Consider warning about them here (currently, it
// seems like too much noise).
ParseVectorAttribute(material_node, "rgba", &geom.rgba);
} else {
Warning(*node,
fmt::format("geom {} specified an unrecognized material {}",
geom.name, material));
}
}
// rgba takes precedence over materials, so must be parsed after.
ParseVectorAttribute(node, "rgba", &geom.rgba);
// Note: The documentation suggests that at least 3 friction parameters
// should be specified. But humanoid_CMU.xml in the DeepMind suite
// specifies only one, and in fact we only need one.
std::vector<double> friction;
{
std::string friction_attr;
ParseStringAttribute(node, "friction", &friction_attr);
friction = ConvertToVector<double>(friction_attr);
}
if (!friction.empty()) {
// MuJoCo's friction specification is [sliding, torsional, rolling]. We
// set the static and dynamic friction to `sliding`, and do not support
// the other parameters.
geom.friction = CoulombFriction(friction[0], friction[0]);
if ((friction.size() > 1 && friction[1] != 0.0) ||
(friction.size() > 2 && friction[2] != 0.0)) {
Warning(
*node,
fmt::format(
"The torsional and rolling friction specified in the friction "
"attribute of {} are unsupported and will be ignored.",
node->Name()));
}
}
WarnUnsupportedAttribute(*node, "fitscale");
WarnUnsupportedAttribute(*node, "user");
if (compute_inertia) {
auto policy = diagnostic_.MakePolicyForNode(node);
InertiaCalculator calculator(policy, mesh, &mesh_inertia_);
const auto [volume, p_GoGcm_G, G_GGo_G] = calculator.Calc(*geom.shape);
if (calculator.used_convex_hull_fallback()) {
// When the Mujoco parser falls back to using a convex hull, it prints
// a warning. We ape that behavior to provide a similar experience.
//
// N.B. Mujoco falls back only if the mesh reported a negative volume.
// SpatialInertia::IsPhysicallyValid() will also fail in that case. But
// fails in other cases (e.g., positive mass but negative inertia) where
// Drake will fallback and Mujoco won't. Such a mesh would be rare.
// Generally, we expect Drake and Mujoco to agree on real world meshes.
Warning(
*node,
fmt::format("CalcSpatialInertia() failed to compute a physically "
"valid inertia for mesh {} (probably the mesh is not "
"watertight). The spatial inertia was computed using "
"its convex hull as a fallback.",
mesh));
}
double mass{};
if (!ParseScalarAttribute(node, "mass", &mass)) {
double density{1000}; /* fallback default ≈ water density */
ParseScalarAttribute(node, "density", &density);
mass = volume * density;
}
SpatialInertia<double> M_GGo_G(mass, p_GoGcm_G, G_GGo_G,
/*skip_validity_check=*/true);
if (!M_GGo_G.IsPhysicallyValid()) {
Error(*node, fmt::format("geom {} {}", geom.name,
M_GGo_G.CriticizeNotPhysicallyValid()));
return geom;
}
// Shift spatial inertia from Go to Bo and express it in the B frame.
const math::RotationMatrix<double>& R_BG = geom.X_BG.rotation();
const Vector3<double>& p_BoGo_B = geom.X_BG.translation();
geom.M_GBo_B = M_GGo_G.ReExpress(R_BG).Shift(-p_BoGo_B);
}
return geom;