Does PhysicsRevoluteJoint Support Tilted Rotation Axis with vector3f in Isaac Sim?

Isaac Sim Version

4.5.0
4.2.0
4.1.0
4.0.0
4.5.0
2023.1.1
2023.1.0-hotfix.1
Other (please specify):

Operating System

Ubuntu 22.04
Ubuntu 20.04
Windows 11
Windows 10
Other (please specify): 24.04

GPU Information

  • Model: GeForce RTX 4090
  • Driver Version: 550.144.03
    CUDA: 12.4

What I’m Trying to Achieve

My URDF defines a revolute joint with a tilted axis, like this:

<link name="link1">
    <inertial>
      <mass value="3.4086" />
      <origin xyz="0.00647 0.002071 0.000525" />
      <inertia ixx="0.00784" ixy="-4.3e-05" ixz="-8e-06" iyy="0.005399" iyz="5.7e-05" izz="0.005556" />
    </inertial>
    <visual>
      <geometry>
        <mesh filename="link1.STL" />
      </geometry>
    </visual>
    <collision>
      <geometry>
        <cylinder length="0.05" radius="0.03" />
      </geometry>
    </collision>
  </link>
  <joint name="JOINT_1" type="revolute">
    <parent link="link0" />
    <child link="link1" />
    <origin xyz="0 -0.1492 -0.04" />
    <axis xyz="0 0.966 0.259" />
  </joint>

This joint connects the robot’s pelvis to a leg, and I want link1 to rotate around a tilted axis (mostly Y, slightly +Z), as shown:

       Y
       |     * Axis: (0, 0.966, 0.259)
       |    /
       |   / link1 (rotates around this axis)
       |  /
       | /
       |/
       O------ X
       link0

through urdf importer, I got usda file like below.

def PhysicsRevoluteJoint "JOINT_1" (
                apiSchemas = ["PhysicsJointStateAPI:angular", "PhysxJointAPI", "PhysicsDriveAPI:angular"]
            )
            {
                float drive:angular:physics:maxForce = 270
                uniform token drive:angular:physics:type = "force"
                uniform token physics:axis = ""
                rel physics:body0 = </World/robot/link0>
                rel physics:body1 = </World/robot/link1>
                float physics:JointEquivalentInertia = 0.2251985
                point3f physics:localPos0 = (0, -0.1492, -0.04)
                point3f physics:localPos1 = (0, 0, 0)
                quatf physics:localRot0 = (0.70710677, 0, -0.18311895, 0.68298423)
                quatf physics:localRot1 = (0.70710677, 0, -0.18311895, 0.68298423)
                ...
            }

Issues

  1. UI Issue: Isaac Sim 4.5.0’s “Property” panel shows axis as “X”. but it’s not for real robot. Is this a UI bug?
  2. Motion Issue: The leg (link1) moves unexpectedly in -y and -x directions when rotating. Is this due to physics:axis, localRot0/localRot1, or something else?
  3. vector3f Support: Does PhysicsRevoluteJoint in 4.5.0 support vector3f for tilted axes? The schema mentions allowedTokens = [“X”, “Y”, “Z”] for uniform token, but is vector3f valid?
vector3f physics:axis = (0, 0.966, 0.259)

Questions

  1. Is vector3f supported for physics:axis in PhysicsRevoluteJoint (Isaac Sim 4.5.0)? Any best practices?
  2. Why does the UI show “X” instead of the vector3f value? Is this a known issue?
  3. Are there example USD files with tilted axes?

Hello, This is the expected behavior. Joints use one of its relative axis to define the degree of freedom, so the physics:axis must indeed be “X” (default), “Y”, or “Z”. The orientation must be embedded in the joint position offsets.
To accommodate for non-aligned axis in the URDF, we default to the X-aligned orientation, and apply the appropriate transforms in the joint offsets.

If you want the orientation to match, your URDF joint should instead be something like:

  <joint name="JOINT_1" type="revolute">
    <parent link="link0" />
    <child link="link1" />
    <origin xyz="0 -0.1492 -0.04" rpy="0 0.966 0.259"/>
    <axis xyz="1 0 0 /> <!-- Whatever axis makes more sense here - I didn't look too much in detail to know-->
  </joint>

Hi rgasoto,

Thank you for your response. I’d like to clarify my URDF setup and ensure I understood your suggestion correctly.

My intent for the JOINT_1 joint is to have its coordinate frame aligned with the parent link (link0, parallel to the world frame), so I’m keeping unchanged. Only the rotation axis is tilted, defined as [0, 0.966, 0.259] (roughly 15° from Y toward +Z). Your suggestion to use and made me think you interpreted my URDF as needing a rotated joint frame, but I want the joint frame to stay aligned with link0 and only tilt the rotation axis.

The USDA output includes

quatf physics:localRot0 = (0.70710677, 0, -0.18311895, 0.68298423)
quatf physics:localRot1 = (0.70710677, 0, -0.18311895, 0.68298423)
uniform token physics:axis = ""

I have two questions:

  1. Does the physics:localRot0/1 quaternion accurately represent my intended rotation axis [0, 0.966, 0.259] with physics:axis = “X”? I want to ensure the USDA captures the tilted axis while maintaining the joint frame’s alignment with link0.
  2. Is it okay for physics:axis to be an empty string ( “”)? Or should it be set to “X”, “Y”, or “Z” to ensure correct behavior?

I appreciate your help in confirming these points