isaac_ros_moveit_benchmark#
Overview#
Isaac ROS MoveIt Benchmark consists of utility packages to measure the performance of various MoveIt 2 plugins, including Isaac ROS cuMotion, on various motion planning problems. Metrics related to planner performance, such as motion time and planning time, as well as metrics related to system usage, such as CPU usage are computed to provide a comprehensive view of planner performance.
The problems are sourced from the MotionBenchmarkMaker (MBM) dataset. The benchmark supports the UR5 CB3 robot and the Franka robot.
The isaac_ros_moveit_benchmark provides a standardized, convenient method to benchmark
various planners that are available as MoveIt 2 plugins.
To see how isaac_ros_moveit_benchmark is used to benchmark some specific planners, consult
the following packages:
Setup#
Set Up Development Environment#
Set up your development environment by following the instructions in getting started.
(Optional) Install dependencies for any sensors you want to use by following the sensor-specific guides.
Note
We strongly recommend installing all sensor dependencies before starting any quickstarts. Some sensor dependencies require restarting the development environment during installation, which will interrupt the quickstart process.
Build the Benchmarks#
Activate the Isaac ROS environment:
isaac-ros activateInstall the prebuilt Debian package:
sudo apt-get update
sudo apt-get install -y ros-jazzy-isaac-ros-ur5-cumotion-benchmark ros-jazzy-isaac-ros-ur5-ompl-benchmark ros-jazzy-isaac-ros-franka-cumotion-benchmark ros-jazzy-isaac-ros-franka-ompl-benchmark
Clone this repository under
${ISAAC_ROS_WS}/src:cd ${ISAAC_ROS_WS}/src && \ git clone -b release-4.0 https://github.com/NVIDIA-ISAAC-ROS/isaac_ros_benchmark.git isaac_ros_benchmark
Activate the Isaac ROS environment:
isaac-ros activateUse
rosdepto install the package’s dependencies:sudo apt-get update
rosdep update && \ rosdep install --from-paths ${ISAAC_ROS_WS}/src/isaac_ros_benchmark/benchmarks/isaac_ros_moveit_benchmark/isaac_ros_moveit_robot_benchmark/ur5/isaac_ros_ur5_cumotion_benchmark --ignore-src -y && \ rosdep install --from-paths ${ISAAC_ROS_WS}/src/isaac_ros_benchmark/benchmarks/isaac_ros_moveit_benchmark/isaac_ros_moveit_robot_benchmark/ur5/isaac_ros_ur5_ompl_benchmark --ignore-src -y && \ rosdep install --from-paths ${ISAAC_ROS_WS}/src/isaac_ros_benchmark/benchmarks/isaac_ros_moveit_benchmark/isaac_ros_moveit_robot_benchmark/franka/isaac_ros_franka_cumotion_benchmark --ignore-src -y && \ rosdep install --from-paths ${ISAAC_ROS_WS}/src/isaac_ros_benchmark/benchmarks/isaac_ros_moveit_benchmark/isaac_ros_moveit_robot_benchmark/franka/isaac_ros_franka_ompl_benchmark --ignore-src -y
Build the package from source:
cd ${ISAAC_ROS_WS}/ && \ colcon build --symlink-install --packages-up-to isaac_ros_ur5_cumotion_benchmark isaac_ros_ur5_ompl_benchmark isaac_ros_franka_cumotion_benchmark isaac_ros_franka_ompl_benchmark
Source the ROS workspace:
Note
Repeat this step in every terminal created inside the Isaac ROS environment.
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
Running the Benchmark#
launch_test $(ros2 pkg prefix isaac_ros_ur5_cumotion_benchmark)/share/isaac_ros_ur5_cumotion_benchmark/ur5_cumotion_benchmark_scripts/ur5_cumotion_mbm.py
launch_test $(ros2 pkg prefix isaac_ros_ur5_ompl_benchmark)/share/isaac_ros_ur5_ompl_benchmark/ur5_ompl_benchmark_scripts/ur5_ompl_mbm.py
launch_test $(ros2 pkg prefix isaac_ros_franka_cumotion_benchmark)/share/isaac_ros_franka_cumotion_benchmark/franka_cumotion_benchmark_scripts/franka_cumotion_mbm.py
launch_test $(ros2 pkg prefix isaac_ros_franka_ompl_benchmark)/share/isaac_ros_franka_ompl_benchmark/franka_ompl_benchmark_scripts/franka_ompl_mbm.py
Available Metrics#
Metric Name |
Explanation |
Interpretation |
|---|---|---|
Success Rate |
The percentage of successful plans over all problems. |
A higher success rate is better, because it indicates that the planner can work across a variety of scenarios. |
Planning Time |
The time taken by the planner to compute a valid plan. |
A lower planning time is better, because it indicates that the planner can generate plans faster. |
Motion Time |
The time it would take the robot to execute the plan generated by the planner. |
A lower motion time is better, because a robot can execute the plan faster. |
Path Length |
The total path length of the plan in radians (as measured in joint space, using an unweighted L2 norm). |
A lower path length is better, because it means that the robot needs to move less to execute the plan. |
Jerk |
The maximum jerk along the planned trajectory. |
A lower jerk is better, because it means that the trajectory is smoother and can be tracked more easily by the robot controller. |