- 📑 Summary
- 🔌 Plugin Overview
- 🚀 Features
- 🛠 Prerequisites
- ⚙️ Installation
▶️ Usage- 🔄 ROS 2 Interface
- 💡 Example
- 👥 Contributing
- ✨ Contributors
A ROS 2 Plugin for the MuJoCo Simulator, enabling seamless integration for robotics simulation and control.
This plugin acts as a bridge, allowing sensor data to flow from MuJoCo to ROS 2, and actuator commands from ROS 2 back into your MuJoCo simulation. It's designed to be straightforward to use and configure, facilitating rapid development and testing of robotic systems.
Mujoco ROS 2 topics plotted on PlotJuggler
- ROS 2 Node Integration: Automatically initializes and manages a dedicated ROS 2 node (
mujoco_ros2_plugin
). - Sensor Data Publication:
- Publishes data from all MuJoCo sensors defined in your model.
- Supports single-value sensors (
example_interfaces::msg::Float64
). - Supports multi-dimensional sensors (
example_interfaces::msg::Float64MultiArray
).
- Actuator Command Subscription:
- Subscribes to ROS 2 topics for controlling MuJoCo actuators.
- Accepts
example_interfaces::msg::Float64
for actuator inputs.
- Configurable:
- Set a custom ROS 2 namespace for all topics (default:
"mujoco/"
). - Adjust the queue size for ROS 2 publishers and subscribers (default:
1
).
- Set a custom ROS 2 namespace for all topics (default:
- Passive MuJoCo Plugin: Operates within MuJoCo's simulation loop for timely data exchange.
- Easy to Build & Install: Standard CMake build process.
Ensure the following are installed and configured on your system:
- MuJoCo Physics Simulator:
- The build system tries to find MuJoCo via the
simulate
program in yourPATH
. - Alternatively, set the
MUJOCO_PATH
environment variable to your MuJoCobin
directory (e.g.,~/.mujoco/mujoco-X.Y.Z/bin
).
- The build system tries to find MuJoCo via the
- ROS 2: A C++20 compatible ROS 2 distribution (e.g., Humble, Iron).
- Source your ROS 2 environment:
source /opt/ros/<your_ros_distro>/setup.bash
- Required ROS 2 packages:
rclcpp
,example_interfaces
,ament_cmake
.
- Source your ROS 2 environment:
- Build Tools:
cmake
(version 3.16+)- C++20 compliant compiler (e.g., GCC, Clang)
-
Set
MUJOCO_PATH
(if needed): If MuJoCo isn't found automatically at yourPATH
, export theMUJOCO_PATH
:export MUJOCO_PATH="/path/to/your/mujoco/bin" # e.g., $HOME/.mujoco/mujoco-3.1.3/bin
-
Compile the Plugin:
cmake -B build cmake --build build
-
Install the Plugin Library:
cmake --install build
This command installs the plugin (e.g.,
libros2_plugin.so
) to${MUJOCO_PATH}/mujoco_plugin/
. This path is typically searched by MuJoCo by default.
MuJoCo needs to register the plugin for every simulation, the installation step usually places it in a standard location so that it can be automatically registered. If you install it elsewhere, or MuJoCo cannot find it, you might need to:
- Option 1: Move the library output file manually to the
mujoco_plugin
folder located at the same directory as the mujoco executable. - Option 2:: Register the plugin manually by calling the
Ros2Plugin::register_plugin()
function before the mujoco simulate loop.
To activate the plugin, add an <extension>
block to your MJCF model file. The plugin is identified by mujoco.ros2
.
<mujoco>
<extension>
<plugin plugin="mujoco.ros2">
<instance name="ros2_plugin">
<!-- Optional: Configuration parameters -->
<!-- <config key="ros_namespace" value="mujoco/"/> -->
<!-- <config key="topic_queue_size" value="1"/> -->
<!-- <config key="topic_reliability" value="reliable"/> -->
</instance>
</plugin>
</extension>
<!-- ... rest of your MJCF model ... -->
</mujoco>
Configure the plugin directly within the MJCF <plugin>
tag:
-
ros_namespace
(string, default:"mujoco/"
): Sets the ROS 2 namespace for all topics. Ensure it ends with a/
for correct namespacing.<config key="ros_namespace" value="custom_namespace/"/>
-
topic_queue_size
(integer, default:1
): Defines the queue size for ROS 2 publishers and subscribers.<config key="topic_queue_size" value="5"/>
-
topic_reliability
(string, default:reliable
): Sets the reliability of the ROS topic QoS.<config key="topic_reliability" value="best_effort"/>
The plugin establishes the following ROS 2 communication channels:
Data from sensors defined in the <sensor>
section of your MJCF will be published.
- Single-Dimension Sensors:
- Topic:
<ros_namespace>sensors/<sensor_name>
- Type:
example_interfaces::msg::Float64
- Topic:
- Multi-Dimension Sensors:
- Topic:
<ros_namespace>sensors/<sensor_name>
- Type:
example_interfaces::msg::Float64MultiArray
- Topic:
Where <sensor_name>
is the name
attribute from the MJCF.
Commands for actuators defined in the <actuator>
section of your MJCF can be sent via these topics.
- Topic:
<ros_namespace>actuators/<actuator_name>/command
- Type:
example_interfaces::msg::Float64
- The
data
field of the message is applied tomjData->ctrl[]
for the respective actuator.
- The
Where <actuator_name>
is the name
attribute from the MJCF.
Consider this MJCF snippet for a simple car:
<mujoco>
<extension>
<plugin plugin="mujoco.ros2">
<instance name="ros2_plugin">
<config key="ros_namespace" value="simple_car/"/>
</instance>
</plugin>
</extension>
<asset>
<mesh name="chasis" scale=".01 .006 .0015"
vertex=" 9 2 0
-10 10 10
9 -2 0
10 3 -10
10 -3 -10
-8 10 -10
-10 -10 10
-8 -10 -10
-5 0 20"/>
</asset>
<default>
<joint damping=".03" actuatorfrcrange="-0.5 0.5"/>
<default class="wheel">
<geom type="cylinder" size=".03 .01" rgba=".5 .5 1 1"/>
</default>
</default>
<worldbody>
<geom type="plane" size="3 3 .01"/>
<body name="car" pos="0 0 .03">
<freejoint/>
<geom name="chasis" type="mesh" mesh="chasis"/>
<geom name="front wheel" pos=".08 0 -.015" type="sphere" size=".015" condim="1" priority="1"/>
<body name="left wheel" pos="-.07 .06 0" zaxis="0 1 0">
<joint name="left_wheel"/>
<geom class="wheel"/>
</body>
<body name="right_wheel" pos="-.07 -.06 0" zaxis="0 1 0">
<joint name="right_wheel"/>
<geom class="wheel"/>
</body>
</body>
</worldbody>
<actuator>
<motor name="left_motor" joint="left_wheel" ctrlrange="-1 1"/>
<motor name="right_motor" joint="right_wheel" ctrlrange="-1 1"/>
</actuator>
<sensor>
<jointactuatorfrc name="left_torque" joint="left_wheel"/>
<jointactuatorfrc name="right_torque" joint="right_wheel"/>
</sensor>
</mujoco>
This would result in:
- Publishers:
/simple_car/sensors/left_torque
(Float64
)/simple_car/sensors/right_torque
(Float64
)
- Subscribers:
/simple_car/actuators/left_motor/command
(Float64
)/simple_car/actuators/right_motor/command
(Float64
)
Interact using ROS 2 tools:
# Listen to a sensor
ros2 topic echo /simple_car/sensors/left_torque
# Send a command to an actuator
ros2 topic pub /simple_car/actuators/right_motor/command example_interfaces/msg/Float64 '{data: 0.5}' --once
To learn how to contribute to the project, see the following contribution guidelines.
-
Use the present tense ("Add feature" not "Added feature").
-
Use the imperative mood ("Move cursor to..." not "Moves cursor to...").
-
It is strongly recommended to start a commit message with a related emoji:
- 📝
:memo:
for documentation. - 🐛
:bug:
for bug issues. - 🚑
:ambulance:
for critical fixes. - 🎨
:art:
for formatting code. - ✨
:sparkles:
for new features.
For more examples, see this reference.
- 📝
The project workflow is based on GitHub Flow.
Thanks goes to these wonderful people (emoji key):
Gabriel Cosme Barbosa 💻 📖 🔬 👀 |
Pedro de Santi 💻 📖 🔬 👀 |
This project follows the all-contributors specification. Contributions of any kind welcome!