Robotics

Create Realistic Robotics Simulations with ROS 2 MoveIt and NVIDIA Isaac Sim

Robotic arm

MoveIt is a robotic manipulation platform that incorporates the latest advances in motion planning, manipulation, 3D perception, kinematics, control, and navigation. PickNik Robotics, the company leading the development of MoveIt, is exploring the use of NVIDIA Isaac Sim in an internal R&D project. The project goals are to improve perception for manipulation and augment with MoveIt Studio, PickNik’s commercial robotics developers platform, with more autonomous behaviors. 

This post shows you how to integrate MoveIt 2 with a robot simulated in NVIDIA Isaac Sim. The tutorial requires a machine with Isaac Sim 2022.2.0 installed and system configurations as listed below. See the NVIDIA Isaac Sim documentation for specific installation details and requirements. 

  1. NVIDIA Isaac Sim 2022.2.0 is installed on an Ubuntu 20.04 host in the $HOME/.local/share/ov/pkg/isaac_sim-2022.2.0 directory. This is the default location.
  2. Docker is installed.
  3. Clone the MoveIt2 Tutorials (see the section on computer setup below) to build an Ubuntu 22.04 Humble-based Docker image that can communicate with Isaac Sim and run this tutorial.

Introduction to ros2_control

To execute trajectories calculated by MoveIt, I recommend using the ros2_control framework to manage and communicate with your robot, real or simulated. This approach is recommended because it offers developers a common API that enables your software to switch between many different robot types and built-in sensors by simply changing some launch arguments.

For example, the Panda robot ros2_control.xacro uses the flag use_fake_hardware to switch between being simulated or connecting to a physical robot, as shown below. 

<hardware>
  <xacro:if value="${use_fake_hardware}">
    <plugin>mock_components/GenericSystem</plugin>
  </xacro:if>
  <xacro:unless value="${use_fake_hardware}">
    <plugin>franka_hardware/FrankaHardwareInterface</plugin>
    <param name="robot_ip">${robot_ip}</param>
  </xacro:unless>
</hardware>

Hardware components can be of different types. The plugin <plugin>mock_components/GenericSystem</plugin> is a simple system that forwards the incoming command_interface values to the tracked state_interface of the joints. This system simulates perfect control of the joints.

To expand the robot’s configuration to Isaac Sim, it is necessary to first introduce topic_based_ros2_control. This hardware interface is a system that subscribes and publishes on configured topics. For this tutorial, the topic /isaac_joint_states will contain the robot’s current state and /isaac_joint_commands will be used to actuate it. 

The moveit_resources_panda_moveit_config used in this tutorial does not support connecting to hardware. Consequently, ros2_control.xacro is now updated to load the TopicBasedSystem plugin when the flag ros2_control_hardware_type is set to isaac.

<xacro:if value="${ros2_control_hardware_type == 'mock_components'}">
    <plugin>mock_components/GenericSystem</plugin>
</xacro:if>
<xacro:if value="${ros2_control_hardware_type == 'isaac'}">
    <plugin>topic_based_ros2_control/TopicBasedSystem</plugin>
    <param name="joint_commands_topic">/isaac_joint_commands</param>
    <param name="joint_states_topic">/isaac_joint_states</param>
</xacro:if>

The included Python script loads a Panda robot and builds an OmniGraph to publish and subscribe to the ROS topics used to control the robot. To learn about configuring your Isaac Sim robot to communicate with ROS 2, see ROS 2 Joint Control: Extension Python Scripting.

Computer setup

Follow the steps below to set up your computer.

1. Install Isaac Sim using the Workstation Installation documentation.

2. Perform a shallow clone of the MoveIt2 Tutorials repo using the following script:

git clone https://github.com/ros-planning/moveit2_tutorials.git -b humble --depth 1

3. Open the folder in which you cloned the tutorials and then switch to the following directory:

cd moveit2_tutorials/doc/how_to_guides/isaac_panda

4. Build the Docker image:

docker compose build

Run the MoveIt Interactive Marker Demo with mock components

To test the mock_components/GenericSystem hardware interface, run the following script:

docker compose up demo_mock_components

RViz will open with the Panda robot using mock_components to simulate the robot and execute trajectories. See the Quickstart in RViz tutorial if this is your first time using MoveIt with RViz.

After you are done testing, select Ctrl+C in the terminal to stop the container.

Run the MoveIt Interactive Marker Demo with Isaac Sim

1. On the host computer, navigate to the Tutorials launch directory:

cd moveit2_tutorials/doc/how_to_guides/isaac_panda/launch

2. Load the Panda robot preconfigured to work with this tutorial. Note that this step assumes Isaac Sim is installed on the host in the $HOME/.local/share/ov/pkg/isaac_sim-2022.2.0" directory.

This step takes a few minutes to download the assets and set up Isaac Sim. Be patient and do not click the Force Quit dialog that pops up while the simulator starts. To load the Panda robot, run the following command:

./python.sh isaac_moveit.py

3. From the moveit2_tutorials/doc/how_to_guides/isaac_panda directory, start a container that connects to Isaac Sim using the topic_based_ros2_control/TopicBasedSystem hardware interface:

docker compose up demo_isaac

RViz will open with the Panda robot using the TopicBasedSystem interface to communicate with the simulated robot and execute trajectories.

Video 1. Learn how to integrate MoveIt and NVIDIA Isaac Sim

Conclusion

Combining MoveIt with NVIDIA Isaac Sim enables developers to create sophisticated and realistic simulations of robotics systems that mirror the real world. By pairing these two frameworks with ros2_control, you can quickly switch between different simulators and real hardware for fast iteration of new algorithms and robot behaviors. For more information on learning or contributing to MoveIt, visit the MoveIt website.

Discuss (2)

Tags