MoveIt Motion Planning Framework#
Learning Objectives#
This tutorial is demonstrating NVIDIA Isaac Sim integrated with the MoveIt Motion Planning Framework using the Franka Emika Panda robot.
Getting Started#
Prerequisite
Install MoveIt from pre-built binaries (Debian):
sudo apt install ros-$ROS_DISTRO-moveit
Installed and built
panda_moveit_config
package in your ROS workspace by following the steps outlined here.This tutorial requires
isaac_moveit
ROS package provided under the directorynoetic_ws/
in our ROS repo. It contains the required launch and config files. Complete ROS and ROS 2 Installation, make sure ROS environment is setup correctly and those packages are inside yourROS_PACKAGE_PATH
.Completed Joint Control: Extension Python Scripting.
ROS bridge is enabled and
roscore
is running before running NVIDIA Isaac Sim.
Running MoveIt#
Load the environment by going to Window > Examples > Robotics Examples. Click on the Robotics Examples tab. Expand the sections on the left hand side and open the example: ROS > MoveIt > MoveIt. Once the stage is loaded completely, the simulation should automatically be playing.
In a ROS sourced terminal, launch the execution launch file with the following command:
roslaunch isaac_moveit franka_isaac_execution.launch
The robot should now automatically move to the ready state and a separate RViz window will open up.
Note
Due to a sync issue with
roslaunch
, sometimes the robot may not automatically move to the ready state. If this happens, stop the launch file and follow these steps to manually run the panda_combined_joints_publisher node before running the launch file:Open the launch file (
<noetic_ws>/src/isaac_moveit/launch/franka_isaac_execution.launch
) and remove the following line:<node pkg="isaac_moveit" name="panda_combined_joints_publisher" type="panda_combined_joints_publisher.py" />
.Open a new terminal sourced to ROS and noetic_ws. Run the following command to manually run panda_combined_joints_publisher ROS node:
rosrun isaac_moveit panda_combined_joints_publisher.py
.Finally, run the newly modified launch file:
roslaunch isaac_moveit franka_isaac_execution.launch
.
In the RViz window, there should already be a MotionPlanning tab open. If not, add the MotionPlanning Plugin by clicking Add. Then, under the moveit_ros_visualization folder, choose MotionPlanning and press Ok.
Plan the movement for the arm by selecting
panda_arm
, found underPlanning Group
. Use the displayed arrows and rotation disks to set a goal position for the robot. Alternatively you can choose to select<random_valid>
underGoal State
.Under Commands, click on Plan to see the robot in Rviz play out the planned trajectory. Press Execute to execute the planned trajectory on the robot in Isaac Sim.
To plan the movement of the hand, under Planning Group select the hand option. Under Goal State, select close.
Click on Plan followed by Execute. The finger joints will start moving to the closed state.
Summary#
In this tutorial, we covered running MoveIt with NVIDIA Isaac Sim.
Next Steps#
Continue on to the next tutorial in our ROS Tutorials series, Custom Message to learn to setup and use custom messages in NVIDIA Isaac Sim.