Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Callback based API for Implementing Custom Moment of Inertia Calculators for Meshes #1304

Merged
merged 142 commits into from
Aug 30, 2023

Conversation

jasmeet0915
Copy link
Contributor

@jasmeet0915 jasmeet0915 commented Jul 28, 2023

🎉 New feature

Based on this proposal.

Note: This PR would require merging #1298 and #1299

Summary

  • Added functions to register custom calculator and get custom calculator in ParserConfig.
  • Added an InterfaceMoiCalculator class that can be used to send appropriate data to the calculator from sdformat.
  • Added a <moi_calculator_params> tag that can be used to access custom calculator params from the SDF by using tags with namespaces. (See this for reference)
  • Added MassMatrix() function to sdf::Mesh class and updated the Collision::MassMatrix() function to pass the parser config as well as sdf::ElementPtr to <moi_calculator_params> tag.

Demo & Usage Example

Demo 1: 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.

Note: The voxel_size inertia param given in the snippet below is just for showing how the <auto_inertia_params> element could be used. This is not actually used by the calculator since we are not using a voxelization-based calculator.

SDF snippet for the duck mesh with auto inertial
<?xml version="1.0" ?>
<sdf version="1.6">
<model name="duck">
  <link name="duck_link">
    <pose>0 0 0 0 0 0</pose>
    <inertial auto="true" />
    <collision name="duck_collision">
    	<pose>0 0 0 0 0 0</pose>
      <density>111.8</density>
      <auto_inertia_params>
        <gz:voxel_size>0.01</gz:voxel_size>
      </auto_inertia_params>
      <geometry>
        <mesh>
          <uri>meshes/duck_collider.dae</uri>
        </mesh>
      </geometry>
    </collision>
    <visual name="duck_visual">
      <pose>0 0 0 0 0 0</pose>
      <geometry>
        <mesh>
          <uri>meshes/duck.dae</uri>
        </mesh>
      </geometry>
    </visual>
  </link>
  <static>true</static>
</model>
</sdf>

duck_mesh_inertia

Demo 2: This demo shows 2 cylinders: One using a Collada cylinder mesh (right) and the other made using the <cylinder> geometry from SDF (left).

Both use <inertial auto="true" /> and we can see that the inertia values for both come up to be almost the same (within 0.005 tolerance). The mesh cylinder uses the mesh inertia calculator added to gz-sim and is used with libsdformat using the callback-based API.

SDF snippet for the mesh cylinder
  <model name="cylinder_dae">
    <pose>4 4 1 0 0 0</pose>
    <link name="cylinder_dae">
      <pose>0 0 0 0 0 0</pose>
      <inertial auto="false" />
      <collision name="cylinder_collision">
        <density>1240.0</density>
        <auto_inertia_params>
          <gz:voxel_size>0.01</gz:voxel_size>
        </auto_inertia_params>
        <geometry>
          <mesh>
            <uri>cylinder_dae/meshes/cylinder.dae</uri>
          </mesh>
        </geometry>
      </collision>
      <visual name="cylinder_visual">
        <pose>0 0 0 0 0 0</pose>
        <geometry>
          <mesh>
            <uri>cylinder_dae/meshes/cylinder.dae</uri>
          </mesh>
        </geometry>
      </visual>
    </link>
    <static>true</static>
  </model>

mesh_and_sdf_cylinder

TODO:

  • Update the nomenclature (interface class name, custom params tag name) to something more appropriate.
    • Rename <moi_calculator_params> to <auto_inertia_params>.
  • Rename Mesh::MassMatrix() to Mesh::CalculateInertial() and change the return type to optional Inertial.
  • Make mesh optional in CustomInertiaCalcProperties class as it might be extended in future for other types of shapes.
  • Add //link/inertial/auto_inertia_params element in spec
  • Update the SDFormat Proposal with an explanation of the API and add a basic example of using the API.
  • Add Tests
  • Add the functions to Python API

Checklist

  • Signed all commits for DCO
  • Added tests
  • Added example and/or tutorial
  • Updated documentation (as needed)
  • Updated migration guide (as needed)
  • Consider updating Python bindings (if the library has them)
  • codecheck passed (See contributing)
  • All tests passed (See test coverage)
  • While waiting for a review on your PR, please help review another open pull request to support the maintainers

Note to maintainers: Remember to use Squash-Merge and edit the commit message to match the pull request summary while retaining Signed-off-by messages.

Signed-off-by: Jasmeet Singh <[email protected]>
Signed-off-by: Jasmeet Singh <[email protected]>
Signed-off-by: Jasmeet Singh <[email protected]>
Signed-off-by: Jasmeet Singh <[email protected]>
Signed-off-by: Jasmeet Singh <[email protected]>
@azeey azeey added the beta Targeting beta release of upcoming collection label Jul 31, 2023
- Updated all functions returning Errors object to take errors object as an output param
- Updated function params to take errors as a first params

Signed-off-by: Jasmeet Singh <[email protected]>
Signed-off-by: Jasmeet Singh <[email protected]>
@azeey azeey added the 🎵 harmonic Gazebo Harmonic label Aug 28, 2023
@azeey azeey changed the base branch from main to sdf14 August 28, 2023 23:08
Copy link
Collaborator

@azeey azeey left a comment

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Looks great! Just a couple of comments

include/sdf/Mesh.hh Outdated Show resolved Hide resolved
src/Collision_TEST.cc Show resolved Hide resolved
include/sdf/Mesh.hh Show resolved Hide resolved
@azeey azeey dismissed ahcorde’s stale review August 30, 2023 19:48

Feedback addressed

@azeey azeey merged commit 017e1f6 into gazebosim:sdf14 Aug 30, 2023
5 checks passed
Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment
Labels
beta Targeting beta release of upcoming collection 🎵 harmonic Gazebo Harmonic
Projects
Archived in project
Development

Successfully merging this pull request may close these issues.

3 participants