Giter Site home page Giter Site logo

mujoco_sim's Introduction

mujoco_sim

ROS interface for MuJoCo simulator

Overview

mujoco_sim_x4.mp4
spawning.robots.mp4

Features

  • 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

Installation

  1. Create a workspace
source /opt/ros/<ros-version>/setup.bash    # source ROS
mkdir -p ~/mujoco_ws/src                    # create directory for workspace
  1. 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
  1. 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
  1. 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

Quick start

This tutorial shows a quick view of some basic functionalities of this software. To learn more details please checkout this Wiki

  1. Import robot from URDF
mujoco_import.mp4
  1. 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 file ur5_display.launch, then launch it
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 file ur5_display.launch, then launch it
roslaunch ur_mujoco ur5_display.launch        # Show up everything
rosrun ur_control test_joint_vel_publisher.py # Run a test
mujoco_vel_control.mp4
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 file panda_arm_display.launch, then launch it
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

Troubleshooting

  1. ERROR: gladLoadGL error
  • Solution: sudo apt install nvidia-driver-515

Software architecture

Picture

mujoco_sim's People

Contributors

hoanggiang93 avatar rohit-kumar-j avatar

Recommend Projects

  • React photo React

    A declarative, efficient, and flexible JavaScript library for building user interfaces.

  • Vue.js photo Vue.js

    ๐Ÿ–– Vue.js is a progressive, incrementally-adoptable JavaScript framework for building UI on the web.

  • Typescript photo Typescript

    TypeScript is a superset of JavaScript that compiles to clean JavaScript output.

  • TensorFlow photo TensorFlow

    An Open Source Machine Learning Framework for Everyone

  • Django photo Django

    The Web framework for perfectionists with deadlines.

  • D3 photo D3

    Bring data to life with SVG, Canvas and HTML. ๐Ÿ“Š๐Ÿ“ˆ๐ŸŽ‰

Recommend Topics

  • javascript

    JavaScript (JS) is a lightweight interpreted programming language with first-class functions.

  • web

    Some thing interesting about web. New door for the world.

  • server

    A server is a program made to process requests and deliver data to clients.

  • Machine learning

    Machine learning is a way of modeling and interpreting data that allows a piece of software to respond intelligently.

  • Game

    Some thing interesting about game, make everyone happy.

Recommend Org

  • Facebook photo Facebook

    We are working to build community through open source technology. NB: members must have two-factor auth.

  • Microsoft photo Microsoft

    Open source projects and samples from Microsoft.

  • Google photo Google

    Google โค๏ธ Open Source for everyone.

  • D3 photo D3

    Data-Driven Documents codes.