Skip to main content
Version: 8

Optimizing Robot Model Meshes

MoveIt Pro's collision checkers and simulation approaches work best with efficient meshes that do not have too much detail / too many polygons, due to the general performance limitations of modern computers.

There are two important approaches we recommend you take to optimize your robot models:

  • Decimation - removing triangles from a mesh to reduce its file size, collision checking overhead, and visualization rendering overhead
  • Decomposition - breaking down a mesh into several meshes so that the convex hull that our simulator's physics engine Mujoco makes does not fill in important voids. E.g. a 5 sided box (AKA a tote) would get turned into a cube if you didn't decompose it In this how to guide we cover how to do both approaches:

Mesh Decimation

You can reduce the number of faces (the resolution of the object) in your meshes' STL file using the decimate_mesh script included in your MoveIt Pro installation. For an example mesh named body.stl, simply run:

moveit_pro dev
decimate_mesh body.stl body_decimated.stl

Then after generating the file, find and replace body.stl with body_decimated.stl in all XML files.

Convex decomposition for MuJoCo meshes

Create .obj files for each rigid body

You can use blender to load mesh files, separate rigid bodies (if required), and export each rigid body to a .obj file. Notes:

  • Export with "Forward Axis" set to Y and "Up Axis" set to Z.
  • If you are exporting more than one rigid body from one blender file, make sure you select the desired object and check the "Selection Only" box when exporting.
  • Reference this blender tutorial on How to Split Objects in Blender if you need to separate rigid bodies from a single object.

Perform convex decomposition using the CoACD tool

Install the coacd tool with pip install coacd and run it on each rigid body .obj file. You should attempt to minimize the convex hulls used to decompose each rigid body to keep collision checking from being too computationally expensive. You can set the maximum number of hulls with the -c option. Start with a small number (5-10) and if the coacd fails with "Assertion p1 < costSize failed" or you see a warning like "Max concavity 1.7976931348623157e+308 exceeds the threshold 0.05 due to 8 convex hull limitation" then increase the number of hulls until it succeeds and the max concavity is not excessively large.

Example command: coacd -i rigid_body.obj -o rigid_body_decomp.obj -c 7

Save each convex hull as its own .stl file

The below separate_hulls.py script automates the process of loading the model and saving each separate object to its own .stl file.

Note: To run this script, you must first install blender and bpy on your host with sudo snap install blender --classic and pip install bpy.

Usage: blender --background --python separate_hulls.py -- rigid_body_decomp.obj ./rigid_body_geometries

# separate_hulls.py
import bpy
import os
import sys

# Get command line arguments
argv = sys.argv
argv = argv[argv.index("--") + 1 :] if "--" in argv else []

if len(argv) != 2:
print(
"Usage: blender --background --python script.py -- <input_obj_file> <output_directory>"
)
sys.exit(1)

obj_file = argv[0]
output_dir = argv[1]

# Clear existing scene
bpy.ops.wm.read_factory_settings(use_empty=True)

# Import OBJ file
bpy.ops.wm.obj_import(filepath=obj_file, forward_axis="Y", up_axis="Z")

# Create output directory if it doesn't exist
os.makedirs(output_dir, exist_ok=True)

# Get all mesh objects in the scene
mesh_objects = [obj for obj in bpy.context.scene.objects if obj.type == "MESH"]

print(f"Found {len(mesh_objects)} mesh objects")

# Create a new scene for exporting
temp_scene = bpy.data.scenes.new("ExportScene")

# Export each mesh as STL
for obj in mesh_objects:
# Clear the temporary scene
for o in temp_scene.objects:
temp_scene.collection.objects.unlink(o)

# Create a copy of the object for the temporary scene
obj_copy = obj.copy()
obj_copy.data = obj.data.copy()

# Link the object copy to the temporary scene
temp_scene.collection.objects.link(obj_copy)

# Create output filename based on object name
stl_filename = f"{obj.name}.stl"
stl_filepath = os.path.join(output_dir, stl_filename)

# Set the temporary scene as active
bpy.context.window.scene = temp_scene

# Export as STL
bpy.ops.wm.stl_export(filepath=stl_filepath, forward_axis="Y", up_axis="Z")

print(f"Exported: {stl_filename}")

# Clean up
bpy.data.scenes.remove(temp_scene)
print("Export complete!")

Form each rigid body in your mujoco mjcf file

For each rigid body, add all .stl files as collision geometries and the original .obj file as the visual geometry.

Example:

  <asset>
<mesh file="rigid_body.obj"/>
<mesh file="rigid_body_geometries/geometry_0.stl"/>
...
<mesh file="rigid_body_geometries/geometry_7.stl"/>
</asset>
...
<body name="rigid_body" pos="0 0 0" quat="1 0 0 0">
<geom quat="1 0 0 0" mesh="rigid_body" group="2" type="mesh" contype="0"/>
<geom quat="1 0 0 0" mesh="geometry_0" group="3" type="mesh"/>
...
<geom quat="1 0 0 0" mesh="geometry_7" group="3" type="mesh"/>
</body>
...