isaac_ros_cumotion_moveit
Source code on GitHub.
Quickstart
Set Up Development Environment
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 isaac_ros_cumotion_moveit
and Examples
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
Set Up MoveIt 2 with cuMotion
Complete the following steps for your selected robot.
Optional: If running on a physical UR robot, install the following support package:
sudo apt install ros-humble-ur-bringup
Generate a URDF for the UR10e from the corresponding xacro:
mkdir -p ${ISAAC_ROS_WS}/isaac_ros_assets/urdf && \ xacro -o ${ISAAC_ROS_WS}/isaac_ros_assets/urdf/ur10e.urdf /opt/ros/humble/share/ur_description/urdf/ur.urdf.xacro ur_type:=ur10e name:=ur10e
Launch MoveIt (including RViz).
ros2 launch isaac_ros_cumotion_examples ur.launch.py ur_type:=ur10e
In a separate terminal, run the cuMotion planner node. Remember to first
source install/setup.bash
if package was built from source.ros2 run isaac_ros_cumotion cumotion_planner_node --ros-args -p robot:=ur10e.xrdf -p urdf_path:=${ISAAC_ROS_WS}/isaac_ros_assets/urdf/ur10e.urdf
Launch MoveIt (including RViz).
ros2 launch isaac_ros_cumotion_examples franka.launch.py
In a separate terminal, run the cuMotion planner node. Remember to first
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
Create a MoveIt configuration for your robot using the MoveIt setup assistant.
cuMotion requires a URDF as well as an XRDF file for the robot. URDFs are available for most common robot arms, but it may be necessary to create an XRDF file. This can be done by hand (e.g., using an existing XRDF file as a reference) or by using the Robot Description Editor in Isaac Sim 4.0 or later.
Copy cuMotion’s planning configuration file to the MoveIt
config
directory for your robot:cp ${ISAAC_ROS_WS}/src/isaac_ros_cumotion/isaac_ros_cumotion_moveit/config/isaac_ros_cumotion_planning.yaml \ PATH/TO/ROBOT_moveit_config/config/
In the MoveIt launch file for your robot (e.g.,
<ROBOT>_moveit_config/launch/<ROBOT>_moveit.launch.py
), add the following entry to theparameters
list of theNode()
constructor formove_group_node
:{ "planning_pipelines": ["ompl", "isaac_ros_cumotion"] }
Install any additional required packages for your robot, and run
source install/setup.bash
if building from source.Launch MoveIt (including RViz) using a suitable launch file for your robot, e.g.:
ros2 launch ROBOT_moveit_config ROBOT_moveit.launch.py
In a separate terminal, 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:=/path/to/ROBOT.xrdf -p urdf_path:=/path/to/ROBOT.urdf
Using the cuMotion Planner in MoveIt
Enable cuMotion by ensuring that isaac_ros_cumotion
and cuMotion
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. For a demonstration of collision-aware planning, first add one or more obstacles in the “Scene Objects” tab.
Note
The “Execute” and “Plan & Execute” buttons in RViz will only work if a physical robot is connected or if the robot is emulated in the corresponding robot driver or via an external simulator. The MoveIt configuration for Franka includes such emulation via a “fake hardware” interface, but the same is not true for UR, which would require an external simulator such as URSim.
Warning
In normal operation, only a single MoveIt move_group
node should be running at a time. If the node fails to
exit cleanly, however, it may result in two nodes running when the graph is next launched. RViz then connects
to both instances, which results in both requesting a plan from the cuMotion planner node via a MoveGroup
action
at nearly the same time. The second to arrive preempts the first without waiting for in-flight CUDA operations to
complete, possibly resulting in “CUDA invalid” errors.
If such errors are observed, please ensure that only a single move_group
node is running. The cuMotion planner
node will be made more robust in a future release.
Try More Examples
To continue your exploration, check out the following suggested examples:
Troubleshooting
Isaac ROS Troubleshooting
For solutions to problems with Isaac ROS, see troubleshooting.