pydrake.multibody.fix_inertia
Utility for fixing invalid inertia data in URDF or SDFormat files, by writing a complete, updated file.
Inertia properties for links are inferred from geometry. Only the file supplied as an input is updated; any included or referred-to files are left untouched. The inferred geometry for each body is determined by the first role which has geometry defined. The roles are visited in the order specified by –geom_inertia_role_order, whose default order is “proximity illustration perception”.
The output file should differ from the input file only by the contents of <inertial> tags. It is possible that some comments may be lost within those tags.
Running:
From a Drake source build, run this as:
bazel run //tools:fix_inertia -- --helpFrom a Drake binary release (including pip releases), run this as:
python3 -m pydrake.multibody.fix_inertia --helpRun with output to the standard output:
bazel run //tools:fix_inertia -- path/to/some_model.urdfRun with output to a separate file:
bazel run //tools:fix_inertia -- \ path/to/some_model.urdf output.urdfRun with output overwriting the input file (sometimes convenient within a source code control workspace):
bazel run //tools:fix_inertia -- --in_place path/to/some_model.urdfThis program respects the ROS_PACKAGE_PATH; if your model uses external resources then you will need to set that environment variable.
Using the results:
The output file will be well-formed XML and parse cleanly in Drake, but it may not be exactly suited to the purpose at hand. Be sure to examine the model file differences, and use model_visualizer to examine the resulting inertial ellipsoids.
See model_visualizer documentation here: https://drake.mit.edu/pydrake/pydrake.visualization.model_visualizer.html
Once the effect of the changes is clear, either use the new output file as-is, or merge in the desired changes using any text file merging tool.