The link's inertial properties do not match the ones in URDF

Hi,

I wrote a standalone Python script to import a robot from URDDF. In general, it works well. However, on closer inspection, I realized if I query robot link inertia properties from the ArticulationView, it only partially matches the ones in the URDF file. There are two sources of differences.

(1) when accessing the body CoMs through ArticulationView::get_body_coms(), the CoM frame rotations are different from URDF.
(2) when accessing the body CoMs through ArticulationView::get_body_inertias(), the Inertia matrices are different.

I realized that the frame orientation defines the principle access. Meaning R^T I R, results in a diagonal matrix.

However, what still needs to be clarified is why the inertia matrices do not match the ones from URDF. Below are the values I generated for the Farbka robot based on the URDF in IsaacSim (panda_arm_hand.urdf):

[From ArticulationView]
body_name: panda_link0
CoM Position: [0. 0. 0.]
CoM Orientation rpy: [ 0.02876538 -0.52236655 0.02217443]
CoM Orientation: [ 0.965967 0.00699627 -0.25833535 0.01103094]
Mass: 2.8142027854919434
Inertia:
[[ 0.01736686 -0.00014481 0.0033251 ]
[-0.00014481 0.02212693 0.00015037]
[ 0.0033251 0.00015037 0.01350513]]

While the actual values should be

[URDF]
link name=“panda_link0”


<inertial>
  <origin rpy="0 0 0" xyz="0 0 0" />
  <mass value="2.8142028896" />
  <inertia ixx="0.0129886979" ixy="0.0" ixz="0.0" iyy="0.0165355284" iyz="0" izz="0.0203311636"/>
</inertial>

Thanks!

[Update]:

To enable loading the inertia tensor, I should have set ImportConfig.import_inertia_tensor to True.

However, it is not still fully working. The loaded URDF still ignores the sub-element origin rpy in the inertial element. Also, the off-diagonal element of the inertia tensor is set to zero, although they are not. Check below:

<inertial>
  <origin rpy="0.00045259 0.01061577 0.02062053" xyz="0.00192414 0.00131838 0.00063246"/>
  <mass value="30.689437866210938"/>
  <inertia ixx="0.18470187485218048" ixy="-0.0010424249339848757" ixz="0.016710679978132248" iyy="1.7260644435882568" iyz="-0.0006984919309616089" izz="1.7602781057357788"/>
</inertial>

Loaded ones are:

<inertial>
  <origin rpy="0.0, 0.0, 0.0" xyz="0.0019241400295868516, 0.0013183800037950277, 0.0006324599962681532"/>
  <mass value="30.689437866210938"/>
  <inertia ixx="0.18470187485218048" ixy="0.0" ixz="0.0" iyy="1.7260645627975464" iyz="0.0" izz="1.7602781057357788"/>
</inertial>

@ffarshidian You are finding known issues with importing intertia tensors into Isaac Sim from URDF which we are looking to fix as soon as possible.

Any updates on this issue? I tried to use URDF and MJCF to import inertia matrix into USD, but the inertia matrix read using ArticulationView::get_body_inertias() is still incorrect.
I also tried to manually decomposite the inertia matrix into principal axis and diagonal matrix, and modified the values in Isaac Sim UI, but the output of ArticulationView::get_body_inertias() still does not match the one with it in URDF.

@AlanSunHR - As mentioned in the earlier message, it is being fixed currently and will be fixed in the future release.

This topic was automatically closed 14 days after the last reply. New replies are no longer allowed.