Articulations#

Articulations provide an alternative, and often superior approach to simulating mechanisms composed of jointed rigid bodies. Typically, you achieve higher simulation fidelity with articulations as they have zero joint error by design, and can handle larger mass ratios between the jointed bodies. PhysX simulates articulations in reduced-coordinates, where the configuration of the articulation is determined by its root body and the joint angles instead of the world pose of each body involved.

You can often turn jointed rigid bodies into an articulation given that they do not contain unsupported joints, see the Joint Table, and ensuring that loops are resolved appropriately. In order to enable articulation simulation on jointed rigid bodies, apply the UsdPhysics.ArticulationRootAPI component to the appropriate primitive, see USD Hierarchy / Articulation Root.

In the following, we often use the term (articulation) link for a rigid body that is part of an articulation.

Note

If you encounter stability issues with articulations in your robot simulations, please refer to the Articulation and Robot Simulation Stability Guide.

Articulation Tree Structure#

Articulations must have a tree structure in terms of the rigid-body links and the joints between them (loops are possible, however). The tree structure is created solely by the Body 0 and Body 1 relationships of the joints connecting the articulation links (i.e. rigid bodies) - the USD hierarchy has no impact on the articulation structure other than during parsing, see below. Therefore, you may organize the joints and links in the stage tree as you see fit.

Here are two example articulations: A ragdoll and a robotic arm.

Articulation examples

The tree structure for the arm is straightforward: The root is at the base on the ground plane, and revolute joints connect the different links up to the manipulator, where the tree has its only branch to connect the two gripper parts to the end-effector with prismatic (i.e. linear) joints.

For the ragdoll, we can choose any link, i.e. limb as the root and the resulting structure is always a tree. For example, we can choose the head to be the root, and connect the torso to it with a spherical joint, which in turn uses spherical joints to attach the arms, and so on.

While in practice, the root can be placed on any link for a floating-base articulation, it is a good rule of thumb to choose a central node such that traversal distances to the leaf nodes of the articulation are reduced. The heuristic for root-node determination described in Create an Articulation Based on Topology typically leads to the selection of central links. Of course, the application may require setting the root to a specific link, e.g. a quadruped torso, because control algorithms are designed around this topology.

Note

An implication of the articulation algorithm operating on reduced coordinates is that contrary to non-articulation jointed rigid bodies, setting poses and velocities on non-root links is not supported and triggers a warning in the console. For further differences and limitations, please see Articulation Limitations and Differences.

Floating and Fixed-Base#

There is a key difference between the two articulation examples: The ragdoll is a floating articulation which means the root (e.g. the head) and therefore the entire robot may move freely in space.

The robot arm is a fixed-base articulation: Its base, i.e. root link is fixed to the world frame.

USD Hierarchy / Articulation Root#

You should consider the USD hierarchy when you apply the UsdPhysics.ArticulationRootAPI component to a prim such that one or more articulations are created.

The rules are as follows:

For a fixed-base articulation, add the Root API either to:

  1. the fixed joint that connects the articulation base to the world, or

  2. an ancestor of the fixed joint in the USD hierarchy. See more information in Create an Articulation Based on Topology.

In the robotic-arm example above, we connect the robot’s base to the world frame using a fixed joint, and then could, for example, apply the root component to this joint.

Note that there is no need to specify the joint frames of the fixed joint since its joint frames are ignored; the main purpose of the fixed joint is to specify the root link. Further note that any joint type supported by articulations may be used as a joint for the root link to the world frame. However, it is recommended that you use a fixed joint, because it best expresses the intention.

For a floating-base articulation, add the Articulation Root component either to:

  1. the rigid-body link that shall be the root, or

  2. an ancestor of the root link in the USD hierarchy. See more information in Create an Articulation Based on Topology.

In the ragdoll example, we could, for example, apply the root component to the head link.

Create a Floating-Base Articulation#

The following Python snippet creates a single dynamic rigid body and converts it to an articulation link that is the root link of a floating-base articulation. The script also sets initial pose and velocity of the root link, which is only possible on root links if articulations are used.

The snippet may be extended to add further links and joints using the USD schema introduced in sections Rigid Bodies, Colliders, and Joints.

from pxr import Usd, UsdGeom, UsdPhysics, Gf, PhysxSchema
import omni.usd

# Create a stage
omni.usd.get_context().new_stage()
stage  = omni.usd.get_context().get_stage()

# Define the root Xform (transformable object)
rootxform = UsdGeom.Xform.Define(stage, "/World")

rigidBodyPath = "/World/rigidBody"

# Initial pose and velocity
rigidBodyStartPosition = Gf.Vec3f(0, 0, 0)
rigidBodyStartRotation = Gf.Quatf(1.0)
rigidBodyStartLinVelocity = Gf.Vec3f(0, 10, 0)
rigidBodyStartAngVelocity = Gf.Vec3f(0, 0, 10)

# Create the rigid body
rigidBodyXform = UsdGeom.Xform.Define(stage, rigidBodyPath)
rigidBodyXform.AddTranslateOp().Set(rigidBodyStartPosition)
rigidBodyXform.AddOrientOp().Set(rigidBodyStartRotation)
rigidBodyPrim = rigidBodyXform.GetPrim()

# Apply the rigid body api and set the body's initial state.
rigidBodyAPI = UsdPhysics.RigidBodyAPI.Apply(rigidBodyPrim)
rigidBodyAPI.CreateRigidBodyEnabledAttr(True)
rigidBodyAPI.CreateVelocityAttr(rigidBodyStartLinVelocity)
rigidBodyAPI.CreateAngularVelocityAttr(rigidBodyStartAngVelocity)

# Auto-compute the mass properties of the rigid body
massAPI = UsdPhysics.MassAPI.Apply(rigidBodyPrim)
massAPI.CreateMassAttr(2.0)

# Apply the articulation api to the rigid body.
# rigidBodyPrim is now the root link of a floating
# articulation that has a single link.
UsdPhysics.ArticulationRootAPI.Apply(rigidBodyPrim)

Create a Fixed-Base Articulation#

The following snippet creates a fixed-base articulation with two links coupled by a revolute joint.

from pxr import Usd, UsdGeom, UsdPhysics, Gf, PhysxSchema
import omni.usd

# Create a stage
omni.usd.get_context().new_stage()
stage  = omni.usd.get_context().get_stage()

# Define the root Xform (transformable object)
rootxform = UsdGeom.Xform.Define(stage, "/World")

rigidBodyPaths = ["/World/rigidBody0", "/World/rigidBody1"]
revoluteJointPath = "/World/revoluteJoint"
fixedJointPath = "/World/fixedJoint"

# The initial pose of the root link.
rootLinkStartPosition = Gf.Vec3f(0, 0, 0)
rootLinkStartRotation = Gf.Quatf(1.0)
# The joint frames of the revolute joint coupling
# the two links of the articulation.
revoluteJointlocalPositions = [Gf.Vec3f(0.0, 10.0, 0.0), Gf.Vec3f(0.0, 0.0, 0.0)]
revoluteJointLocalRotations = [Gf.Quatf(1.0), Gf.Quatf(1.0)]

# body0 is chosen to be the root link.
rootLinkId = 0
rigidBodyXforms = [None] * 2

for i in range(2):

    # Create the rigid body
    rigidBodyXform = UsdGeom.Xform.Define(stage, rigidBodyPaths[i])
    rigidBodyXforms[i] = rigidBodyXform
    rigidBodyPrim = rigidBodyXform.GetPrim()
    rigidBodyAPI = UsdPhysics.RigidBodyAPI.Apply(rigidBodyPrim)
    rigidBodyAPI.CreateRigidBodyEnabledAttr(True)
    massAPI = UsdPhysics.MassAPI.Apply(rigidBodyPrim)
    massAPI.CreateMassAttr(2.0)


# Create a revolute joint between the two rigid body prims
revoluteJoint = UsdPhysics.RevoluteJoint.Define(stage, revoluteJointPath)
revoluteJoint.CreateAxisAttr(UsdPhysics.Tokens.y)
revoluteJoint.CreateBody0Rel().AddTarget(rigidBodyPaths[0])
revoluteJoint.CreateBody1Rel().AddTarget(rigidBodyPaths[1])
revoluteJoint.CreateLocalPos0Attr().Set(revoluteJointlocalPositions[0])
revoluteJoint.CreateLocalRot0Attr().Set(revoluteJointLocalRotations[0])
revoluteJoint.CreateLocalPos1Attr().Set(revoluteJointlocalPositions[1])
revoluteJoint.CreateLocalRot1Attr().Set(revoluteJointLocalRotations[1])

# Create a fixed joint between the root link and the world.
# Mark the fixed joint as the root. This will create a fixed
# base articulation with body0 as the root link.
fixedJoint = UsdPhysics.FixedJoint.Define(stage, fixedJointPath)
fixedJoint.CreateBody0Rel().AddTarget(rigidBodyPaths[rootLinkId])
UsdPhysics.ArticulationRootAPI.Apply(fixedJoint.GetPrim())

# Set the initial pose of the root link
rigidBodyXforms[rootLinkId].AddTranslateOp().Set(rootLinkStartPosition)
rigidBodyXforms[rootLinkId].AddOrientOp().Set(rootLinkStartRotation)

Create an Articulation Based on Topology#

When the articulation root is not directly applied to a fixed joint or rigid body, the simulator attempts to determine the articulation type and topology automatically.

The automation process works as follows:
  1. Traverse the hierarchy below the articulation root.

  2. Create topologies, which are graphs based on the traversed bodies and joints connecting them.

  3. For each topology, apply a deterministic algorithm to select the articulation root:

    • If any joint to the world is found, the topology (articulation) is considered fixed-base. The articulation root link is the body connected to the world with this joint.

    • If no world joint is found, the topology is considered floating-base. In this case, the articulation root is set to the graph node (articulation link) with minimal eccentricity.

Note that with this automation, it’s not possible to know the articulation root beforehand. As a result applying poses and velocities to the articulation root is not feasible unless the root is identified after parsing.

JointStateAPI for Set and Get of Joint Position And Velocity#

Each degree of freedom of an articulated joint has position and velocity attributes. These attributes may be queried or modified by applying PhysxSchema.JointStateAPI to the corresponding joint prim. This is a feature unique to articulated joints.

The PhysxSchema.JointStateAPI can be used to set initial position and velocity of the articulation joint. In the absence of the API, the simulation initializes the joint positions and velocities to zero.

The following Python snippet may be added to the snippet in section Create a Fixed-Base Articulation to set the initial position and velocity of the revolute joint:

jointStateAPI = PhysxSchema.JointStateAPI.Apply(revoluteJoint.GetPrim(), UsdPhysics.Tokens.angular)
jointStateAPI.CreatePositionAttr(45.0)
jointStateAPI.CreateVelocityAttr(180.0)

The position and velocity of the degree of freedom permitted by the revolute joint may be queried as follows:

jointPosition = jointStateAPI.GetPositionAttr().Get()
jointVelocity = jointStateAPI.GetVelocityAttr().Get()

Tokens such as UsdPhysics.Tokens.linear and UsdPhysics.Tokens.rotX are used to specify the degree of freedom whose state will be queried or modified. For example, a prismatic joint would use the token UsdPhysics.Tokens.linear, while a spherical joint would use UsdPhysics.Tokens.rotX, UsdPhysics.Tokens.rotY, or UsdPhysics.Tokens.rotZ, as appropriate.

Note

For performance in reinforcement learning or other simulation workloads, you may enable the physics Fabric extension (see enabling Fabric). The above USD access to the joint state will no longer work in that case, but you can use the Tensor API ArticulationView instead that directly accesses PhysX data.

Closed Loops#

Articulation joints on their own do not support closed loops. For example, links A, B, C may be connected with articulation joints coupling A to B and B to C, but not with an articulation joint that also couples C to A. This final joint would create a closed loop of articulation joints and is not supported.

Articulation Closed Loop

Closing loops is still possible by using a regular joint (rather than an articulation joint). This is achieved by marking the loop-closing joint as being excluded from the articulation. For the example above, this would involve marking the joint coupling C to A as excluded from the articulation, see below.

Note

Simulation of articulations with closed-loops is more challenging for the solver and you may encounter instabilities; try lowering the simulation time step, and follow other advice in Articulation and Robot Simulation Stability Guide.

Exclude Joints from Articulations#

You most often exclude joints from an articulation when breaking closed loops; but you may also use it to connect a swappable manipulator to a robot arm, i.e. to connect two articulations to each other using a fixed joint.

The snippet creates four links arranged at the corners of a square in the x-y plane. Each edge of the square has a corresponding joint which results in a closed loop. This loop is broken by excluding the last joint from the articulation. An additional joint is added to make the articulation fixed-base.

from pxr import Usd, UsdGeom, UsdPhysics, Gf, PhysxSchema
import omni.usd

# Create a stage
omni.usd.get_context().new_stage()
stage  = omni.usd.get_context().get_stage()

# Define the root Xform (transformable object)
rootxform = UsdGeom.Xform.Define(stage, "/World")

rootLinkfixedJointPath = "/World/rootLinkfixedJoint"
rigidBodyPaths = ["/World/rigidBody0", "/World/rigidBody1", "/World/rigidBody2", "/World/rigidBody3"]
rigidBodyBoxPaths = ["/World/rigidBody0/box", "/World/rigidBody1/box", "/World/rigidBody2/box", "/World/rigidBody3/box"]
rigidBodyStartPositions = [Gf.Vec3f(0, 0, 0), Gf.Vec3f(0, 10, 0), Gf.Vec3f(10, 10, 0), Gf.Vec3f(10, 0, 0)]
fixedJointPaths = ["/World/fixedJoint0", "/World/fixedJoint1", "/World/fixedJoint2", "/World/fixedJoint3"]
fixedJointBodyPairs = [[0, 1], [1,2], [2,3], [3,0]]

# The joint frames of the revolute joint coupling
# the two links of the articulation.
fixedJointlocalPositions0 = [Gf.Vec3f(0.0, 10.0, 0.0), Gf.Vec3f(10.0, 0.0, 0.0), Gf.Vec3f(0.0, -10.0, 0.0), Gf.Vec3f(-10.0, 0.0, 0.0)]
fixedJointlocalPositions1 = [Gf.Vec3f(0.0, 0.0, 0.0), Gf.Vec3f(0.0, 0.0, 0.0), Gf.Vec3f(0.0, 0.0, 0.0), Gf.Vec3f(0.0, 0.0, 0.0)]
fixedJointLocalRotations0 = [Gf.Quatf(1.0), Gf.Quatf(1.0), Gf.Quatf(1.0), Gf.Quatf(1.0)]
fixedJointLocalRotations1 = [Gf.Quatf(1.0), Gf.Quatf(1.0), Gf.Quatf(1.0), Gf.Quatf(1.0)]

for i in range(4):

    # Create the rigid body
    rigidBodyXform = UsdGeom.Xform.Define(stage, rigidBodyPaths[i])
    rigidBodyXform.AddTranslateOp().Set(rigidBodyStartPositions[i])
    rigidBodyPrim = rigidBodyXform.GetPrim()
    rigidBodyAPI = UsdPhysics.RigidBodyAPI.Apply(rigidBodyPrim)
    rigidBodyAPI.CreateRigidBodyEnabledAttr(True)
    massAPI = UsdPhysics.MassAPI.Apply(rigidBodyPrim)
    massAPI.CreateMassAttr(2.0)

for i in range(4):

    fixedJoint = UsdPhysics.FixedJoint.Define(stage, fixedJointPaths[i])
    body0Index = fixedJointBodyPairs[i][0]
    body1Index = fixedJointBodyPairs[i][1]
    fixedJoint.CreateBody0Rel().AddTarget(rigidBodyPaths[body0Index])
    fixedJoint.CreateBody1Rel().AddTarget(rigidBodyPaths[body1Index])
    fixedJoint.CreateLocalPos0Attr().Set(fixedJointlocalPositions0[body0Index])
    fixedJoint.CreateLocalRot0Attr().Set(fixedJointLocalRotations0[body0Index])
    fixedJoint.CreateLocalPos1Attr().Set(fixedJointlocalPositions1[body1Index])
    fixedJoint.CreateLocalRot1Attr().Set(fixedJointLocalRotations1[body1Index])
    if i==3:
        fixedJoint.CreateExcludeFromArticulationAttr(True)

# Create a fixed joint to the world and define it
# as the articulation root
rootLinkFixedJoint = UsdPhysics.FixedJoint.Define(stage, rootLinkfixedJointPath)
rootLinkFixedJoint.CreateBody0Rel().AddTarget(rigidBodyPaths[0])
UsdPhysics.ArticulationRootAPI.Apply(rootLinkFixedJoint.GetPrim())

Articulation Mimic Joints#

Mimic joints allow the position of two degrees of freedom of the same articulation to be coupled with a linear relationship.

For example, you can use mimic joints to create

  • a gear joint by coupling two revolute joints, or

  • a rack-and-pinion-joint by coupling a prismatic and revolute joint.

Note that when simulating articulations, it is recommended that you use mimic joints instead of the Meta Joints implementations of the gear and rack-and-pinion joints. Mimic joints are articulation-specific and fully GPU accelerated.

Mimic joints are characterized by a gear ratio G and an offset γ such that:

qA+GqB+γ=0

with qA and qB denoting the positions of the two degrees of freedom coupled by the mimic joint.

Note

  • Mimic joints only support revolute joints with limits applied. The limits may have any value. For example, setting the limit to a very large value could create a situation where the limit is never exceeded.

  • Mimic joints only support articulation joints.

The following Python snippet creates a mimic joint that implements a gear-joint relationship. The mimic joint couples the two revolute joint positions of joint0 and joint1. Then, joint0 is initialized to an angular speed of 800 degrees per second, while joint1 is initialized to zero angular speed. The mimic joint with gear ratio five will then pull joint1 along as the simulation progresses.

from pxr import Usd, UsdGeom, UsdPhysics, Gf, PhysxSchema, Sdf
import omni.usd

# Create a stage
omni.usd.get_context().new_stage()
stage  = omni.usd.get_context().get_stage()

# Define the root Xform (transformable object)
rootxform = UsdGeom.Xform.Define(stage, "/World")

rootBodyPath = "/World/rootBody"
rootBodyFixedJointPath = "/World/rootBodyFixedJoint"

rigidBodyPaths = ["/World/rigidBody0", "/World/rigidBody1"]
rigidBodySpherePaths = ["/World/rigidBody/sphere", "/World/rigidBody/sphere"]
sphereRadii = [5, 5]
revoluteJointPaths = ["/World/revoluteJoint0", "/World/revoluteJoint1"]
revoluteJointBody0Positions = [Gf.Vec3f(-5, 0, 0), Gf.Vec3f(5, 0, 0)]

# Create the root body
rootBodyXform = UsdGeom.Xform.Define(stage, rootBodyPath)
rootBodyXform.AddTranslateOp().Set(Gf.Vec3f(0.0))
rootBodyXform.AddOrientOp().Set(Gf.Quatf(1.0))
rootBodyPrim = rootBodyXform.GetPrim()
rigidBodyAPI = UsdPhysics.RigidBodyAPI.Apply(rootBodyPrim)
rigidBodyAPI.CreateRigidBodyEnabledAttr(True)

# Create two siblings (body0 and body1) as children of the root.
# Create an inbound revolute joint (joint0 and joint1) for each child.
for i in range(2):

    # Create a rigid body
    rigidBodyXform = UsdGeom.Xform.Define(stage, rigidBodyPaths[i])
    rigidBodyPrim = rigidBodyXform.GetPrim()
    rigidBodyAPI = UsdPhysics.RigidBodyAPI.Apply(rigidBodyPrim)
    rigidBodyAPI.CreateRigidBodyEnabledAttr(True)
    massAPI = UsdPhysics.MassAPI.Apply(rigidBodyPrim)
    massAPI.CreateDensityAttr(2.0)

    # Add a sphere collider
    sphereGeom = UsdGeom.Sphere.Define(stage, rigidBodySpherePaths[i])
    sphereGeom.CreateRadiusAttr(sphereRadii[i])
    sphereGeom.AddTranslateOp().Set(Gf.Vec3f(0.0))
    sphereGeom.AddOrientOp().Set(Gf.Quatf(1.0))
    spherePrim = sphereGeom.GetPrim()
    UsdPhysics.CollisionAPI.Apply(spherePrim)

    # Create a revolute joint between the root link and the rigid body
    revoluteJoint = UsdPhysics.RevoluteJoint.Define(stage, revoluteJointPaths[i])
    revoluteJoint.CreateBody0Rel().AddTarget(rootBodyPath)
    revoluteJoint.CreateBody1Rel().AddTarget(rigidBodyPaths[i])
    revoluteJoint.CreateAxisAttr(UsdPhysics.Tokens.z)
    revoluteJoint.CreateLocalPos0Attr().Set(revoluteJointBodyPositions[i])
    revoluteJoint.CreateLowerLimitAttr(-9000.0)
    revoluteJoint.CreateUpperLimitAttr(9000.0)

# Create a fixed joint between the root body and the world.
# Mark the fixed joint as the root. This will create a fixed
# base articulation with body0 as the root link.
fixedJoint = UsdPhysics.FixedJoint.Define(stage, rootLinkFixedJointPath)
fixedJoint.CreateBody0Rel().AddTarget(rigidBodyPaths[0])
UsdPhysics.ArticulationRootAPI.Apply(fixedJoint.GetPrim())

jointPrim0 = stage.GetPrimAtPath(revoluteJointPaths[0])

# Apply a joint speed to one of the revolute joints
jointStateAPI = PhysxSchema.JointStateAPI.Apply(jointPrim0, UsdPhysics.Tokens.angular)
jointStateAPI.CreatePositionAttr(0.0)
jointStateAPI.CreateVelocityAttr(800.0)

# Create a mimic joint
mimicJointAPI = PhysxSchema.PhysxMimicJointAPI.Apply(jointPrim0, UsdPhysics.Tokens.rotZ)
mimicJointAPI.GetReferenceJointRel().AddTarget(revoluteJointPaths[1])
mimicJointAPI.GetReferenceJointAxisAttr().Set(UsdPhysics.Tokens.rotZ)
mimicJointAPI.GetGearingAttr().Set(5.0)
mimicJointAPI.GetOffsetAttr().Set(0.0)

Articulation Mimic Joint Compliance#

Mimic joints support compliance, as discussed here in the PhysX SDK guide. In the absence of compliance, mimic joints apply the impulses necessary to instantaneously maintain the mimic joint equation. This can lead to instability in the event that another sub-system is pushing back equally hard to break the mimic joint constraint.

Gripping scenarios may exhibit mimic joint instability when finger joints are “passively” actuated via a mimic joint connected to a driven joint. This scenario is especially prone to instability when the driven joint is configured to be very stiff (i.e. high position gain) compared to the typically small masses and inertia of finger links: When the finger tip is in contact with an object, the mimic joint will be a constraint competing with the hard contact which may cause stability issues.

One solution to the numerical issues arising from the competing constraints is to add compliance to the mimic joints. Mimic joint compliance is achieved with two parameters that model compliance as a spring-damper: natural frequency and damping ratio.

The following python script may be added to the script in section Articulation Mimic Joints to add compliance to a mimic joint:

from omni.physx.bindings._physx import (
    MIMIC_JOINT_ATTRIBUTE_NAME_NATURAL_FREQUENCY_ROTX,
    MIMIC_JOINT_ATTRIBUTE_NAME_NATURAL_FREQUENCY_ROTY,
    MIMIC_JOINT_ATTRIBUTE_NAME_NATURAL_FREQUENCY_ROTZ,
    MIMIC_JOINT_ATTRIBUTE_NAME_DAMPING_RATIO_ROTX,
    MIMIC_JOINT_ATTRIBUTE_NAME_DAMPING_RATIO_ROTY,
    MIMIC_JOINT_ATTRIBUTE_NAME_DAMPING_RATIO_ROTZ)

# Set the compliance attributes of the mimic joint
jointPrim0.CreateAttribute(MIMIC_JOINT_ATTRIBUTE_NAME_NATURAL_FREQUENCY_ROTX, Sdf.ValueTypeNames.Float).Set(100.0)
jointPrim0.CreateAttribute(MIMIC_JOINT_ATTRIBUTE_NAME_DAMPING_RATIO_ROTX, Sdf.ValueTypeNames.Float).Set(1.2)

Tuning a Compliant Mimic Joint#

A metric that helps tuning compliance is the product of simulation timestep and natural frequency. Larger product values are more likely to lead to instability, while smaller product values are more likely to lead to stability. If the product of simulation timestep and natural frequency is many orders of magnitude greater than 1, there is no effective compliance, and you may just as well avoid configuring compliance.

  1. A good starting point for the product of natural frequency and simulation timestep is 1. This might lead to the mimic joint appearing sluggish. Increase the natural frequency until the sluggishness is reduced to an acceptable or even imperceptible level but not so great that the compliance has no effect.

  2. Increasing the number of position iterations with the TGS solver reduces the effective simulation timestep. This is particularly true when the behavior of the articulation is not dominated by collision response.

  3. Joints such as gear and rack-and-pinion joints are rarely underdamped. Avoid damping ratios less than 1 to avoid oscillations arising from underdamping. Avoid values much greater than 1 to avoid sluggish approaches to the equilibrium state of the mimic joint.

  4. Note that increasing the number of position iterations and/or reducing the simulation timestep incurs a performance penalty. For recovering some performance, see also the hints in Reduce Simulation Timestep for Complex Systems and Closed Loops.

Articulation Limitations and Differences#

The following list describes further differences and limitations:

  • Each articulation link has a single inbound joint and any loops in the topology must be broken as described in Closed Loops.

  • Articulations do not support all types of USD joints, see the list here for compatibility.

  • Articulation joints of type UsdPhysics.SphericalJoint have swing limits that form a pyramid rather than an elliptical cone.

  • Articulation joints only support a single linear degree of freedom or up to three angular degrees of freedom, you should consider this limitation when a D6 Joint is to be included in an articulation.

  • Initial articulation joint violations are resolved before the first simulation step involving the articulation. Joint violations arising from joint-position limits persist until the simulation resolves them. See also JointStateAPI for Set and Get of Joint Position And Velocity.

  • Articulation joints do not support the breaking force and torque attributes associated with UsdPhysics.Joint.

  • Articulation joints may not be removed from the stage at run-time (after a simulation step has been performed).

  • Articulation joints support querying and setting velocity and position attributes of each degree of freedom of a joint with the PhysxSchema.JointStateAPI.

  • Articulated joints with a single degree of angular motion may accumulate a joint position greater than 360° if limits are enabled on the joint. This is true of joints that are configured with UsdPhysics.RevoluteJoint and joints that are configured with UsdPhysics.Joint and allow only angular motion around a single axis. The joint position of a revolute joint that does not have limits applied will wrap on a 360° boundary.

  • Articulated joints configured using UsdPhysics.Joint and UsdPhysics.LimitAPI do not support distance limits configured with the UsdPhysics.Tokens.distance token.

  • Articulation joints may not be instanced, see Joint Instancing.

  • The breakForce attribute of UsdPhysics.Joint is ignored for articulation joints.

  • Articulation joint limits are hard constraints that do not support stiffness and damping parameters in the PhysxSchema.PhysxLimitAPI.

Extensions and Articulations#

When you use extensions that access the underlying PhysX articulation data (e.g. Omni Physics Tensors), it is beneficial to set up articulations such that their USD and PhysX topologies are identical - only then do you get a one-to-one relationship between USD and PhysX joint parameters such as limits and drive targets. The USD physics interface must provide identical behavior for articulation and regular joints, and it may therefore swap joint limits or negate joint drive targets when parsing from USD to the PhysX articulation; this is because USD joints do not have to follow the articulation topology, e.g., it may be that the body0 relationship does not point to the parent link in the PhysX articulation, but the USD joint limit is defined in the body0 to body1 joint frame order.