Blender Workflow for Cleaning CAD Meshes for ROS 2 / Gazebo¶
This guide explains how to fix common mesh problems when importing CAD models, for example from Onshape, into Blender before using them in ROS 2 and Gazebo.
Typical problems this workflow fixes:
- Missing faces in Gazebo
- Flipped normals
- Extremely large mesh sizes
- Broken CAD mesh geometry
The goal is to produce a clean visual mesh (.dae or .obj) and a simple collision mesh (.stl) for use in URDF.
1. Open the mesh in Blender¶
- Start Blender.
- Go to
File -> Import. -
Import your mesh file:
-
Collada (
.dae) - STL (
.stl) - OBJ (
.obj)
If importing from CAD:
- OBJ is usually the most stable format.
2. Select the mesh object¶
Look at the Outliner in the top-right panel.
Select the object with the triangle icon. That means it is a mesh.
Example:
Collection
└ robot_part
3. Enter Edit Mode¶
With the mesh selected, press:
Tab
Or use:
Object Mode -> Edit Mode
Now you should see vertices, edges, and faces.
4. Select all geometry¶
Press:
A
Everything should now be selected.
5. Remove duplicate vertices¶
CAD exports often contain duplicated vertices.
Press:
M
Then choose:
By Distance
Blender will merge overlapping vertices.
Example message:
Removed 12000 vertices
6. Fix face normals¶
Incorrect normals cause missing faces in Gazebo.
Press:
Shift + N
This recalculates all normals to point outward.
7. Check face orientation¶
Enable the overlay:
Viewport Overlays -> Face Orientation
Colors mean:
- Blue -> Correct orientation
- Red -> Flipped faces
Goal:
Outer surfaces should be BLUE
8. Flip incorrect faces if necessary¶
If some faces remain red:
- Select those faces.
- Press:
Alt + N
- Choose:
Flip
9. Triangulate the mesh¶
Gazebo works best with triangular faces.
Press:
A
Ctrl + T
Now all faces are triangles.
10. Reduce mesh size¶
CAD models often contain millions of polygons.
- Go to the Modifiers panel.
- Click:
Add Modifier -> Decimate
Recommended settings:
Ratio: 0.2 - 0.4
Apply the modifier.
Example result:
1,200,000 faces -> 40,000 faces
11. Apply object transforms¶
Return to Object Mode:
Tab
Then press:
Ctrl + A
Choose:
Rotation & Scale
This prevents scaling issues in Gazebo.
12. Export the visual mesh¶
Export the cleaned mesh:
File -> Export -> Collada (.dae)
Recommended options:
- Apply Modifiers
- Selected Objects
- Triangulate
Example file:
robot_visual.dae
13. Create a collision mesh¶
Duplicate the object:
Shift + D
Rename it:
robot_collision
Apply heavy simplification:
Decimate Ratio = 0.05
Export as:
File -> Export -> STL
Example file:
robot_collision.stl
14. Use in URDF¶
Example URDF link:
<link name="base_link">
<visual>
<geometry>
<mesh filename="package://robot_description/meshes/robot_visual.dae"/>
</geometry>
</visual>
<collision>
<geometry>
<mesh filename="package://robot_description/meshes/robot_collision.stl"/>
</geometry>
</collision>
</link>
Recommended mesh sizes¶
| Mesh Type | Recommended Faces |
|---|---|
| Visual | < 50k |
| Collision | < 5k |
Best practices for robot simulation¶
Avoid including small CAD details.
Remove:
- Screws
- Threads
- Fillets
- Decorative logos
These increase simulation cost without improving physics.
Typical robotics pipeline¶
CAD (Onshape / SolidWorks)
v
Export STEP / OBJ
v
Blender cleanup
v
Visual mesh (.dae / .obj)
Collision mesh (.stl)
v
URDF
v
ROS 2 + Gazebo
Summary¶
This workflow helps robot meshes:
- Render correctly in Gazebo
- Load faster
- Simulate more efficiently
- Avoid flipped normals and missing faces