Inertia values not aligned to local reference frame
Closed this issue · 7 comments
I created a simple example to showcase the problem. It consists of a box and a bracket with the latter being connected to the box via a revolute mate (see attached screenshot). The exporter then uses the coordinate frame defined by the revolute mate as the local coordinate frame for the bracket (shown as the RGB coordinate frame at the center of the hole). So what we expect is that all 6 inertia values as well as the 3 center of gravity coordinates are described in this frame.
When clicking on the bracket in the assembly we get the following output:
Center of gravity (xyz): -15.054 mm, 18.702 mm,13.454 mm (origin was placed randomly hence the weird values)
Inertia tensor diagonal: Ixx=313692.22gmm^2, Iyy=320080.54gmm^2, Izz=465064.448gmm^2
So these are the value described in the assembly frame (see frame at the top right corner). Now, as described above, the URDF defines a local frame for the bracket link based on the revolute mate coordinate system which by default uses the z-axis as the axis of revolution. So what we expect is that both the center of gravity as well as the inertia tensor entries get transformed to this local coordinate system. However what we find in the URDF file is:
Center of gravity (xyz): 0, 31.91mm, 25mm (check, correctly aligned with revolute mate coordinate sytem)
Inertia tensor diagonal: Ixx=313692.22gmm^2, Iyy=320080.54gmm^2, Izz=465064.448gmm^2
While the center of gravity got correctly transformed to the local coordinate frame defined by the revolute mate, the inertia tensor did not get aligned with the coordinate axis of this local frame. The inertia tensor is still given in the assembly frame.
What we are expecting to get is (check transformation from assembly frame to revolute mate frame):
Inertia tensor diagonal: Ixx=465064.448gmm^2, Iyy=313692.22gmm^2, Izz=320080.54gmm^2
Am I misunderstanding something or is this an issue?
Hello,
Thanks for giving feedback
Just to be sure I understands correctly, here is an example:
The "grey" part is the one interresting me here. It is connected to the blue one with a revolute DOF. We expect its inertia to be smaller along the axis where the cylinder lies, and equal along the other axises. Which is what happens if I click on the mass button:
If I do export this to URDF, I also get:
<inertia ixx="2.59962e-05" ixy="-6.35538e-22" ixz="0" iyy="2.59962e-05" iyz="0" izz="1.10535e-05" />
Now, if I attach my object differently in the assembly, for example like that:
The inertia seen in assembly is now smaller along x axis:
However, when exporting URDF, the inertia is still:
<inertia ixx="2.59962e-05" ixy="6.35538e-22" ixz="0" iyy="2.59962e-05" iyz="0" izz="1.10535e-05" />
Which is what is expected, because it is expressed in the link frame which itself is different (in that case, the rpy
value differs in the joint
)
(Note: To do this test you need the links to be properly ordered, (in my case the blue should be the "root" of the URDF and the grey its child), else there will be no DOF between the inspected part and its parent and thus the inertial will be indeed aligned with the assembly frame)
Is my test inconsistent with yours ?
Can you share URDFs and test assembly ?
Thanks for setting up the test case and the verification. I gave you access to the Onshape assembly. The one to be exported is "Assembly_Main". The URDF output is attached below as a txt-file.
robot.txt
Can you share the document so that I can edit or copy it? Else I can't run an import on it
I tried to replicate your process by doing the same parts but I don't get the same result.
When exporting it I get:
<inertia ixx="0.000325101" ixy="0" ixz="0" iyy="0.000485552" iyz="0" izz="0.000330938" />
Where those are the expected values because they are expressed in the DOF frame
I just changed your rights for the Onshape file I sent to you through your e-mail so that you can edit it too. Kindly let me know if it works now.
Hello, thanks for sharing the document with me and allowing me to reproduce the problem.
I think I found the issue, the formula changing the inertia tensor basis was in the wrong way around
Changing the inertia tensor
In our case, since in addLinkDynamics
, the matrix received changes coordinates from the part to the link frame (because we apply it to change the COM frame directly), and inertia is expressed in the part frame, it should be indeed:
inertia = R*I*R.T
Someday, I need to refactor the code so that the frames where things are expressed and the transformation matrices are made more explicit.
I fixed this and published 0.3.16
, can you confirm that it is OK for you?
[1] For reference, from Modern Robotics chapter 8:
What a beauty, it works correctly now. inertia = R*I*R.T
is indeed the correct equation. Thanks for your effort and your time!
Thanks for reporting!