Skip to content

Commit ac0701d

Browse files
havesscopybara-github
authored andcommitted
Add mujoco compiler settings to MjcSceneAPI in mjcPhysics.
PiperOrigin-RevId: 783729333 Change-Id: Ic1c3e4fb47a901de4eebdc2e987d276f4202d9ed
1 parent 5069534 commit ac0701d

File tree

9 files changed

+1091
-30
lines changed

9 files changed

+1091
-30
lines changed

include/mujoco/experimental/usd/mjcPhysics/sceneAPI.h

Lines changed: 404 additions & 0 deletions
Large diffs are not rendered by default.

include/mujoco/experimental/usd/mjcPhysics/tokens.h

Lines changed: 73 additions & 6 deletions
Original file line numberDiff line numberDiff line change
@@ -60,8 +60,9 @@ struct MjcPhysicsTokensType {
6060
const TfToken affine;
6161
/// \brief "auto"
6262
///
63-
/// Fallback value for MjcPhysicsSceneAPI::GetJacobianAttr(), Fallback value
64-
/// for MjcPhysicsActuator::GetMjcActLimitedAttr(), Fallback value for
63+
/// Fallback value for MjcPhysicsSceneAPI::GetInertiaFromGeomAttr(), Fallback
64+
/// value for MjcPhysicsSceneAPI::GetJacobianAttr(), Fallback value for
65+
/// MjcPhysicsActuator::GetMjcActLimitedAttr(), Fallback value for
6566
/// MjcPhysicsActuator::GetMjcCtrlLimitedAttr(), Fallback value for
6667
/// MjcPhysicsActuator::GetMjcForceLimitedAttr(), Fallback value for
6768
/// MjcPhysicsJointAPI::GetMjcActuatorfrclimitedAttr(), This token represents
@@ -76,6 +77,10 @@ struct MjcPhysicsTokensType {
7677
///
7778
/// Possible value for MjcPhysicsMeshCollisionAPI::GetInertiaAttr()
7879
const TfToken convex;
80+
/// \brief "degree"
81+
///
82+
/// Fallback value for MjcPhysicsSceneAPI::GetAngleAttr()
83+
const TfToken degree;
7984
/// \brief "dense"
8085
///
8186
/// Possible value for MjcPhysicsSceneAPI::GetJacobianAttr(), This token
@@ -97,8 +102,9 @@ struct MjcPhysicsTokensType {
97102
const TfToken exact;
98103
/// \brief "false"
99104
///
100-
/// Possible value for MjcPhysicsActuator::GetMjcActLimitedAttr(), Possible
101-
/// value for MjcPhysicsActuator::GetMjcCtrlLimitedAttr(), Possible value for
105+
/// Possible value for MjcPhysicsSceneAPI::GetInertiaFromGeomAttr(), Possible
106+
/// value for MjcPhysicsActuator::GetMjcActLimitedAttr(), Possible value for
107+
/// MjcPhysicsActuator::GetMjcCtrlLimitedAttr(), Possible value for
102108
/// MjcPhysicsActuator::GetMjcForceLimitedAttr(), Possible value for
103109
/// MjcPhysicsJointAPI::GetMjcActuatorfrclimitedAttr()
104110
const TfToken false_;
@@ -184,6 +190,62 @@ struct MjcPhysicsTokensType {
184190
///
185191
/// MjcPhysicsActuator
186192
const TfToken mjcBiasType;
193+
/// \brief "mjc:compiler:alignFree"
194+
///
195+
/// MjcPhysicsSceneAPI
196+
const TfToken mjcCompilerAlignFree;
197+
/// \brief "mjc:compiler:angle"
198+
///
199+
/// MjcPhysicsSceneAPI
200+
const TfToken mjcCompilerAngle;
201+
/// \brief "mjc:compiler:autoLimits"
202+
///
203+
/// MjcPhysicsSceneAPI
204+
const TfToken mjcCompilerAutoLimits;
205+
/// \brief "mjc:compiler:balanceInertia"
206+
///
207+
/// MjcPhysicsSceneAPI
208+
const TfToken mjcCompilerBalanceInertia;
209+
/// \brief "mjc:compiler:boundInertia"
210+
///
211+
/// MjcPhysicsSceneAPI
212+
const TfToken mjcCompilerBoundInertia;
213+
/// \brief "mjc:compiler:boundMass"
214+
///
215+
/// MjcPhysicsSceneAPI
216+
const TfToken mjcCompilerBoundMass;
217+
/// \brief "mjc:compiler:fitAABB"
218+
///
219+
/// MjcPhysicsSceneAPI
220+
const TfToken mjcCompilerFitAABB;
221+
/// \brief "mjc:compiler:fuseStatic"
222+
///
223+
/// MjcPhysicsSceneAPI
224+
const TfToken mjcCompilerFuseStatic;
225+
/// \brief "mjc:compiler:inertiaFromGeom"
226+
///
227+
/// MjcPhysicsSceneAPI
228+
const TfToken mjcCompilerInertiaFromGeom;
229+
/// \brief "mjc:compiler:inertiaGroupRange:max"
230+
///
231+
/// MjcPhysicsSceneAPI
232+
const TfToken mjcCompilerInertiaGroupRangeMax;
233+
/// \brief "mjc:compiler:inertiaGroupRange:min"
234+
///
235+
/// MjcPhysicsSceneAPI
236+
const TfToken mjcCompilerInertiaGroupRangeMin;
237+
/// \brief "mjc:compiler:saveInertial"
238+
///
239+
/// MjcPhysicsSceneAPI
240+
const TfToken mjcCompilerSaveInertial;
241+
/// \brief "mjc:compiler:setTotalMass"
242+
///
243+
/// MjcPhysicsSceneAPI
244+
const TfToken mjcCompilerSetTotalMass;
245+
/// \brief "mjc:compiler:useThread"
246+
///
247+
/// MjcPhysicsSceneAPI
248+
const TfToken mjcCompilerUseThread;
187249
/// \brief "mjc:condim"
188250
///
189251
/// MjcPhysicsCollisionAPI
@@ -595,6 +657,10 @@ struct MjcPhysicsTokensType {
595657
/// Fallback value for MjcPhysicsSceneAPI::GetConeAttr(), This token
596658
/// represents the pyramidal contact friction cone type.
597659
const TfToken pyramidal;
660+
/// \brief "radian"
661+
///
662+
/// Possible value for MjcPhysicsSceneAPI::GetAngleAttr()
663+
const TfToken radian;
598664
/// \brief "rk4"
599665
///
600666
/// Possible value for MjcPhysicsSceneAPI::GetIntegratorAttr(), This token
@@ -611,8 +677,9 @@ struct MjcPhysicsTokensType {
611677
const TfToken sparse;
612678
/// \brief "true"
613679
///
614-
/// Possible value for MjcPhysicsActuator::GetMjcActLimitedAttr(), Possible
615-
/// value for MjcPhysicsActuator::GetMjcCtrlLimitedAttr(), Possible value for
680+
/// Possible value for MjcPhysicsSceneAPI::GetInertiaFromGeomAttr(), Possible
681+
/// value for MjcPhysicsActuator::GetMjcActLimitedAttr(), Possible value for
682+
/// MjcPhysicsActuator::GetMjcCtrlLimitedAttr(), Possible value for
616683
/// MjcPhysicsActuator::GetMjcForceLimitedAttr(), Possible value for
617684
/// MjcPhysicsJointAPI::GetMjcActuatorfrclimitedAttr()
618685
const TfToken true_;

src/experimental/usd/mjcPhysics/generatedSchema.usda

Lines changed: 63 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -7,6 +7,69 @@ class "MjcSceneAPI" (
77
doc = "API providing global simulation options for MuJoCo."
88
)
99
{
10+
uniform bool mjc:compiler:alignFree = 0 (
11+
displayName = "Align Free"
12+
doc = "This attribute toggles the default behaviour of an optimization that applies to bodies with a free joint and no child bodies. When True, the body frame and free joint will automatically be aligned with inertial frame, which leads to both faster and more stable simulation."
13+
)
14+
uniform token mjc:compiler:angle = "degree" (
15+
allowedTokens = ["degree", "radian"]
16+
displayName = "Angle"
17+
doc = "This attribute specifies whether the angles in mjcPhysics attributes have units of degrees or radians if not otherwise noted."
18+
)
19+
uniform bool mjc:compiler:autoLimits = 1 (
20+
displayName = "Automatic Limits"
21+
doc = 'This attribute affects the behavior of attributes such as "limited" (on MjcJointAPI), "forcelimited" "ctrllimited", and "actlimited" (on MjcActuator). If True, these attributes are unnecessary and their value will be inferred from the presence of their corresponding "range" attribute. If False, no such inference will happen: For a joint to be limited, both limited=True and range:min/max must be specified. In this mode, it is an error to specify a range without a limit.'
22+
)
23+
uniform bool mjc:compiler:balanceInertia = 0 (
24+
displayName = "Balance Inertia"
25+
doc = 'A valid diagonal inertia matrix must satisfy A+B>=C for all permutations of the three diagonal elements. Some poorly designed models violate this constraint, which will normally result in a compile error. If this attribute is set to "true", the compiler will silently set all three diagonal elements to their average value whenever the above condition is violated.'
26+
)
27+
uniform double mjc:compiler:boundInertia = 0 (
28+
displayName = "Bound Inertia"
29+
doc = "This attribute imposes a lower bound on the diagonal inertia components of each body except for the world body."
30+
)
31+
uniform double mjc:compiler:boundMass = 0 (
32+
displayName = "Bound Mass"
33+
doc = "This attribute imposes a lower bound on the mass of each body except for the world body."
34+
)
35+
uniform bool mjc:compiler:fitAABB = 0 (
36+
displayName = "Fit AABB"
37+
doc = "The compiler is able to replace a mesh with a geometric primitive fitted to that mesh. If this attribute is True, the fitting procedure uses the axis-aligned bounding box (AABB) of the mesh. Otherwise it uses the equivalent-inertia box of the mesh."
38+
)
39+
uniform bool mjc:compiler:fuseStatic = 0 (
40+
displayName = "Fuse Static"
41+
doc = """This attribute controls a compiler optimization feature where static bodies are fused with their parent, and any elements defined in those bodies are reassigned to the parent. Static bodies are fused with their parent unless
42+
43+
* They are referenced by another element in the model.
44+
45+
* They contain a site which is referenced by a force or torque sensor.
46+
"""
47+
)
48+
uniform token mjc:compiler:inertiaFromGeom = "auto" (
49+
allowedTokens = ["false", "true", "auto"]
50+
displayName = "Inertia From Geom"
51+
doc = 'This attribute controls the automatic inference of body masses and inertias from geoms attached to the body. If this setting is "false", no automatic inference is performed. In that case each body must have explicitly defined mass and inertia with the inertial element, or else a compile error will be generated. If this setting is "true", the mass and inertia of each body will be inferred from the geoms attached to it, overriding any values specified with the inertial element. The default setting "auto" means that masses and inertias are inferred automatically only when the inertial element is missing in the body definition. One reason to set this attribute to "true" instead of "auto" is to override inertial data imported from a poorly designed model.'
52+
)
53+
uniform int mjc:compiler:inertiaGroupRange:max = 5 (
54+
displayName = "Inertia Group Range Max"
55+
doc = "This attribute specifies the maximum of the geom group range that is used to infer body masses and inertias (when such inference is enabled). The group attribute of geom is an integer. If this integer falls in the range specified here, the geom will be used in the inertial computation, otherwise it will be ignored. This feature is useful in models that have redundant sets of geoms for collision and visualization. Note that the world body does not participate in the inertial computations, so any geoms attached to it are automatically ignored. Therefore it is not necessary to adjust this attribute and the geom-specific groups so as to exclude world geoms from the inertial computation."
56+
)
57+
uniform int mjc:compiler:inertiaGroupRange:min = 0 (
58+
displayName = "Inertia Group Range Min"
59+
doc = "This attribute specifies the maximum of the geom group range that is used to infer body masses and inertias (when such inference is enabled). The group attribute of geom is an integer. If this integer falls in the range specified here, the collider will be used in the inertial computation, otherwise it will be ignored. Note that the world body does not participate in the inertial computations, so any geoms attached to it are automatically ignored. Therefore it is not necessary to adjust this attribute and the geom-specific groups so as to exclude world geoms from the inertial computation."
60+
)
61+
uniform bool mjc:compiler:saveInertial = 0 (
62+
displayName = "Save Inertial"
63+
doc = "If True, the compiler will save explicit inertial clauses for all bodies."
64+
)
65+
uniform double mjc:compiler:setTotalMass = -1 (
66+
displayName = "Set Total Mass"
67+
doc = "If this value is positive, the compiler will scale the masses and inertias of all bodies in the model, so that the total mass equals the value specified here. The world body has mass 0 and does not participate in any mass-related computations. This scaling is performed last, after all other operations affecting the body mass and inertia. The same scaling operation can be applied at runtime to the compiled mjModel with the function mj_setTotalmass."
68+
)
69+
uniform bool mjc:compiler:useThread = 1 (
70+
displayName = "Use Thread"
71+
doc = "If this is True, the model compiler will run in multi-threaded mode. Currently multi-threading is used for computing the length ranges of actuators and for parallel loading of meshes."
72+
)
1073
uniform bool mjc:flag:actuation = 1 (
1174
displayName = "Actuation Forces Toggle"
1275
doc = "Enables all standard computations related to actuator forces, including actuator dynamics."

src/experimental/usd/mjcPhysics/sceneAPI.cpp

Lines changed: 170 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -615,6 +615,162 @@ UsdAttribute MjcPhysicsSceneAPI::CreateIslandFlagAttr(
615615
/* custom = */ false, SdfVariabilityUniform, defaultValue, writeSparsely);
616616
}
617617

618+
UsdAttribute MjcPhysicsSceneAPI::GetAutoLimitsAttr() const {
619+
return GetPrim().GetAttribute(MjcPhysicsTokens->mjcCompilerAutoLimits);
620+
}
621+
622+
UsdAttribute MjcPhysicsSceneAPI::CreateAutoLimitsAttr(
623+
VtValue const &defaultValue, bool writeSparsely) const {
624+
return UsdSchemaBase::_CreateAttr(
625+
MjcPhysicsTokens->mjcCompilerAutoLimits, SdfValueTypeNames->Bool,
626+
/* custom = */ false, SdfVariabilityUniform, defaultValue, writeSparsely);
627+
}
628+
629+
UsdAttribute MjcPhysicsSceneAPI::GetBoundMassAttr() const {
630+
return GetPrim().GetAttribute(MjcPhysicsTokens->mjcCompilerBoundMass);
631+
}
632+
633+
UsdAttribute MjcPhysicsSceneAPI::CreateBoundMassAttr(
634+
VtValue const &defaultValue, bool writeSparsely) const {
635+
return UsdSchemaBase::_CreateAttr(
636+
MjcPhysicsTokens->mjcCompilerBoundMass, SdfValueTypeNames->Double,
637+
/* custom = */ false, SdfVariabilityUniform, defaultValue, writeSparsely);
638+
}
639+
640+
UsdAttribute MjcPhysicsSceneAPI::GetBoundInertiaAttr() const {
641+
return GetPrim().GetAttribute(MjcPhysicsTokens->mjcCompilerBoundInertia);
642+
}
643+
644+
UsdAttribute MjcPhysicsSceneAPI::CreateBoundInertiaAttr(
645+
VtValue const &defaultValue, bool writeSparsely) const {
646+
return UsdSchemaBase::_CreateAttr(
647+
MjcPhysicsTokens->mjcCompilerBoundInertia, SdfValueTypeNames->Double,
648+
/* custom = */ false, SdfVariabilityUniform, defaultValue, writeSparsely);
649+
}
650+
651+
UsdAttribute MjcPhysicsSceneAPI::GetSetTotalMassAttr() const {
652+
return GetPrim().GetAttribute(MjcPhysicsTokens->mjcCompilerSetTotalMass);
653+
}
654+
655+
UsdAttribute MjcPhysicsSceneAPI::CreateSetTotalMassAttr(
656+
VtValue const &defaultValue, bool writeSparsely) const {
657+
return UsdSchemaBase::_CreateAttr(
658+
MjcPhysicsTokens->mjcCompilerSetTotalMass, SdfValueTypeNames->Double,
659+
/* custom = */ false, SdfVariabilityUniform, defaultValue, writeSparsely);
660+
}
661+
662+
UsdAttribute MjcPhysicsSceneAPI::GetUseThreadAttr() const {
663+
return GetPrim().GetAttribute(MjcPhysicsTokens->mjcCompilerUseThread);
664+
}
665+
666+
UsdAttribute MjcPhysicsSceneAPI::CreateUseThreadAttr(
667+
VtValue const &defaultValue, bool writeSparsely) const {
668+
return UsdSchemaBase::_CreateAttr(
669+
MjcPhysicsTokens->mjcCompilerUseThread, SdfValueTypeNames->Bool,
670+
/* custom = */ false, SdfVariabilityUniform, defaultValue, writeSparsely);
671+
}
672+
673+
UsdAttribute MjcPhysicsSceneAPI::GetBalanceInertiaAttr() const {
674+
return GetPrim().GetAttribute(MjcPhysicsTokens->mjcCompilerBalanceInertia);
675+
}
676+
677+
UsdAttribute MjcPhysicsSceneAPI::CreateBalanceInertiaAttr(
678+
VtValue const &defaultValue, bool writeSparsely) const {
679+
return UsdSchemaBase::_CreateAttr(
680+
MjcPhysicsTokens->mjcCompilerBalanceInertia, SdfValueTypeNames->Bool,
681+
/* custom = */ false, SdfVariabilityUniform, defaultValue, writeSparsely);
682+
}
683+
684+
UsdAttribute MjcPhysicsSceneAPI::GetAngleAttr() const {
685+
return GetPrim().GetAttribute(MjcPhysicsTokens->mjcCompilerAngle);
686+
}
687+
688+
UsdAttribute MjcPhysicsSceneAPI::CreateAngleAttr(VtValue const &defaultValue,
689+
bool writeSparsely) const {
690+
return UsdSchemaBase::_CreateAttr(
691+
MjcPhysicsTokens->mjcCompilerAngle, SdfValueTypeNames->Token,
692+
/* custom = */ false, SdfVariabilityUniform, defaultValue, writeSparsely);
693+
}
694+
695+
UsdAttribute MjcPhysicsSceneAPI::GetFitAABBAttr() const {
696+
return GetPrim().GetAttribute(MjcPhysicsTokens->mjcCompilerFitAABB);
697+
}
698+
699+
UsdAttribute MjcPhysicsSceneAPI::CreateFitAABBAttr(VtValue const &defaultValue,
700+
bool writeSparsely) const {
701+
return UsdSchemaBase::_CreateAttr(
702+
MjcPhysicsTokens->mjcCompilerFitAABB, SdfValueTypeNames->Bool,
703+
/* custom = */ false, SdfVariabilityUniform, defaultValue, writeSparsely);
704+
}
705+
706+
UsdAttribute MjcPhysicsSceneAPI::GetFuseStaticAttr() const {
707+
return GetPrim().GetAttribute(MjcPhysicsTokens->mjcCompilerFuseStatic);
708+
}
709+
710+
UsdAttribute MjcPhysicsSceneAPI::CreateFuseStaticAttr(
711+
VtValue const &defaultValue, bool writeSparsely) const {
712+
return UsdSchemaBase::_CreateAttr(
713+
MjcPhysicsTokens->mjcCompilerFuseStatic, SdfValueTypeNames->Bool,
714+
/* custom = */ false, SdfVariabilityUniform, defaultValue, writeSparsely);
715+
}
716+
717+
UsdAttribute MjcPhysicsSceneAPI::GetInertiaFromGeomAttr() const {
718+
return GetPrim().GetAttribute(MjcPhysicsTokens->mjcCompilerInertiaFromGeom);
719+
}
720+
721+
UsdAttribute MjcPhysicsSceneAPI::CreateInertiaFromGeomAttr(
722+
VtValue const &defaultValue, bool writeSparsely) const {
723+
return UsdSchemaBase::_CreateAttr(
724+
MjcPhysicsTokens->mjcCompilerInertiaFromGeom, SdfValueTypeNames->Token,
725+
/* custom = */ false, SdfVariabilityUniform, defaultValue, writeSparsely);
726+
}
727+
728+
UsdAttribute MjcPhysicsSceneAPI::GetAlignFreeAttr() const {
729+
return GetPrim().GetAttribute(MjcPhysicsTokens->mjcCompilerAlignFree);
730+
}
731+
732+
UsdAttribute MjcPhysicsSceneAPI::CreateAlignFreeAttr(
733+
VtValue const &defaultValue, bool writeSparsely) const {
734+
return UsdSchemaBase::_CreateAttr(
735+
MjcPhysicsTokens->mjcCompilerAlignFree, SdfValueTypeNames->Bool,
736+
/* custom = */ false, SdfVariabilityUniform, defaultValue, writeSparsely);
737+
}
738+
739+
UsdAttribute MjcPhysicsSceneAPI::GetInertiaGroupRangeMinAttr() const {
740+
return GetPrim().GetAttribute(
741+
MjcPhysicsTokens->mjcCompilerInertiaGroupRangeMin);
742+
}
743+
744+
UsdAttribute MjcPhysicsSceneAPI::CreateInertiaGroupRangeMinAttr(
745+
VtValue const &defaultValue, bool writeSparsely) const {
746+
return UsdSchemaBase::_CreateAttr(
747+
MjcPhysicsTokens->mjcCompilerInertiaGroupRangeMin, SdfValueTypeNames->Int,
748+
/* custom = */ false, SdfVariabilityUniform, defaultValue, writeSparsely);
749+
}
750+
751+
UsdAttribute MjcPhysicsSceneAPI::GetInertiaGroupRangeMaxAttr() const {
752+
return GetPrim().GetAttribute(
753+
MjcPhysicsTokens->mjcCompilerInertiaGroupRangeMax);
754+
}
755+
756+
UsdAttribute MjcPhysicsSceneAPI::CreateInertiaGroupRangeMaxAttr(
757+
VtValue const &defaultValue, bool writeSparsely) const {
758+
return UsdSchemaBase::_CreateAttr(
759+
MjcPhysicsTokens->mjcCompilerInertiaGroupRangeMax, SdfValueTypeNames->Int,
760+
/* custom = */ false, SdfVariabilityUniform, defaultValue, writeSparsely);
761+
}
762+
763+
UsdAttribute MjcPhysicsSceneAPI::GetSaveInertialAttr() const {
764+
return GetPrim().GetAttribute(MjcPhysicsTokens->mjcCompilerSaveInertial);
765+
}
766+
767+
UsdAttribute MjcPhysicsSceneAPI::CreateSaveInertialAttr(
768+
VtValue const &defaultValue, bool writeSparsely) const {
769+
return UsdSchemaBase::_CreateAttr(
770+
MjcPhysicsTokens->mjcCompilerSaveInertial, SdfValueTypeNames->Bool,
771+
/* custom = */ false, SdfVariabilityUniform, defaultValue, writeSparsely);
772+
}
773+
618774
namespace {
619775
static inline TfTokenVector _ConcatenateAttributeNames(
620776
const TfTokenVector &left, const TfTokenVector &right) {
@@ -679,6 +835,20 @@ const TfTokenVector &MjcPhysicsSceneAPI::GetSchemaAttributeNames(
679835
MjcPhysicsTokens->mjcFlagInvdiscrete,
680836
MjcPhysicsTokens->mjcFlagMulticcd,
681837
MjcPhysicsTokens->mjcFlagIsland,
838+
MjcPhysicsTokens->mjcCompilerAutoLimits,
839+
MjcPhysicsTokens->mjcCompilerBoundMass,
840+
MjcPhysicsTokens->mjcCompilerBoundInertia,
841+
MjcPhysicsTokens->mjcCompilerSetTotalMass,
842+
MjcPhysicsTokens->mjcCompilerUseThread,
843+
MjcPhysicsTokens->mjcCompilerBalanceInertia,
844+
MjcPhysicsTokens->mjcCompilerAngle,
845+
MjcPhysicsTokens->mjcCompilerFitAABB,
846+
MjcPhysicsTokens->mjcCompilerFuseStatic,
847+
MjcPhysicsTokens->mjcCompilerInertiaFromGeom,
848+
MjcPhysicsTokens->mjcCompilerAlignFree,
849+
MjcPhysicsTokens->mjcCompilerInertiaGroupRangeMin,
850+
MjcPhysicsTokens->mjcCompilerInertiaGroupRangeMax,
851+
MjcPhysicsTokens->mjcCompilerSaveInertial,
682852
};
683853
static TfTokenVector allNames = _ConcatenateAttributeNames(
684854
UsdAPISchemaBase::GetSchemaAttributeNames(true), localNames);

0 commit comments

Comments
 (0)