GSoC 2023: Automatically Computing Moments of Inertia for SDFormat Links
Organization: Open Robotics
Mentors: Addisu Taddese (@azeey ), Dharini Dutia (@quarkytale)
Student: Jasmeet Singh (Github, LinkedIn, Website)
Link to GSoC Project: Google Summer of Code
Hello Everyone,
This summer I was selected to work on gz-sim
and sdformat
as part of the Google Summer of Code Program 2023. My primary focus was the development of a feature enabling the automatic computation of Moments of Inertia for SDFormat Links in simulation.
Throughout the program, I worked closely with my esteemed mentors, Addisu Taddese and Dharini Dutia, to make substantial contributions to the gz-sim
and sdformat
libraries. I am grateful to Open Robotics for providing me with this opportunity and I’m truly appreciative of the invaluable guidance and support provided by my mentors. This GSoC journey has been an immensely enriching learning experience!
Overview
Setting physically plausible values for inertial parameters is crucial for an accurate simulation. However, these parameters are often complex to comprehend and visualize, and users may tend to enter wrong values leading to incorrect simulation.
Therefore, during the GSoC program this year, we have worked on implementing a feature for libsdformat that allows automatic calculation of Moments of Inertia for SDFormat links.
Motivation Behind the Project
Currently, there are 2 major workflows used by the users to obtain the correct inertial parameters of their models:
-
Using CAD software like Fusion360 or Solidworks. Many users design their robot models using such CAD software which provides plugins that automatically generate the URDF/SDF for their model. Such plugins handle the calculation of the inertial parameters. For example, Fusion360 provides the Fusion2URDF plugin which automatically generates a URDF with all the inertial parameters.
-
Another way is to use 3rd-party Mesh Processing Software like Meshlab. Such software takes the mesh file as an input and provides the inertial parameters as an output which can then be copied and pasted into the URDF/SDF file.
Both of these ways create a dependency on external software and might be complicated for beginners. In case the user doesn’t provide any inertial values, a default Mass Matrix is used with mass = 1.0
and Diagonal Elements = (1, 1, 1)
which might not be best suited for all kinds of models. Native support for automatic inertia calculations directly into libsdformat
would work as a better alternative to using the default values and facilitate the effortless generation of accurate simulations.
Project Summary
This project enables automatic calculation for the Moments of Inertia, Mass, and Inertial Pose (Center of Mass pose) of a link described using SDFormat. The following Geometry types are currently supported:
- Box
- Capsule
- Cylinder
- Ellipsoid
- Sphere
- Mesh
A new auto
attribute for the <inertial>
tag was introduced through the project which can be set to true or false (The value is false by default) to enable or disable the automatic calculations for a link respectively:
<inertial auto="true" />
In case, auto
is set to true, the constituent collision geometries of the link are considered for the calculations. A newly introduced <density>
tag can be used to specify the mass density value of the collision in kg/m^3. The density of water (1000 kg/m^3) is utilized as the default value:
<collision name="collision">
<density>2710.0</density>
<geometry>
<cylinder>
<radius>0.5</radius>
<length>1</length>
</cylinder>
</geometry>
</collision>
The gif above shows the visualization of automatically computed inertia for a cylinder.
In case of multiple collision geometries in a link, a user is free to provide different density values for each and their individual inertia values would be aggregated to calculate the final inertia of the link. However, if there are no collisions present, an ELEMENT_MISSING
error would be thrown.
It is important to note here that if auto
is set to true
and the user has still provided values through the <mass>
, <pose>
and <inertia>
tags, they would be overwritten by the automatically computed values.
Note: SDF Spec version 1.11 or greater is required to utilize the new tags and attributes
of this feature.
Existing MassMatrix()
functions from the gz-math
library were used for the inertia calculation of basic shapes (box, capsule, cylinder, ellipsoid, and sphere) and this functionality was integrated within libsdformat
itself.
On the other hand, a different approach was taken for the mesh geometry type since inertia calculations for 3D meshes can be complex and the preference for calculation method could vary for different users. A callback-based API was created that allows users to register their own custom inertia calculators. An integration-based numerical method was implemented in gz-sim
for computing the inertial properties of 3D meshes through the callback. This method uses Gauss’s Theorem and Greene’s Theorem of integration to convert volume integrals to surface integrals (Gauss’s Theorem) and then surface integrals to line integrals (Greene’s Theorem). More details about this method can found here.
Demos
Let’s have a look at some demos that would help you grasp a better understanding of the outcomes of this feature.
Default vs. Automatically Computed Inertia Values
This demo shows 2 cylinders: one with default inertial values (right, green) and the other with automatic inertia calculations enabled (left, yellow).
In this demo, we can see the difference between the inertia of both cylinders through the visualization enabled. The difference shows that the calculated values are more realistic for cylinders as compared to the default ones.
Automatic Inertia Calculation for Links with Multiple Collisions
This demo shows a model with a link having 2 collisions: a cube with a cylinder on top of it.
Default values won’t be a good choice in this scenario as we have seen in the previous demo and manually calculating the values would not be straightforward. Therefore, using the automatic inertia calculations we can easily get realistic inertial values for the compound shape.
Pendulum Example World & Effect of Density
This example world has two structurally identical models. The pendulum link of both models contains 3 cylindrical collision geometries: One on the top which forms the joint, One in a longer cylinder in the middle, and One at the end which forms the bob of the pendulum. Even, though they are identical, the center of mass for both are different as they use different density values for the different cylinder collisions.
On one hand, the upper joint collision of the pendulum on the left has the highest density which causes the center of mass to shift closer to the axis while on the other hand, the bob collision of the pendulum on the right has the highest density which causes the center of mass to shift towards the end of the pendulum. This difference in mass distribution about the axis of rotation results in a difference in the moment of inertia of the 2 setups and hence different angular velocities.
Mesh Inertia Calculation Example with Rubber Ducky 3D Mesh
This demo shows the automatic inertia calculation feature on a rubber ducky model which is a non-convex mesh. On the left, we have the rubber ducky mesh with automatic calculations enabled and on the right, the mesh uses the default values.
Note: The inertial values are due to the scale of the mesh. You can see the banana for scale in between the 2 ducks. A density value for the duck was used which was calculated by using the mass and volume data of the duck found online.
Mesh Inertia Calculation with Rolling Shapes Demo
In this demo, the rightmost shape is a hollow cylinder (yellow) that was made using a collada mesh. This model was uploaded to and loaded from fuel. Apart from this, we can see there is a solid cylinder, a solid sphere, and a solid capsule. All of these are made using the <geometry>
tag and have automatic inertia calculations enabled.
Here, the moments of inertia for the hollow cylinder (which is convex mesh shape) are calculated and from the simulation, we can see that it reaches the bottom of the incline last. This is physically accurate as the mass distribution for the hollow cylinder is concentrated at a distance from the axis of rotation (which passes through the center of mass in this case).
Some Key Points Regarding Mesh Inertia Calculator
Here are some key points to consider when using automatic inertia calculation with 3D Meshes:
- Water-tight triangle meshes are required for the Mesh Inertia Calculator.
- Currently, the mesh inertia is calculated about the mesh origin. Since the link inertia value needs to be about the Center of Mass, the mesh origin needs to be set at the Center of Mass (Centroid).
- Since the vertex data is used for inertia calculations, a high vertex count would be needed for near-ideal values. However, it is recommended to use basic shapes with the geometry tag (Box, Capsule, Cylinder, Ellipsoid, and Sphere) as collision geometries to reduce the load of calculations. For eg: in this integration test a cylinder mesh with 4096 vertices was used which resulted in inertia values withing a 0.005 tolerance of ideal.
List of PRs
Future Plans
During the project, most of our goals were satisfied and the desired results were obtained. However, there are some things that need to be developed for a better workflow:
- Link level
<density>
and<auto_inertial_params>
tags were added but their functionality was not implemented. It would be good to provide users with the ability to provide density values for the whole link instead of copying the same values for each collision. - Currently, the mesh origin needs to be set at the geometric center (centroid) for correct inertia values. Since there are many cases where the mesh origin might be set elsewhere, it would be good to have a functionality that can transform the computed inertia tensor to the mesh centroid in such a case.
About Me
I am a recent Electronics and Communications Engineering graduate hailing from India. I have a strong passion for robotics and aspire to become a Roboticist. My primary areas of interest lie in robot perception, robotic simulations, and mechatronics. Over the course of two years, I have gained valuable experience in robotics development with ROS, through participating in various competitions, personal projects, and internships.
Additionally, I am also the co-founder of a Robotics Research and Development Society called A.T.O.M Robotics Lab at my college. Apart from robotics, I possess a keen enthusiasm for Embedded Systems, PCB design, and 3D Printing. I tend to frequently combine these interests to build hobby projects and eagerly share with the community. In my free time, I enjoy engaging in sketching, painting, and reading sci-fi novels.