Tutorial for cuMotion MoveIt Plugin with Isaac Sim
Overview
This tutorial walks through the process of planning trajectories for a simulated Franka robot in Isaac Sim leveraging the cuMotion plugin for MoveIt 2 provided by Isaac ROS cuMotion. It is based on an example developed by PickNik Robotics, which in turn was based on a less featureful MoveIt example provided with Isaac Sim.
This tutorial has been tested with Isaac Sim 4.0 and Isaac Sim 2023.1.1.
Tutorial Walkthrough
Set up your development environment by following the instructions in Getting Started.
Clone
isaac_ros_common
under${ISAAC_ROS_WS}/src
.cd ${ISAAC_ROS_WS}/src && \ git clone -b release-3.1 https://github.com/NVIDIA-ISAAC-ROS/isaac_ros_common.git isaac_ros_common
Install the
isaac_ros_cumotion_examples
package and its dependencies (includingisaac_ros_cumotion
andisaac_ros_cumotion_moveit
):Launch the Docker container using the
run_dev.sh
script:cd ${ISAAC_ROS_WS}/src/isaac_ros_common && \ ./scripts/run_dev.sh
Install the prebuilt Debian package:
sudo apt-get install -y ros-humble-isaac-ros-cumotion-examples
Clone this repository under
${ISAAC_ROS_WS}/src
:cd ${ISAAC_ROS_WS}/src && \ git clone --recurse-submodules -b release-3.1 https://github.com/NVIDIA-ISAAC-ROS/isaac_ros_cumotion.git isaac_ros_cumotion
Launch the Docker container using the
run_dev.sh
script:cd ${ISAAC_ROS_WS}/src/isaac_ros_common && \ ./scripts/run_dev.sh
Use
rosdep
to install the package’s dependencies:rosdep install --from-paths ${ISAAC_ROS_WS}/src/isaac_ros_cumotion --ignore-src -y
Build the package from source:
cd ${ISAAC_ROS_WS} && \ colcon build --packages-up-to isaac_ros_cumotion_examples
Source the ROS workspace:
Note
Make sure to repeat this step in every terminal created inside the Docker container.
Because this package was built from source, the enclosing workspace must be sourced for ROS to be able to find the package’s contents.
source install/setup.bash
Install and configure Isaac Sim following the steps in the Isaac ROS Isaac Sim Setup Guide, stopping after step 4.
This tutorial uses the Isaac Sim “standalone workflow,” in which Isaac Sim is launched via a python script. In the terminal opened using the “Open in Terminal” button in the Isaac Sim App Selector (and notably not in a shell within the Isaac ROS docker container), source your ROS 2 workspace, e.g.,
source /opt/ros/humble/setup.bash
Run
python.sh
with the full path to thestart_isaac_sim_franka.py
script provided by theisaac_ros_cumotion_examples
package. Please note that this is a standalone script and could be copied to another location for convenience.Please clone or download the script from here. Then run it with
python.sh
as follows../python.sh <DOWNLOAD_PATH>/start_isaac_sim_franka.py
./python.sh ${ISAAC_ROS_WS}/src/isaac_ros_cumotion/isaac_ros_cumotion_examples/isaac_sim_scripts/start_isaac_sim_franka.py
Once Isaac Sim fully loads, the timeline will begin playing automatically.
Note
The example should be loaded in Isaac Sim before MoveIt is launched.
In a terminal within the Isaac ROS Docker container, launch MoveIt (including RViz) using the provided launch file. Remember to first run
source install/setup.bash
if package was built from source.ros2 launch isaac_ros_cumotion_examples franka_isaac_sim.launch.py
The visualization of the robot in RViz should reflect the current joint state of the simulated robot in Isaac Sim.
In a separate terminal within the Docker container, run the cuMotion planner node. Remember to first run
source install/setup.bash
if package was built from source.ros2 run isaac_ros_cumotion cumotion_planner_node --ros-args -p robot:=franka.xrdf -p urdf_path:=/opt/ros/humble/share/moveit_resources_panda_description/urdf/panda.urdf
In RViz, enable cuMotion by ensuring that
isaac_ros_cumotion
andcuMotion
are selected within the “Planning Library” pane within the “Context” tab in the bottom left corner of the RViz window.
Then select a target pose for the robot end effector, and click the “Plan” button in the “Planning” tab. If planning is successful, an animation of the trajectory will be visualized in RViz.
Click the “Execute” button in RViz. The simulated Franka robot in Isaac Sim will follow the motion of the robot in RViz.