Modeling a Rocker–Bogie Closed-Loop Differential in Isaac Sim While Maintaining URDF Tree Structure

Problem Description

I am modeling a two-wheel rocker–bogie rover suspension for simulation in Isaac Sim. As expected, URDF requires a strict tree structure and does not support closed-loop kinematic chains. However, the rocker–bogie mechanism contains a passive differential bar that mechanically enforces the constraint:

θL+θR=constant

In the real mechanism, this differential:

  • Couples the left and right rocker rotations

  • Transfers torque between rockers

  • Distributes load symmetrically

Because URDF does not allow closed loops (a link cannot have multiple parents), I currently model the robot as a tree:

base_link
 ├── left_rocker_joint (passive revolute)
 │    └── left_bogie_joint
 └── right_rocker_joint (passive revolute)
      └── right_bogie_joint

The mechanical differential bar is omitted.


Core Question

What is the recommended way in Isaac Sim to accurately simulate the rocker differential behavior while keeping the URDF articulation tree valid?

Additional Context

  • The rocker joints are passive (no motors).

  • The rover is intended for physically accurate mobility simulation (not just navigation/SLAM).

  • I want to preserve realistic load transfer and suspension behavior.

  • I am aware that many simplified rover URDF models omit the differential entirely, but I would like to understand the proper high-fidelity modeling approach within Isaac Sim.

    If there is documentation or example projects demonstrating this pattern, I would appreciate references.

Hi, the suggestion is similar to what you did, modeling the differential bar as a passive revolute joint with zero drive gains, allowing natural load balancing.

from pxr import UsdPhysics, PhysxSchema

#In your URDF, define differential as a continuous joint with no limits
#Then in Isaac Sim, configure it as passive

stage = omni.usd.get_context().get_stage()
differential_joint_path = "/World/Rover/DifferentialJoint"
differential_prim = stage.GetPrimAtPath(differential_joint_path)

#Apply PhysX joint API for advanced control
physx_joint = PhysxSchema.PhysxJointAPI.Apply(differential_prim)

#Set to passive (zero st_iffness and damping)
joint = UsdPhysics.RevoluteJoint(differential_prim)
drive = UsdPhysics.DriveAPI.Apply(differential_prim, "angular")
drive.CreateStiffnessAttr(0.0)  # Zero stiffness = passive
drive.CreateDampingAttr(0.1)    # Small damping for stability
drive.CreateMaxForceAttr(0.0)   # No actuation

#Optional_: Add friction for realistic behavior
physx_joint.CreateJointFrictionAttr(0.01)

Example URDF Structure:

<joint name="differential_joint" type="continuous">
  <parent link="chassis"/>
  <child link="differential_bar"/>
  <axis xyz="0 1 0"/>  
  <dynamics damping="0.1" friction="0.01"/>
</joint>

<joint name="left_rocker_joint" type="revolute">
  <parent link="differential_bar"/>
  <child link="left_rocker"/>
</joint>

<joint name="right_rocker_joint" type="revolute">
  <parent link="differential_bar"/>
  <child link="right_rocker"/>
</joint>