From e10e4641a4095fb218cba4574c2569c4a2091963 Mon Sep 17 00:00:00 2001 From: Shubham Saboo <72225064+FD-Shubham@users.noreply.github.com> Date: Sat, 9 May 2026 16:32:49 -0700 Subject: [PATCH 1/4] Add guide for creating custom robot models in MuJoCo This document provides a comprehensive guide on creating custom robot models for MuJoCo, covering the entire workflow from CAD design to simulation, including URDF and MJCF formats, physics parameter tuning, and testing strategies. --- wiki/simulation/mujoco-robot-modeling.md | 547 +++++++++++++++++++++++ 1 file changed, 547 insertions(+) create mode 100644 wiki/simulation/mujoco-robot-modeling.md diff --git a/wiki/simulation/mujoco-robot-modeling.md b/wiki/simulation/mujoco-robot-modeling.md new file mode 100644 index 00000000..40427b1b --- /dev/null +++ b/wiki/simulation/mujoco-robot-modeling.md @@ -0,0 +1,547 @@ +--- +date: 2026-05-09 +title: Creating Custom Robot Models for MuJoCo +--- +MuJoCo (Multi-Joint dynamics with Contact) is a high-performance physics engine widely used in robotics research, reinforcement learning, and biomechanics. Creating a custom robot model involves two complementary phases: designing the physical robot and encoding its geometry and dynamics into a simulation-ready model file. This article covers the full pipeline from physical design to a working MuJoCo simulation, including link geometry, joint layout, actuator selection, and authoring both URDF and MJCF model files. Readers will also find guidance on physics parameter tuning, mesh preparation, and testing strategies. Whether you are building a robot arm, legged system, or aerial manipulator, this article provides the foundational knowledge to get your robot simulating correctly in MuJoCo. + +## Workflow: CAD to Simulation + +The recommended pipeline for building a MuJoCo model from a physical design is: + +1. Design robot geometry in CAD (Fusion 360, SolidWorks, OnShape, or FreeCAD). +2. Export visual meshes at full resolution and simplified collision meshes (target < 500 triangles per link). +3. Export inertial properties per body: mass, center of mass, and inertia tensor. +4. Generate a URDF using an exporter such as `sw2urdf` or `onshape-to-robot`. +5. Validate the URDF with `check_urdf` or `urdfpy`. +6. Convert to MJCF using `mujoco.MjModel.from_xml_path()`. +7. Refine the MJCF: contacts, actuators, sensors, defaults, and keyframes. +8. Test in the MuJoCo viewer and adjust physics parameters iteratively. + +### Mesh Preparation + +Raw CAD meshes are typically too detailed for collision simulation. Use Open3D to generate simplified collision meshes: + +```python +import open3d as o3d + +mesh = o3d.io.read_triangle_mesh("forearm_visual.stl") +simplified = mesh.simplify_quadric_decimation(target_number_of_triangles=200) +o3d.io.write_triangle_mesh("forearm_collision.stl", simplified) +``` + +For concave parts, decompose into convex hulls using V-HACD before importing into MuJoCo. MuJoCo processes convex-vs-convex contacts significantly faster than concave meshes, and convex decomposition avoids internal contact artifacts. + +```bash +pip install pyvhacd +python -c " +import pyvhacd +hulls = pyvhacd.compute('concave_part.stl', max_hulls=16) +for i, h in enumerate(hulls): h.export(f'hull_{i:02d}.stl') +" +``` + +### Automated URDF Generation with onshape-to-robot + +For OnShape-based designs, the `onshape-to-robot` tool automates URDF and mesh export: + +```bash +pip install onshape-to-robot + +# Place a config.json with your OnShape document ID and API credentials, +# then run from the project directory: +onshape-to-robot . + +# Convert the resulting URDF to MJCF: +python -c " +import mujoco +m = mujoco.MjModel.from_xml_path('robot.urdf') +mujoco.mj_saveModel(m, 'robot.xml') +" +``` + +## Physical Model Design + +Before writing a single line of XML, you must define the robot's physical architecture. Decisions made here directly affect simulation accuracy, computational cost, and control complexity. + +MuJoCo represents robots as structured XML files — either URDF (Unified Robot Description Format, the ROS-standard interchange format) or MJCF (MuJoCo's native format). Both encode the same core information: the hierarchy of rigid bodies, how they are connected by joints, their geometric shapes, and how they are actuated. Before authoring either format, you need to nail down the physical properties described below — every field in those XML files corresponds directly to a concrete design decision about your robot. + +### Kinematic Structure + +The kinematic chain is the ordered sequence of rigid bodies (links) connected by joints. Three common topologies appear in practice: + +- **Serial chains** — one parent per link; used in robot arms and leg segments. +- **Parallel mechanisms** — closed-loop structures such as delta robots and Stewart platforms. +- **Trees** — branching limbs used in humanoids and quadrupeds. + +Start with a Degrees of Freedom (DoF) analysis. Count the independent joints needed for your task. Each revolute or prismatic joint costs one DoF and one control signal. + +### Link Geometry + +Each link must be described by a collision geometry and optionally a separate visual geometry. MuJoCo supports several primitive shapes natively: + +| Shape | MJCF Tag | Common Use Case | +|-------|----------|-----------------| +| Box | `` | Chassis, base plates, cuboid links | +| Sphere | `` | Ball joints, feet, sensors | +| Capsule | `` | Limbs, fingers | +| Cylinder | `` | Wheels, rollers | +| Ellipsoid | `` | Organic approximations | +| Mesh | `` | CAD-exported STL/OBJ geometry | + +> Prefer capsules over cylinders for link geometry. Capsules are computationally cheaper in contact detection and avoid edge-contact singularities that can destabilize the solver. + +### Joint Types + +MuJoCo uses different joint type names than URDF. The mapping is: + +| URDF Type | MJCF Type | Description | +|-----------|-----------|-------------| +| `revolute` | `hinge` | Rotation about a fixed axis | +| `prismatic` | `slide` | Translation along an axis | +| `floating` | `free` | 6-DoF floating base | +| *(not supported)* | `ball` | 3-DoF spherical joint | +| `fixed` | *(merge bodies)* | Rigid attachment, no DoF | + +### Mass and Inertia + +Accurate inertial parameters are critical for realistic dynamics. For each link you need the mass (kg), center of mass (CoM) position relative to the link frame, and the inertia tensor expressed as six unique values: `ixx`, `iyy`, `izz`, `ixy`, `ixz`, `iyz`. + +For uniform primitive shapes, inertia can be computed analytically. For example, for a solid cylinder of mass `m`, radius `r`, and height `h`: + +```python +ixx = iyy = m * (3*r**2 + h**2) / 12 +izz = m * r**2 / 2 +ixy = ixz = iyz = 0.0 +``` + +For mesh-based links, use MeshLab, SolidWorks, or Fusion 360 to export inertial properties from your CAD model. As a starting point, MuJoCo can auto-compute inertia from geometry by setting `inertiafromgeom="true"` in the `` tag. + +> The inertia tensor must be positive-definite. Verify these triangle inequalities for every link: `ixx + iyy > izz`, `ixx + izz > iyy`, `iyy + izz > ixx`. Violating them will produce `nan` values or simulation instability. + +### Actuator Selection + +MuJoCo provides several actuator models. The right choice depends on your hardware: + +| Actuator | Best For | +|----------|----------| +| `motor` | DC motors and linear actuators (pure torque/force output) | +| `position` | Hobby servos and Dynamixel (PD position servo) | +| `velocity` | Velocity-controlled motors | +| `general` | Maximum flexibility with custom gain, bias, and dynamics chain | +| `cylinder` | Pneumatic or hydraulic actuators | +| `muscle` | Hill-type muscle model for biomechanics | + +## Creating the URDF Model + +URDF (Unified Robot Description Format) is an XML format originally developed for ROS. It describes a robot as a tree of links and joints and can be converted to MJCF using MuJoCo's built-in converter. URDF is the recommended starting format when ROS compatibility is needed. + +### URDF File Structure + +```xml + + + + + ... + ... + + + + + + + + + + +``` + +### Defining a Link + +Each link has three sub-elements: ``, ``, and ``. All three are optional but recommended for simulation: + +```xml + + + + + + + + + + + + + + + + + + + + + + + + + + + +``` + +### Defining a Joint + +```xml + + + + + + + + + + + + + + + + + + + + + + + + +``` + +### Validating Your URDF + +Always validate the URDF before converting to MJCF: + +```bash +# ROS-based validation +check_urdf my_robot.urdf + +# Python: parse with urdfpy (no ROS required) +pip install urdfpy +python -c "from urdfpy import URDF; r = URDF.load('my_robot.urdf'); print(r.link_names)" + +# Standalone parser +pip install urdf-parser-py +python -c " +from urdf_parser_py.urdf import URDF +robot = URDF.from_xml_file('my_robot.urdf') +print('Links:', [l.name for l in robot.links]) +print('Joints:', [j.name for j in robot.joints]) +" +``` + +## MJCF: Native MuJoCo Format + +MJCF is the native description language of MuJoCo. It offers significantly richer features than URDF: tendons, actuator dynamics, contact parameters, sensors, keyframes, and more. You can author MJCF directly or convert from URDF and refine. + +### Converting URDF to MJCF + +```python +import mujoco + +# Load from URDF and save as MJCF +model = mujoco.MjModel.from_xml_path('my_robot.urdf') +mujoco.mj_saveModel(model, 'my_robot.xml') +``` + +> The URDF-to-MJCF conversion may produce suboptimal contact and collision parameters. Always review the converted MJCF manually — especially the ``, `