Understanding physics:diagonalInertia, physics:centerOfMass, and physics:principalAxes for UR10 Joints in Isaac Sim

Isaac Sim Version

4.2.0

Operating System

Windows 11

GPU Information

  • Model: geforce 3060

  • Driver Version: 560

Topic Description

Understanding physics:diagonalInertia, physics:centerOfMass, and physics:principalAxes for UR10 Joints in Isaac Sim

Detailed Description

Hello everyone,

I am working with UR10 robotic arm in Isaac Sim and trying to properly extract and apply joint-related physical properties, including physics:diagonalInertia, physics:centerOfMass, and physics:principalAxes. I have a few questions regarding their roles and how they influence the simulation.

1. physics:diagonalInertia (Diagonal Inertia)

1-1: What is the exact role of diagonalInertia in defining UR10’s joints?

1-2: How does it relate to the inertia tensor in PhysX/Isaac Sim?

1-3: Is this value automatically computed based on mass and shape, or do I need to manually define it?

1-4: If manually defined, what units and reference frames should I consider?

2. physics:centerOfMass (Center of Mass)

2-1: In UR10, each joint has its own center of mass. Does Isaac Sim compute it based on geometry, or should I explicitly set this value?

2-2: Is the centerOfMass defined in the local joint frame or the global frame?

2-3: What impact does an incorrect centerOfMass have on the joint dynamics and simulation stability?

3. physics:principalAxes (Principal Axes)

3-1: How are principalAxes related to diagonalInertia?

3-2: Do I need to extract this data from a URDF file or another source, or can it be computed inside Isaac Sim?

3-3: If these axes are misaligned or incorrect, how does it affect joint movements and torque calculations?

I am particularly interested in extracting accurate data for each UR10 joint to ensure proper physics-based behavior in the simulation. If anyone has experience working with similar robotic arms in Isaac Sim or PhysX, I would appreciate any insights or references.

Thank you in advance!

Steps to Reproduce

  1. Importing UR10 in NVIDIA localhost and adding an Action Graph.

  2. These are attributes included in the attribute Name of the Action Graph associated with the link.

pic

video

Hi @aiden_kim,

Thank you for your question. Here are some answers:

1. physics:diagonalInertia (Diagonal Inertia)

1-1: What is the exact role of diagonalInertia in defining UR10’s joints?
The diagonal inertia represents the inertia of a rigid body along its principal axes of inertia. Specifically it refers to the rotational inertia and determined the resistance of the body to rotational acceleration around each axis, so it is important to get right for accurate physics simulation.

1-2: How does it relate to the inertia tensor in PhysX/Isaac Sim?
An inertia tensor, when expressed at the center of mass becomes diagonal. The inertia tensors in PhysX/Isaac Sim are expressed at the center of mass of bodies, so they are directly related to the diagonalInertia.

1-3: Is this value automatically computed based on mass and shape, or do I need to manually define it?
If you’re importing a UR10 from a URDF file, the inertia values should be defined in the URDF. The URDF specification (see ROS URDF/XML/link documentation) includes an <inertia> element with attributes for the moments of inertia (ixx, iyy, izz) and products of inertia (ixy, ixz, iyz).

If the URDF doesn’t specify inertia, Isaac Sim will generate default values based on a uniform mass distribution assumption and the geometry of the prim. This approach is not recommended for accurate simulation, as real robot links typically have non-uniform mass distribution (e.g., motors concentrated in one area, hollow sections in others).

1-4: If manually defined, what units and reference frames should I consider?
Inertia is typically measured in kg·m². The reference frame for inertia is the body’s principal axes frame located at the center of mass. When defining in URDF, the inertia values are specified relative to the center of mass frame, which may have an offset from the link’s origin frame (specified by the <origin> tag within the <inertial> element).

2. physics:centerOfMass (Center of Mass)

2-1: In UR10, each joint has its own center of mass. Does Isaac Sim compute it based on geometry, or should I explicitly set this value?
For each link in the UR10, you should explicitly set the center of mass rather than relying on Isaac Sim’s computation. While Isaac Sim can calculate it based on geometry assuming uniform density, this is likely not going to be accurate.

2-2: Is the centerOfMass defined in the local joint frame or the global frame?
In the local link frame

2-3: What impact does an incorrect centerOfMass have on the joint dynamics and simulation stability?
An incorrect center of mass will alter how gravity and other forces act on the links, affecting joint torque calculations and resulting in unrealistic movements. It doesn’t affect simulation stability, but it will produce physically inaccurate dynamics behavior.

3. physics:principalAxes (Principal Axes)

3-1: How are principalAxes related to diagonalInertia?
The principal axes define the orientation of the reference frame in which the inertia tensor is expressed. The physics:diagonalInertia values are the moments of inertia measured along these principal axes. Typically these axes are aligned with the link’s local frame, but they may not be. For example, if the <inertial> <origin> rpy in the URDF is defined as something other than (0, 0, 0) then this will apply a rotation on the principal axes relative to the link reference frame.

3-2: Do I need to extract this data from a URDF file or another source, or can it be computed inside Isaac Sim?
Isaac Sim has APIs to set the values in code like set_body_inertias, you can also define them in a URDF (or get a URDF that already has them defined) and Isaac Sim will load those values into the Articulation. On a quick search online, I found this urdf

3-3: If these axes are misaligned or incorrect, how does it affect joint movements and torque calculations?
Misaligned principal axes lead to incorrect inertia tensor representation in the simulation. This affects how torques and forces propagate through the kinematic chain, resulting in inaccurate joint accelerations and velocities.

Hope that helps!

1 Like

Thank you!!

Here you can find very useful documentation on Rigid Body dynamics:

Specifically instructions on using the mass/inertia authoring tools:

Also, under the good these GUIs are calling USD Physics API so another good source of information:

1 Like

This topic was automatically closed after 5 days. New replies are no longer allowed.

This topic was automatically opened after 4 days.