Note
This project is a work-in-progress, so new features will be added slowly. Feel free to contribute your own improvements.
This class establishes communication between a MuJoCo simulation and ROS2.
It publishes a sensor_msgs::msg::JointState
topic for you to use, and allows commands to the joints via a std_msgs::msg::Float64MultiArray
topic:
It can run in POSITION
, VELOCITY
, or TORQUE
mode which may be set via the config and/or launch file(s).
Tip
You can download MuJoCo robot models here.
- Launches a MuJoCo simulation.
- Creates a ROS2 node for communication.
- Publishes joint state information over ROS2.
- Provides real-time visualization of the robot and its environment.
- Allows manual interaction with the simulation.
- ROS2 (Humble Hawksbill or later)
- MuJoCo
- GLFW
- Standard C++ libraries
Ensure that you have ROS2 and MuJoCo installed on your system.
-
Install ROS2: Follow the ROS2 installation guide for your operating system.
-
Install MuJoCo: Download and install MuJoCo from the official website.
-
Install GLFW:
sudo apt-get install libglfw3-dev
Clone the repository:
git clone https://github.com/Woolfrey/interface_mujoco_ros2
cd interface_mujoco_ros2
Build the package:
colcon build
Source the ROS2 workspace:
source install/setup.bash
There are 2 different control modes currently available:
To run velocity control, you can launch:
ros2 launch mujoco_interface velocity_mode.py
This requires that the topic /joint_commands
contains an array of velocites (in rad/s).
To run torque control, you can launch:
ros2 launch mujoco_interface torque_mode.py
This requires that the topic /joint_commands
contains an array of torques (Nm).
Tip
In torque mode, gravity and Coriolis torques are automatically compensated for.
Contributions are welcome! Please fork the repository and submit pull requests.
- Fork the Project
- Create your Feature Branch (git checkout -b feature/AmazingFeature)
- Commit your Changes (git commit -m 'Add some AmazingFeature')
- Push to the Branch (git push origin feature/AmazingFeature)
- Open a Pull Request
Distributed under the GNU General Public License. See LICENSE for more information. Contact
Jon Woolfrey - [email protected]