Skip to content

Isaac ROS

Practical

Isaac ROS is NVIDIA’s collection of GPU-accelerated ROS 2 packages that bring high-performance AI and perception capabilities to robots running on Jetson and discrete GPUs.

Why Isaac ROS?

Standard ROS 2 perception runs on CPU. Isaac ROS moves the heavy lifting to GPU:

CapabilityCPU (Standard ROS)GPU (Isaac ROS)
Image processing~30 FPS~300+ FPS
Stereo depth~10 FPS~90 FPS
Visual SLAM~15 FPS~60 FPS
Object detection~5 FPS~100+ FPS
3D reconstructionSecondsReal-time

Architecture

┌──────────────────────────────────────────────────────────────────┐
│ Your ROS 2 Application │
├──────────────────────────────────────────────────────────────────┤
│ Isaac ROS Packages │
│ ┌─────────────┐ ┌─────────────┐ ┌─────────────┐ ┌────────────┐ │
│ │ Visual SLAM │ │ AprilTag │ │ Freespace │ │ DNN │ │
│ │ │ │ Detection │ │ Segmentation│ │ Inference │ │
│ └─────────────┘ └─────────────┘ └─────────────┘ └────────────┘ │
├──────────────────────────────────────────────────────────────────┤
│ NITROS (Zero-Copy Transport) ┌─────────────────────┐ │
│ ┌─────────────────────────────────┐ │ Type Adaptation │ │
│ │ GPU Memory → GPU Memory │ │ (sensor_msgs ↔ │ │
│ │ No CPU copy between nodes │ │ nitros types) │ │
│ └─────────────────────────────────┘ └─────────────────────┘ │
├──────────────────────────────────────────────────────────────────┤
│ NVIDIA Libraries │
│ ┌─────────┐ ┌─────────┐ ┌─────────┐ ┌─────────┐ ┌───────────┐ │
│ │ VPI │ │TensorRT │ │ cuDNN │ │ CUDA │ │ Triton │ │
│ └─────────┘ └─────────┘ └─────────┘ └─────────┘ └───────────┘ │
└──────────────────────────────────────────────────────────────────┘

Key Packages

Visual Perception

PackageFunction
isaac_ros_visual_slamGPU-accelerated Visual SLAM (cuVSLAM)
isaac_ros_apriltagFiducial marker detection
isaac_ros_centerpose6-DOF object pose estimation
isaac_ros_foundationposeZero-shot pose estimation
isaac_ros_depth_image_procDepth processing and pointcloud
isaac_ros_image_procImage rectification, resize, format conversion

NITROS: Zero-Copy Transport

The secret sauce of Isaac ROS performance:

// Standard ROS 2: CPU memory copy at every node
Node A (GPU) → Copy to CPU → Publish → Subscribe → Copy to GPU → Node B (GPU)
// NITROS: GPU memory stays on GPU
Node A (GPU) → NITROS Publish → NITROS Subscribe → Node B (GPU)
↓ ↑
[Same GPU memory pointer]

Using NITROS Types

# Standard ROS image subscriber (CPU)
from sensor_msgs.msg import Image
# NITROS-accelerated subscriber (GPU)
from isaac_ros_nitros_image_type.msg import NitrosImage

NITROS types are automatically adapted to/from standard ROS types at graph boundaries.

Installation

Requires Docker Engine 27.2.0+. The Isaac ROS CLI manages dev container setup.

  1. Set up Docker (recommended approach)

    Terminal window
    # Clone Isaac ROS Common
    git clone https://github.com/NVIDIA-ISAAC-ROS/isaac_ros_common.git
    cd isaac_ros_common
  2. Launch development container

    Terminal window
    # On Jetson
    ./scripts/run_dev.sh
    # On x86 with GPU
    ./scripts/run_dev.sh --gpus all
  3. Clone desired packages

    Terminal window
    cd /workspaces/isaac_ros-dev/src
    git clone https://github.com/NVIDIA-ISAAC-ROS/isaac_ros_visual_slam.git
  4. Build and source

    Terminal window
    cd /workspaces/isaac_ros-dev
    colcon build --symlink-install
    source install/setup.bash

Example: Visual SLAM

Terminal window
# Launch Isaac ROS Visual SLAM with a RealSense camera
ros2 launch isaac_ros_visual_slam isaac_ros_visual_slam_realsense.launch.py
# Subscribe to SLAM output
import rclpy
from nav_msgs.msg import Odometry
def odom_callback(msg):
pos = msg.pose.pose.position
print(f"Position: ({pos.x:.2f}, {pos.y:.2f}, {pos.z:.2f})")
# ... standard ROS 2 subscriber setup

Performance Tips

Comparison with Standard ROS

AspectStandard ROS 2Isaac ROS
ComputeCPUGPU (CUDA, TensorRT)
MemorySystem RAMGPU VRAM + zero-copy
LatencyHigher (CPU bound)Lower (parallel GPU)
PowerLess efficientOptimized for Jetson
CompatibilityUniversalNVIDIA hardware

Prerequisites

Supported platforms:

  • Jetson AGX Thor with JetPack 7.x
  • Jetson Orin (AGX, NX) with JetPack 6.x
  • x86_64 with NVIDIA discrete GPU

Learn More

Sources