Control Panda with MoveIt! in Omniverse Isaac

In this blog post, we will import an existing robotic arm model into NVIDIA’s Omniverse Isaac simulation environment and create a ROS package and an Isaac extension for controlling the arm with MoveIt!. MoveIt! will control to the robotic arm inside Isaac via the ROS Bridge.

NVIDIA Omniverse Isaac gains popularity with a rich feature set and realistic simulations with accurate physics and ray-tracing. In this post, we will lay the foundation for a simulation world where a robotic arm can be used for more complex tasks such as populating a conveyor belt with packages in a warehouse.

Overview

We will use the Franka Emika Panda arm as an example, but the configuration path outlined in this post applies to any robotic arm with a correct URDF file. In the illustration below, you can see our workflow for controlling the robotic arm in Isaac with ROS using MoveIt!. We will use the robot URDF as input for the MoveIt Setup Assistant and the Isaac URDF importer.

The MoveIt Setup Assistant will output a ROS package that provides everything we need to start the motion planning pipeline. In addition, we will create a small ROS package that launches the motion planning pipeline. This package can later be used as a starting point for more complex implementations.

The Isaac URDF importer will output a .usd (binary) or .usda (human-readable) file which we will import into a scene with an Isaac extension. With the extension, we will create a so-called Action graph that provides an interface for communication between the robotic arm in Isaac Sim and the robot control and motion planning components running on the ROS side.

We will build this prototype with the long term support version of ROS2, Humble, and NVIDIA Omniverse Isaac version 2023.1.1.

Implementation

ROS / MoveIt!

We will use a simple URDF file for the Franka Emika robotic arm as the starting point of our ROS configuration. The model defines the robot without the hand component. In the workflow illustration, we outlined how we will use the URDF file to create a ROS package as MoveIt configuration. The robot URDF itself is located inside a different, simple ROS package called franka_description. I created this package for the purpose of this tutorial. It contains the URDF file and the geometry files that visualize the robot’s links and their collision models.

Let’s start by creating a ROS2 workspace and cloning the franka_description repository into the src directory:

mkdir -p ~/isaac_moveit_ws/src
cd ~/isaac_moveit_ws/src
git clone https://github.com/erdalpekel/franka_description.git
cd ..
colcon build
source install/setup.bash
ros2 run moveit_setup_assistant moveit_setup_assistant

After building and sourcing the workspace we can start the MoveIt! Setup Assistant as outlined above. The assistant uses the robot URDF as input and configures the motion planning pipeline with the input provided by the user. In the gallery provided below, you can see how to configure the robotic arm.

The user checks for self-collisions of the arm’s links and proceeds to add a planning group. We add the robot’s links, joints and kinematic chain for the planning group definition. We also specify the kinamtic solver to kdl_kinematics. In the following steps, we generate the ROS2 and MoveIt! controllers with the assistant and finish the configuration by adding information about the author. We save the package to a new subdirectory inside our workspace called franka_moveit_config.

The Moveit! configuration is not finisehd yet. We will alter the default configuration to make it compatible with Omniverse Isaac Sim. The first step is to change the package.xml by adding the ROS packages topic_based_control, joint_state_broadcaster and joint_trajectory_controller as execution dependencies. Next, we will change the hardware interface that ros_control uses to control the arm. In config/panda.ros2_control.xacro add the following lines:

<hardware>
  <plugin>topic_based_ros2_control/TopicBasedSystem</plugin>
  <param name="joint_commands_topic">/joint_commands</param>
  <param name="joint_states_topic">/joint_states</param>
</hardware>

These lines ensure, that ros_control controls the arm via messages sent to and received from predefined ROS topics instead of pure function calls on a C++ plugin. These topics are defined above as /joint_commands and /joint_states.

Next, we will add the configuration file config/moveit_controllers.yaml that defines the controllers MoveIt! should load and use at startup:

moveit_controller_manager: moveit_simple_controller_manager/MoveItSimpleControllerManager

moveit_simple_controller_manager:
  controller_names:
    - panda_arm_controller

  panda_arm_controller:
    type: FollowJointTrajectory
    action_ns: follow_joint_trajectory
    default: true
    joints:
      - panda_joint1
      - panda_joint2
      - panda_joint3
      - panda_joint4
      - panda_joint5
      - panda_joint6
      - panda_joint7

Finally, we will create a new ROS package in the ROS part with a new launch file and a Clock node. The clock node synchronizes simulation time with Isaac Sim and launches all necessary components including RViz, MoveIt!, ros2_control controller_manager and tf2.

cd ~/isaac_moveit_ws/src
git clone https://github.com/erdalpekel/isaac_moveit_sample.git
cd ..
colcon build

Before we continue with Isaac Sim, we will add the following line to the ~/.bashrc file:

source ~/isaac_moveit_ws/install/setup.bash

Sourcing our ROS workspace will ensure, that Isaac sim can find the geometry files referenced within our robot’s URDF model during Isaac Sim’s import process.

Isaac Sim

In Isaac Sim we will import the robot URDF as .usda file, create an extension, and modify its source code to add the robot to the scene. In the final step, we will add a so called Action Graph to the scene with the Isaac APIs.

Import URDF model in Isaac

Importing the robot URDF in Isaac Sim is straightforward. Isaac Sim provides an extensions for importing URDFs. In the gallery below, you can see how we imported the Panda arm by providing its path. Additionally, we save the imported model as .usda file, because we will modify it in the next step.

We will modify the .usda model in order to eliminate the Root parent node and move the PhysicsArticulationRoot from the base link panda_link0 to the parent node panda. All occurrences of /Root in the document should be deleted:

#usda 1.0
(
    defaultPrim = "panda"
    upAxis = "Z"
)

    def Xform "panda" (
        apiSchemas = ["PhysicsArticulationRootAPI", "PhysxArticulationAPI"]
    )
    {
        bool physxArticulation:enabledSelfCollisions = 0
        int physxArticulation:solverPositionIterationCount = 32
        int physxArticulation:solverVelocityIterationCount = 16
        token ui:displayGroup = "Material Graphs"
...

Create Scene with Panda

In the next step we will create and save an empty scene at scene/scene.usda that we can populate with our robotic arm in the next step:

Create Isaac Extension

We will create an Isaac Sim extension that will load a so-called scenario with the robotic arm and the configurations for bridging the simulations to ROS and MoveIt!. Isaac Sim provides an extension generator that we will use to create our extension as illustrated in the gallery below:

We will remove the boilerplate code in the ui_builder.py and scenario.py files to exchange to Universal Robots arm with our own model and create the Action Graph. Additionally, we will add the panda arm to the scene at scene/scene.usda:

    def "panda" (
        prepend payload = @./robots/panda.usda@
    )
    {
        quatd xformOp:orient = (1, 0, 0, 0)
        # double xformOp:rotateX:unitsResolve = -90
        double3 xformOp:scale = (1, 1, 1)
        double3 xformOp:scale:unitsResolve = (100, 100, 100)
        double3 xformOp:translate = (0, 0, 0)
        uniform token[] xformOpOrder = ["xformOp:translate", "xformOp:orient", "xformOp:scale", "xformOp:rotateX:unitsResolve", "xformOp:scale:unitsResolve"]
    }

Add Action Graph

The final step in our sample extensions is the addition of an Action Graph. The Action Graph consists of interconnected nodes that each represent independent units of function. For example, the ROS2 Publish Joint State node publishes the robotic arm’s joint angles to the ROS topic /joint_states at a predefined frequency. In general, the Action Graph allows our extension to read data from the scenario in Isaac Sim and communicate with ROS nodes over the ROS bridge. Action Graphs are not restricted to use with robotic arms but can also be used outside of the ROS / robotics context.

We will create the Action Graph with the Omniverse Python API in the scenario.py file within the setup_scenario() method. The og.Controller.edit function allows us to create and edit an Action Graph at a given prim path. We create the following nodes (see figure below):

  • ROS2 Subscribe Clock: Subscribes to the simulation time published by our Clock.cpp node
  • ROS2 Subscribe Joint State: Subscribes to /joint_states ROS topic and send joint angles to robotic arm Articulation at prim path /World/panda
  • ROS2 Publish Joint State: Publishes robotic arm’s joint angles to /joint_states ROS topic
  • ROS2 Publish Transform Tree: Publishes transform tree of all prims below /World prim in simulation scene (including robotic arm at /World/panda)
  • Articulation Controller: Controls robotic arm Articulation

Result

The resulting ROS package can be started with the following commands:

ros2 launch isaac_moveit_sample simulation.launch.py

The Isaac Sim extension can be opened from the top navigation bar. We now have two windows: RViz for the motion planning pipeline for Panda and Isaac Sim with panda arm simulation running on Load and Run. We will load and run the simulation in Isaac Sim and start an arbitrary motion planning and execution request in RViz:

Panda arm is successfully planning to the goal and Isaac Sim is executing the motion plan with the simulated arm. The custom ROS package as well as the modified franka_description and Isaac Sim extension repositories are available in my GitHub profile.

One thought on “Control Panda with MoveIt! in Omniverse Isaac

Comments are closed.