inertiafromgeom not working as expected

Discussion in 'Modeling' started by Ethan Brooks, Sep 20, 2017.

  1. I have the following simple model:

    Code:
    <!--bodies.xml-->
    
    <mujoco model="world">
      <compiler angle="radian" inertiafromgeom="true"/>
      <worldbody>
        <body pos="0 0 0" name="outer_body">
          <joint axis="1 0 0" name="slide_x" type="slide"/>
          <inertial pos="0 0 0" mass="1" diaginertia="1 1 1" />
          <body name="inner_body" pos="0 0 0">
            <inertial pos="0 0 0" mass="1" diaginertia="1 1 1" />
            <geom type="cylinder" size="1 1"/>
          </body>
        </body>
      </worldbody>
    </mujoco>
    
    According to the documentation for inertiafromgeom:

    This led me to believe that the 'inertial' element for outer_body is redundant and should be inferred from inner_body. However if I comment out the outer inertial element and run the simulate script on my model I get the following error:
    Code:
    ❯ LD_LIBRARY_PATH=. ./simulate bodies.xml
    MuJoCo Pro library version 1.50
    
    
    
    
    Error: mass and inertia of moving bodies must be positive
    Object name = base_footprint, id = 1, line = 4, column = 5
    
    My interpretation of this error is that the compiler is failing to infer the mass and inertia of outer_body from inner_body. What am I not understanding? Thank you.
     
  2. Emo Todorov

    Emo Todorov Administrator Staff Member

    This option makes the compiler infer the body mass from geoms attached to the body, not from child bodies. If there are no geoms attached to a given body, the automatic inference mechanism does not do anything. So in your case, since there are no geoms attached to the parent body, it does not overwrite the explicit inertial definition.
     
  3. Is there any way to get mass/inertia from child bodies? Or should I just do the math myself and hard code it? Obviously mass sums. Is the same true for diaginertia? I am honestly not entirely sure what a "diagonal inertia matrix" is.
     
  4. Emo Todorov

    Emo Todorov Administrator Staff Member

    You don't want to do this. The mass and inertia of each body defined in the model are interpreted as belonging to that body, not to its children. At runtime, the simulator sums up all the masses and intertias along the kinematic sub-tree rooted at each body, and uses these quantities internally to compute the dynamics. So if you attempted to do it yourself, you would end up simulating a model with much larger mass/inertia than intended.

    To answer your math question, masses sum up in the obvious way, while inertias need to be transformed. Look up "composite rigid body algorithm" for details.
     
  5. I see. Thank you for the clarification. This is very helpful.