ROS interface for MuJoCo simulator
mujoco_sim_x4.mp4
spawning.robots.mp4
- Advanced physics engine from https://mujoco.org/
- Import and export of URDF and MJCF
- Integration of controller interfaces, controller managers and hardware interfaces from http://wiki.ros.org/ros_control
- Integrate PD computed-torque control to ensure stability
- Spawn objects and destroy objects in run-time using rosservice
- Synchronize simulation time and real time (the simulation time can also be set to speed up or slow down)
- Visualize everything from MuJoCo to rviz
- Provide velocity controller for the base
- Support mimic joints from URDF
- Create a workspace
source /opt/ros/<ros-version>/setup.bash # source ROS
mkdir -p ~/mujoco_ws/src # create directory for workspace
- Initialize the workspace from this file and update the workspace
wstool init ~/mujoco_ws/src # initialize .rosinstall
wstool merge -t ~/mujoco_ws/src https://raw.githubusercontent.com/HoangGiang93/mujoco_ws/main/noetic.rosinstall
wstool update -t ~/mujoco_ws/src # pull the repositories
- Install dependency of all packages in the workspace
rosdep install --ignore-src --from-paths ~/mujoco_ws/src/mujoco_sim/ ~/mujoco_ws/src/mujoco_msgs/ ~/mujoco_ws/src/mujoco_world/ # install dependencies available through apt
- Build packages
cd ~/mujoco_ws # go to the workspace directory
catkin_make # build packages (or catkin build)
source ~/mujoco_ws/devel/setup.bash # source new overlay
This tutorial shows a quick view of some basic functionalities of this software. To learn more details please checkout this Wiki
- Import robot from URDF
mujoco_import.mp4
- Control the robot
mujoco_sim integrates hardware interfaces from http://wiki.ros.org/ros_control. Currently only effort-based joints are supported, so PID gains are required. It's recommended to set the parameters as {p: 2000, i: 100, d: 50}
Here are some examples:
- Joint position controller
- Include
ur_pos_control.launch
in the launch fileur5_display.launch
, then launch it
- Include
roslaunch ur_mujoco ur5_display.launch # Show up everything
rosrun ur_control test_joint_pos_publisher.py # Run a test
mujoco_pos_control.mp4
- Joint velocity controller
- Include
ur_vel_control.launch
in the launch fileur5_display.launch
, then launch it
- Include
roslaunch ur_mujoco ur5_display.launch # Show up everything
rosrun ur_control test_joint_vel_publisher.py # Run a test
mujoco_vel_control.mp4
- Joint trajectory controller (using test_trajectory from http://wiki.ros.org/ros_control_boilerplate)
- Include
ur_traj_control.launch
in the launch fileur5_display.launch
, then launch it
- Include
roslaunch ur_mujoco ur5_display.launch # Show up everything
roslaunch ur_control ur_test_trajectory.launch # Run a test
mujoco_traj_control.mp4
- Cartesian trajectory controller (using giskard, a cool framework for constraint- and optimization-based robot motion control, which is highly recommended)
- Include
franka_traj_control.launch
in the launch filepanda_arm_display.launch
, then launch it
- Include
roslaunch franka_mujoco panda_arm_display.launch # Show up everything
roslaunch giskardpy giskardpy_panda_arm.launch # Run giskard
mujoco_cartesian_traj_control.mp4
- Run the whole pick-and-place demo (using giskard, please update the following .rosinstall)
wstool merge -t ~/mujoco_ws/src https://raw.githubusercontent.com/HoangGiang93/mujoco_ws/main/giskard.rosinstall
wstool update -t ~/mujoco_ws/src
cd ~/mujoco_ws/src
catkin build
source ~/mujoco_ws/devel/setup.bash
roslaunch franka_mujoco dual_panda_arm_demo.launch
ERROR: gladLoadGL error
- Solution:
sudo apt install nvidia-driver-515