DR mujoco
The documentation page for DR mujoco which simulate differential drive robot for educational purpose.
MuJoCo & ROS 2 Simulator Overview
This simulator is a bridge program designed to connect the advanced physics engine MuJoCo with the ROS 2 robotics framework.
It allows you to test your ROS 2 including control, navigation, and perception algorithms—in a realistic, physics-based environment.
Key Features
Seamless ROS 2 Integration (The Core Feature)
The simulator’s most important feature is its complete integration into the ROS 2 ecosystem.
-
Uses Standard Topics:
- It accepts robot movement commands via the standard /cmd_vel topic, using the
geometry_msgs/msg/Twist
message type. - It publishes the robot’s position and velocity status as an /odom topic, using the
nav_msgs/msg/Odometry
message type.
- It accepts robot movement commands via the standard /cmd_vel topic, using the
-
Publishes Sensor Data as ROS 2 Messages:
- Video from the robot’s camera is published as a
sensor_msgs/msg/Image
message, which can be viewed in RViz or used as input for computer vision nodes. - Wheel encoder tick counts are published as
std_msgs/msg/Int32
messages, allowing for more realistic odometry calculation tests.
- Video from the robot’s camera is published as a
-
Compatible with Existing ROS 2 Tools:
- You can use the entire ROS 2 ecosystem you’re already familiar with, such as visualizing odometry and sensor data in
RViz2
or inspecting the node and topic connections withrqt_graph
.
- You can use the entire ROS 2 ecosystem you’re already familiar with, such as visualizing odometry and sensor data in
Realistic Physics Simulation
Thanks to the fast and accurate MuJoCo physics engine, the simulator faithfully reproduces contact, friction, and inertia. This helps to reduce the “Sim-to-Real Gap,” making the transition from simulation to a physical robot smoother.
Customizable Robot Models
The robot in the simulation is defined using MuJoCo’s XML format, giving you the freedom to design and test your own creations. You can quickly modify wheel sizes, body mass, sensor placements, and more to prototype different robot designs.
How It Works
This simulator acts as a bidirectional “translator” between your ROS 2 nodes and the MuJoCo engine.
[Your ROS 2 Node] <-- ROS 2 Topics --> [This Simulator] <-- MuJoCo API --> [MuJoCo Physics Engine]
(e.g., Teleop Node) (/cmd_vel, /odom) (ROS 2 <=> MuJoCo)
Get started
Requirements Ubuntu 22.04, 24.04 ROS2 Humble, Jazzy Mujoco more than 3.3.5 It should work with other versions but they have not been tested. Installation Install mujoco pip install mujoco Clone simulator repository from here. https://github.com/Centre-for-Biorobotics/dr_mujoco Put it on your ros2 workspace and then colcon build. You can launch demo script as ros2 launch dr_mujoco default.launch.py If you see the red box on the simulator, it is success! This simulator is for differential drive robot.
Make your robot model
How to Create MuJoCo XML Files This is a step-by-step guide for beginners on how to create the MuJoCo XML files used in this simulator. What is a MuJoCo XML File? MuJoCo (Multi-Joint dynamics with Contact) is an advanced physics simulation engine. The XML file is what defines the simulation environment, including the world, the robot’s shape, its weight, and how its joints move. For this simulator, you will primarily prepare two XML files:
Run a simulation
How to Run the Simulation with a ROS 2 Launch File A ROS 2 Launch File is a powerful tool for automating the startup and configuration of nodes. It allows you to run complex applications with a single, reproducible command. This page breaks down a sample launch file to explain how it works and provides the steps to run your simulation. Understanding the Launch File Below is a typical launch file for starting the simulation.