Skip to main content
Version: 6

Creating a MuJoCo Config from a URDF

Tutorial Level: Intermediate

To create a Mujoco world for your MoveIt Pro config to run in simulation, you will need to create a MuJoCo Modeling XML File (MJCF) that defines the robot and the environment. The easiest way to create this file is by starting with your existing URDF file.

This tutorial will walk through the URDF to MJCF migration process.

Configuration package references:

MJCF references:

Steps

Prerequisites

  • MoveIt Pro >= 6.0.0
  • MuJoCo >= 3.1.6
    • Run pip install mujoco to install.

Retrieve the rendered URDF of the robot

  1. Run the non-MuJoCo MoveIt Pro site config:

    moveit_pro run -v
  2. Enter the MoveIt Pro docker container:

    moveit_pro shell
  3. Copy the auto-generated URDF file from the /robot_description topic to a file.

    ros2 topic echo --once --full-length /robot_description | sed 's/\\n/\
    /g' > ~/user_ws/robot_description.urdf
  4. You may also have to rectify the filename paths for the mesh files. Example:

    • From: <mesh filename="file:///home/USERNAME/user_ws/install/kortex_description/share/kortex_description/arms/gen3/7dof/meshes/base_link.dae"/>
    • To: <mesh filename="package://kortex_description/arms/gen3/7dof/meshes/base_link.dae"/>

Create the MuJoCo config

Create a new config based on the site config called [robot_name]_mujoco_config and create the [robot_name]_mujoco_config/description/mujoco directory.

Inside of the mujoco directory create and populate the following:

  • assets directory:
    • Add in all of the .stl collision files for the robot and gripper.
    • If the visual files are currently in .stl or .dae files, use Blender to convert them to .obj files.
      • NOTE 1: Make sure the axes are aligned correctly when you export the obj files from blender. You may need to change the "Up Axis" to Z and the "Forward Axis" to X when you export.
      • NOTE 2: May need to use the obj2mjcf tool to create .obj files that have material information embedded in them. This tool can also perform convex mesh decomposition if needed.
  • [robot_name]_mujoco.xml MJCF file:
    • You can convert a URDF to MJCF in XML via either of the following 2 methods:
      1. Using the MuJoCo binaries, which can be installed via the instructions in the MuJoCo Getting started docs:
        ./compile <robot_name>.urdf <robot_name>.xml
      2. Using the MuJoCo pip package, which can be installed via pip install mujoco:
        python3 -c "import mujoco; model = mujoco.MjModel.from_xml_path('<robot_name>.urdf'); mujoco.mj_saveLastXML('<robot_name>.xml', model)"
    • ROS 2 package resolution does not work, so you may have to do some find and replace if your URDF uses ROS style references to mesh locations.
    • Confirm all the links from the robot.urdf file are present.
    • Use .stl assets to define collision geometries and obj files to define visual geometries.
    • Add actuators and tune.
    • NOTE: You can preview your robot model and tune the actuators using python3 -m mujoco --mjcf=/path/to/robot.xml
  • scene.xml MJCF file.
    • Include robot MJCF file.
    • Add sites if the simulation includes a scene camera.

The file structure beneath the description directory should resemble the following:

description
├── mujoco
│   ├── assets
│   │   ├── base_link.obj
│   │   ├── base_link.STL
│   │   └── ...
│   ├── robot.xml
│   └── scene.xml
└── robot_description.xacro

Use the MujocoSystem plugin in your robot description Xacro file

Change the content of the <ros2_control>/<hardware> tag to something like:

      <hardware>
<plugin>picknik_mujoco_ros/MujocoSystem</plugin>
<param name="mujoco_model">$(arg mujoco_model)</param>
<param name="mujoco_model_package">YOUR_MUJOCO_CONFIG_PKG</param>
<param name="render_publish_rate">10</param>
<param name="tf_publish_rate">60</param>
</hardware>

And specify the mujoco_model argument at the top as a Xacro arg like:

  <xacro:arg name="mujoco_model" default="description/mujoco/scene.xml" />

Current Sensor Support

NOTE: All <site> tags defined in the MJCF file will be picked up by the MuJoCo ros2_control plugin and published to tf2.

  • Force torque sensor:

    • Add a site with a force and torque sensor in the MJCF file. Ex:
    ...
    <site name="fts" size="0.01" pos="0.0 0.0 -0.0615" quat="0 0.0 1.0 0.0"/>
    ...
    <sensor>
    <force name="ee_force_sensor" site="fts"/>
    <torque name="ee_torque_sensor" site="fts" />
    </sensor>
    • You will also want to add an link in robot description file if you intend to plan using the force torque sensor reference frame. Ex:
    <link name="fts_link"/>
    <joint name="fts_joint" type="fixed">
    <origin rpy="0.0 0.0 3.14159265358979" xyz="0 0 0.0"/>
    <parent link="end_effector_link"/>
    <child link="fts_link"/>
    <axis xyz="0 0 0"/>
    </joint>
  • Camera:

    • Add a camera sensor and a site at the camera sensor location. Ex:
    <camera name="scene_camera" pos="3.12273 -1.45361 3.05847" fovy="58" mode="fixed" resolution="640 480" quat="0.815698 0.490631 0.15796 0.262616"/>
    <site name="scene_camera_optical_frame" pos="3.12273 -1.45361 3.05847" quat="0.15796 0.262616 -0.815698 -0.490631" size="0.03"/>
    • Note: the camera site z-axis must be flipped 180 degrees to get point clouds in the correct frame.
  • Lidar:

    • Add a site for each lidar laser angle using the <replicate> tag in the MJCF along with a <rangefinder>. Ex:
      <replicate count="360" sep="-" offset="0 0 0" euler="0.0174533 0 0">
    <site name="lidar" size="0.01" pos="-0.075 0.0 0.0" quat="0.0 0.0 0.0 1.0"/>
    </replicate>
    ...
    <sensor>
    <rangefinder site="lidar" user="0.1 -3.14159 3.14159 0.0174533 0.1 6.0"/>
    </sensor>
    • Add a lidar_publish_rate param in the ros2_control hardware section of the robot description file. Ex:
      <ros2_control>
    <hardware>
    <plugin>picknik_mujoco_ros/MujocoSystem</plugin>
    ...
    <param name="lidar_publish_rate">10</param>
    </hardware>
    </ros2_control>

Other configuration package changes

  • In the [robot_name]_mujoco_config/config/config.yaml file, make sure to change all package references from [robot_name]_base_config to [robot_name]_mujoco_config.