manipulation.make_drake_compatible_model
- manipulation.make_drake_compatible_model.MakeDrakeCompatibleModel(input_filename, output_filename, package_map=<pydrake.multibody.parsing.PackageMap object>, overwrite=False, remap_mujoco_geometry_groups={})
Converts a model file (currently .urdf or .xml)to be compatible with the Drake multibody parsers.
For all models:
Converts any .stl files to obj https://github.com/RobotLocomotion/drake/issues/19408
Converts any .dae files to obj https://github.com/RobotLocomotion/drake/issues/19109
Resizes meshes to work around any non-uniform scale attributes https://github.com/RobotLocomotion/drake/issues/22046
In addition, for MuJoCo .xml models:
Converts dynamic half-space collision geometries to (very) large boxes https://github.com/RobotLocomotion/drake/issues/19263
Truncates all rgba attributes to [0, 1]. https://github.com/RobotLocomotion/drake/issues/22445
Applies refpos and refquat attributes to the mesh .obj files. https://github.com/RobotLocomotion/drake/issues/22488
Applies materials specified in mujoco .xml directly to the mesh .obj files.
Any new files will be created alongside the original files (e.g. .obj files will be created next to the existing .stl files); all new files will get a descriptive suffix, and existing files will not be overwritten by default.
- Parameters:
input_filename (str) – The path to the input file to be converted.
output_filename (str) – The path where the converted file will be saved. Using the same string as input_filename is allowed.
package_map (PackageMap, optional) – The package map to use. Defaults to None.
overwrite (bool, optional) – Whether to overwrite existing files. Defaults to False.
remap_mujoco_geometry_groups (dict[int, int], optional) – Drake’s mujoco parser registers visual geometry for geometry groups < 3 (the mujoco default), which is a common, but not universal, convention. This argument allows you to remap (substituting the value for the key).
- Return type:
None