| | |
| | |
| | |
| | |
| | |
| | |
| | |
| | |
| | |
| | |
| | |
| | |
| | |
| |
|
| | #include <mujoco/experimental/usd/mjcPhysics/jointAPI.h> |
| |
|
| | #include <pxr/usd/sdf/assetPath.h> |
| | #include <pxr/usd/sdf/types.h> |
| | #include <pxr/usd/usd/schemaRegistry.h> |
| | #include <pxr/usd/usd/typed.h> |
| |
|
| | PXR_NAMESPACE_OPEN_SCOPE |
| |
|
| | |
| | TF_REGISTRY_FUNCTION(TfType) { |
| | TfType::Define<MjcPhysicsJointAPI, TfType::Bases<UsdAPISchemaBase> >(); |
| | } |
| |
|
| | |
| | MjcPhysicsJointAPI::~MjcPhysicsJointAPI() {} |
| |
|
| | |
| | MjcPhysicsJointAPI MjcPhysicsJointAPI::Get(const UsdStagePtr &stage, |
| | const SdfPath &path) { |
| | if (!stage) { |
| | TF_CODING_ERROR("Invalid stage"); |
| | return MjcPhysicsJointAPI(); |
| | } |
| | return MjcPhysicsJointAPI(stage->GetPrimAtPath(path)); |
| | } |
| |
|
| | |
| | UsdSchemaKind MjcPhysicsJointAPI::_GetSchemaKind() const { |
| | return MjcPhysicsJointAPI::schemaKind; |
| | } |
| |
|
| | |
| | bool MjcPhysicsJointAPI::CanApply(const UsdPrim &prim, std::string *whyNot) { |
| | return prim.CanApplyAPI<MjcPhysicsJointAPI>(whyNot); |
| | } |
| |
|
| | |
| | MjcPhysicsJointAPI MjcPhysicsJointAPI::Apply(const UsdPrim &prim) { |
| | if (prim.ApplyAPI<MjcPhysicsJointAPI>()) { |
| | return MjcPhysicsJointAPI(prim); |
| | } |
| | return MjcPhysicsJointAPI(); |
| | } |
| |
|
| | |
| | const TfType &MjcPhysicsJointAPI::_GetStaticTfType() { |
| | static TfType tfType = TfType::Find<MjcPhysicsJointAPI>(); |
| | return tfType; |
| | } |
| |
|
| | |
| | bool MjcPhysicsJointAPI::_IsTypedSchema() { |
| | static bool isTyped = _GetStaticTfType().IsA<UsdTyped>(); |
| | return isTyped; |
| | } |
| |
|
| | |
| | const TfType &MjcPhysicsJointAPI::_GetTfType() const { |
| | return _GetStaticTfType(); |
| | } |
| |
|
| | UsdAttribute MjcPhysicsJointAPI::GetGroupAttr() const { |
| | return GetPrim().GetAttribute(MjcPhysicsTokens->mjcGroup); |
| | } |
| |
|
| | UsdAttribute MjcPhysicsJointAPI::CreateGroupAttr(VtValue const &defaultValue, |
| | bool writeSparsely) const { |
| | return UsdSchemaBase::_CreateAttr( |
| | MjcPhysicsTokens->mjcGroup, SdfValueTypeNames->Int, |
| | false, SdfVariabilityUniform, defaultValue, writeSparsely); |
| | } |
| |
|
| | UsdAttribute MjcPhysicsJointAPI::GetMjcSpringdamperAttr() const { |
| | return GetPrim().GetAttribute(MjcPhysicsTokens->mjcSpringdamper); |
| | } |
| |
|
| | UsdAttribute MjcPhysicsJointAPI::CreateMjcSpringdamperAttr( |
| | VtValue const &defaultValue, bool writeSparsely) const { |
| | return UsdSchemaBase::_CreateAttr( |
| | MjcPhysicsTokens->mjcSpringdamper, SdfValueTypeNames->DoubleArray, |
| | false, SdfVariabilityUniform, defaultValue, writeSparsely); |
| | } |
| |
|
| | UsdAttribute MjcPhysicsJointAPI::GetMjcSolreflimitAttr() const { |
| | return GetPrim().GetAttribute(MjcPhysicsTokens->mjcSolreflimit); |
| | } |
| |
|
| | UsdAttribute MjcPhysicsJointAPI::CreateMjcSolreflimitAttr( |
| | VtValue const &defaultValue, bool writeSparsely) const { |
| | return UsdSchemaBase::_CreateAttr( |
| | MjcPhysicsTokens->mjcSolreflimit, SdfValueTypeNames->DoubleArray, |
| | false, SdfVariabilityUniform, defaultValue, writeSparsely); |
| | } |
| |
|
| | UsdAttribute MjcPhysicsJointAPI::GetMjcSolimplimitAttr() const { |
| | return GetPrim().GetAttribute(MjcPhysicsTokens->mjcSolimplimit); |
| | } |
| |
|
| | UsdAttribute MjcPhysicsJointAPI::CreateMjcSolimplimitAttr( |
| | VtValue const &defaultValue, bool writeSparsely) const { |
| | return UsdSchemaBase::_CreateAttr( |
| | MjcPhysicsTokens->mjcSolimplimit, SdfValueTypeNames->DoubleArray, |
| | false, SdfVariabilityUniform, defaultValue, writeSparsely); |
| | } |
| |
|
| | UsdAttribute MjcPhysicsJointAPI::GetMjcSolreffrictionAttr() const { |
| | return GetPrim().GetAttribute(MjcPhysicsTokens->mjcSolreffriction); |
| | } |
| |
|
| | UsdAttribute MjcPhysicsJointAPI::CreateMjcSolreffrictionAttr( |
| | VtValue const &defaultValue, bool writeSparsely) const { |
| | return UsdSchemaBase::_CreateAttr( |
| | MjcPhysicsTokens->mjcSolreffriction, SdfValueTypeNames->DoubleArray, |
| | false, SdfVariabilityUniform, defaultValue, writeSparsely); |
| | } |
| |
|
| | UsdAttribute MjcPhysicsJointAPI::GetMjcSolimpfrictionAttr() const { |
| | return GetPrim().GetAttribute(MjcPhysicsTokens->mjcSolimpfriction); |
| | } |
| |
|
| | UsdAttribute MjcPhysicsJointAPI::CreateMjcSolimpfrictionAttr( |
| | VtValue const &defaultValue, bool writeSparsely) const { |
| | return UsdSchemaBase::_CreateAttr( |
| | MjcPhysicsTokens->mjcSolimpfriction, SdfValueTypeNames->DoubleArray, |
| | false, SdfVariabilityUniform, defaultValue, writeSparsely); |
| | } |
| |
|
| | UsdAttribute MjcPhysicsJointAPI::GetMjcStiffnessAttr() const { |
| | return GetPrim().GetAttribute(MjcPhysicsTokens->mjcStiffness); |
| | } |
| |
|
| | UsdAttribute MjcPhysicsJointAPI::CreateMjcStiffnessAttr( |
| | VtValue const &defaultValue, bool writeSparsely) const { |
| | return UsdSchemaBase::_CreateAttr( |
| | MjcPhysicsTokens->mjcStiffness, SdfValueTypeNames->Double, |
| | false, SdfVariabilityUniform, defaultValue, writeSparsely); |
| | } |
| |
|
| | UsdAttribute MjcPhysicsJointAPI::GetMjcActuatorfrcrangeMinAttr() const { |
| | return GetPrim().GetAttribute(MjcPhysicsTokens->mjcActuatorfrcrangeMin); |
| | } |
| |
|
| | UsdAttribute MjcPhysicsJointAPI::CreateMjcActuatorfrcrangeMinAttr( |
| | VtValue const &defaultValue, bool writeSparsely) const { |
| | return UsdSchemaBase::_CreateAttr( |
| | MjcPhysicsTokens->mjcActuatorfrcrangeMin, SdfValueTypeNames->Double, |
| | false, SdfVariabilityUniform, defaultValue, writeSparsely); |
| | } |
| |
|
| | UsdAttribute MjcPhysicsJointAPI::GetMjcActuatorfrcrangeMaxAttr() const { |
| | return GetPrim().GetAttribute(MjcPhysicsTokens->mjcActuatorfrcrangeMax); |
| | } |
| |
|
| | UsdAttribute MjcPhysicsJointAPI::CreateMjcActuatorfrcrangeMaxAttr( |
| | VtValue const &defaultValue, bool writeSparsely) const { |
| | return UsdSchemaBase::_CreateAttr( |
| | MjcPhysicsTokens->mjcActuatorfrcrangeMax, SdfValueTypeNames->Double, |
| | false, SdfVariabilityUniform, defaultValue, writeSparsely); |
| | } |
| |
|
| | UsdAttribute MjcPhysicsJointAPI::GetMjcActuatorfrclimitedAttr() const { |
| | return GetPrim().GetAttribute(MjcPhysicsTokens->mjcActuatorfrclimited); |
| | } |
| |
|
| | UsdAttribute MjcPhysicsJointAPI::CreateMjcActuatorfrclimitedAttr( |
| | VtValue const &defaultValue, bool writeSparsely) const { |
| | return UsdSchemaBase::_CreateAttr( |
| | MjcPhysicsTokens->mjcActuatorfrclimited, SdfValueTypeNames->Token, |
| | false, SdfVariabilityUniform, defaultValue, writeSparsely); |
| | } |
| |
|
| | UsdAttribute MjcPhysicsJointAPI::GetMjcActuatorgravcompAttr() const { |
| | return GetPrim().GetAttribute(MjcPhysicsTokens->mjcActuatorgravcomp); |
| | } |
| |
|
| | UsdAttribute MjcPhysicsJointAPI::CreateMjcActuatorgravcompAttr( |
| | VtValue const &defaultValue, bool writeSparsely) const { |
| | return UsdSchemaBase::_CreateAttr( |
| | MjcPhysicsTokens->mjcActuatorgravcomp, SdfValueTypeNames->Bool, |
| | false, SdfVariabilityUniform, defaultValue, writeSparsely); |
| | } |
| |
|
| | UsdAttribute MjcPhysicsJointAPI::GetMjcMarginAttr() const { |
| | return GetPrim().GetAttribute(MjcPhysicsTokens->mjcMargin); |
| | } |
| |
|
| | UsdAttribute MjcPhysicsJointAPI::CreateMjcMarginAttr( |
| | VtValue const &defaultValue, bool writeSparsely) const { |
| | return UsdSchemaBase::_CreateAttr( |
| | MjcPhysicsTokens->mjcMargin, SdfValueTypeNames->Double, |
| | false, SdfVariabilityUniform, defaultValue, writeSparsely); |
| | } |
| |
|
| | UsdAttribute MjcPhysicsJointAPI::GetMjcRefAttr() const { |
| | return GetPrim().GetAttribute(MjcPhysicsTokens->mjcRef); |
| | } |
| |
|
| | UsdAttribute MjcPhysicsJointAPI::CreateMjcRefAttr(VtValue const &defaultValue, |
| | bool writeSparsely) const { |
| | return UsdSchemaBase::_CreateAttr( |
| | MjcPhysicsTokens->mjcRef, SdfValueTypeNames->Double, |
| | false, SdfVariabilityUniform, defaultValue, writeSparsely); |
| | } |
| |
|
| | UsdAttribute MjcPhysicsJointAPI::GetMjcSpringrefAttr() const { |
| | return GetPrim().GetAttribute(MjcPhysicsTokens->mjcSpringref); |
| | } |
| |
|
| | UsdAttribute MjcPhysicsJointAPI::CreateMjcSpringrefAttr( |
| | VtValue const &defaultValue, bool writeSparsely) const { |
| | return UsdSchemaBase::_CreateAttr( |
| | MjcPhysicsTokens->mjcSpringref, SdfValueTypeNames->Double, |
| | false, SdfVariabilityUniform, defaultValue, writeSparsely); |
| | } |
| |
|
| | UsdAttribute MjcPhysicsJointAPI::GetMjcArmatureAttr() const { |
| | return GetPrim().GetAttribute(MjcPhysicsTokens->mjcArmature); |
| | } |
| |
|
| | UsdAttribute MjcPhysicsJointAPI::CreateMjcArmatureAttr( |
| | VtValue const &defaultValue, bool writeSparsely) const { |
| | return UsdSchemaBase::_CreateAttr( |
| | MjcPhysicsTokens->mjcArmature, SdfValueTypeNames->Double, |
| | false, SdfVariabilityUniform, defaultValue, writeSparsely); |
| | } |
| |
|
| | UsdAttribute MjcPhysicsJointAPI::GetMjcDampingAttr() const { |
| | return GetPrim().GetAttribute(MjcPhysicsTokens->mjcDamping); |
| | } |
| |
|
| | UsdAttribute MjcPhysicsJointAPI::CreateMjcDampingAttr( |
| | VtValue const &defaultValue, bool writeSparsely) const { |
| | return UsdSchemaBase::_CreateAttr( |
| | MjcPhysicsTokens->mjcDamping, SdfValueTypeNames->Double, |
| | false, SdfVariabilityUniform, defaultValue, writeSparsely); |
| | } |
| |
|
| | UsdAttribute MjcPhysicsJointAPI::GetMjcFrictionlossAttr() const { |
| | return GetPrim().GetAttribute(MjcPhysicsTokens->mjcFrictionloss); |
| | } |
| |
|
| | UsdAttribute MjcPhysicsJointAPI::CreateMjcFrictionlossAttr( |
| | VtValue const &defaultValue, bool writeSparsely) const { |
| | return UsdSchemaBase::_CreateAttr( |
| | MjcPhysicsTokens->mjcFrictionloss, SdfValueTypeNames->Double, |
| | false, SdfVariabilityUniform, defaultValue, writeSparsely); |
| | } |
| |
|
| | namespace { |
| | static inline TfTokenVector _ConcatenateAttributeNames( |
| | const TfTokenVector &left, const TfTokenVector &right) { |
| | TfTokenVector result; |
| | result.reserve(left.size() + right.size()); |
| | result.insert(result.end(), left.begin(), left.end()); |
| | result.insert(result.end(), right.begin(), right.end()); |
| | return result; |
| | } |
| | } |
| |
|
| | |
| | const TfTokenVector &MjcPhysicsJointAPI::GetSchemaAttributeNames( |
| | bool includeInherited) { |
| | static TfTokenVector localNames = { |
| | MjcPhysicsTokens->mjcGroup, |
| | MjcPhysicsTokens->mjcSpringdamper, |
| | MjcPhysicsTokens->mjcSolreflimit, |
| | MjcPhysicsTokens->mjcSolimplimit, |
| | MjcPhysicsTokens->mjcSolreffriction, |
| | MjcPhysicsTokens->mjcSolimpfriction, |
| | MjcPhysicsTokens->mjcStiffness, |
| | MjcPhysicsTokens->mjcActuatorfrcrangeMin, |
| | MjcPhysicsTokens->mjcActuatorfrcrangeMax, |
| | MjcPhysicsTokens->mjcActuatorfrclimited, |
| | MjcPhysicsTokens->mjcActuatorgravcomp, |
| | MjcPhysicsTokens->mjcMargin, |
| | MjcPhysicsTokens->mjcRef, |
| | MjcPhysicsTokens->mjcSpringref, |
| | MjcPhysicsTokens->mjcArmature, |
| | MjcPhysicsTokens->mjcDamping, |
| | MjcPhysicsTokens->mjcFrictionloss, |
| | }; |
| | static TfTokenVector allNames = _ConcatenateAttributeNames( |
| | UsdAPISchemaBase::GetSchemaAttributeNames(true), localNames); |
| |
|
| | if (includeInherited) |
| | return allNames; |
| | else |
| | return localNames; |
| | } |
| |
|
| | PXR_NAMESPACE_CLOSE_SCOPE |
| |
|
| | |
| | |
| | |
| | |
| | |
| | |
| | |
| | |
| |
|