isaac_ros_data_replayer

Source code on GitHub.

Overview

The isaac_ros_data_replayer package enables replaying sensor data recorded using the isaac_ros_data_recorder package. This package also enables reliable extraction of stereo cameras in different formats, including depth using AI-based perception. Supported formats include MP4, PNG, and PFM. Stereo camera frames are extracted in synchronized pairs while depth frames are aligned to the left stereo imager.

Quickstart

Set Up Development Environment

  1. Set up your development environment by following the instructions in getting started.

  2. Clone isaac_ros_common under ${ISAAC_ROS_WS}/src.

    cd ${ISAAC_ROS_WS}/src && \
       git clone https://github.com/NVIDIA-ISAAC-ROS/isaac_ros_common.git
    
  3. (Optional) Install dependencies for any sensors you want to use by following the sensor-specific guides.

    Warning

    We strongly recommend installing all sensor dependencies before starting any quickstarts. Some sensor dependencies require restarting the Isaac ROS Dev container during installation, which will interrupt the quickstart process.

Download Quickstart Assets

  1. Download quickstart data from NGC:

    Make sure required libraries are installed.

    sudo apt-get install -y curl tar
    

    Then, run these commands to download the asset from NGC.

    NGC_ORG="nvidia"
    NGC_TEAM="isaac"
    NGC_RESOURCE="isaac_ros_assets"
    NGC_VERSION="isaac_ros_data_replayer"
    NGC_FILENAME="quickstart.tar.gz"
    
    REQ_URL="https://api.ngc.nvidia.com/v2/resources/$NGC_ORG/$NGC_TEAM/$NGC_RESOURCE/versions/$NGC_VERSION/files/$NGC_FILENAME"
    
    mkdir -p ${ISAAC_ROS_WS}/isaac_ros_assets/${NGC_VERSION} && \
        curl -LO --request GET "${REQ_URL}" && \
        tar -xf ${NGC_FILENAME} -C ${ISAAC_ROS_WS}/isaac_ros_assets/${NGC_VERSION} && \
        rm ${NGC_FILENAME}
    

Build and run isaac_ros_data_replayer

  1. Install the required Debian packages:

sudo apt update
sudo apt-get install -y ros-humble-isaac-ros-data-replayer 
source /opt/ros/humble/setup.bash
  1. Install the required assets:

sudo apt-get install -y ros-humble-isaac-ros-ess-models-install
source /opt/ros/humble/setup.bash
    
ros2 run isaac_ros_ess_models_install install_ess_models.sh --eula
  1. Run the launch file:

ros2 launch isaac_ros_data_replayer data_replayer.launch.py \
    rosbag:=${ISAAC_ROS_WS}/isaac_ros_assets/isaac_ros_data_replayer/quickstart

Replay a single camera

ros2 launch isaac_ros_data_replayer data_replayer.launch.py \
   rosbag:=${ISAAC_ROS_WS}/isaac_ros_assets/isaac_ros_data_replayer/quickstart \
   enabled_stereo_cameras:=front_stereo_camera enabled_fisheye_cameras:=None enable_3d_lidar:=False

Visualize

  1. Open a new terminal inside the Docker container:

    cd ${ISAAC_ROS_WS}/src/isaac_ros_common && \
       ./scripts/run_dev.sh
    
  2. Run RViz to visualize data:

    rviz2
    
    data_replayer_rviz

Data Extraction

  1. Run data extraction:

ros2 run isaac_ros_data_replayer data_extraction.py \
   --rosbag ${ISAAC_ROS_WS}/isaac_ros_assets/isaac_ros_data_replayer/quickstart \
   --camera front_stereo_camera --output ${ISAAC_ROS_WS} \
   --engine_file_path ${ISAAC_ROS_WS}/isaac_ros_assets/models/dnn_stereo_disparity/dnn_stereo_disparity_v4.0.0/ess.engine
  1. Convert rosbag to MP4:

    ros2 run isaac_ros_data_replayer camera_converter.py \
       -i  ${ISAAC_ROS_WS}/isaac_ros_assets/isaac_ros_data_replayer/quickstart \
       -t /front_stereo_camera/left/image_compressed \
       -o ${ISAAC_ROS_WS}/front_stereo_camera_left.mp4
    
  2. Convert MP4 to PNG:

    mkdir ${ISAAC_ROS_WS}/front_stereo_camera_left && \
       ffmpeg -i ${ISAAC_ROS_WS}/front_stereo_camera_left.mp4 -vf fps=30 ${ISAAC_ROS_WS}/front_stereo_camera_left/%05d.png
    

Troubleshooting

Isaac ROS Troubleshooting

For solutions to problems with Isaac ROS, see troubleshooting.

Not all camera frames extracted from recording

Data extraction extracts synchronized camera frames from a recording. If the number of frames from the left and right camera are not equal, then some frames will be ignored to keep the left and right cameras in sync.

API

Usage

ros2 launch isaac_ros_data_replayer data_replayer.launch.py rosbag:=<rosbag>

ROS Launch Arguments

ROS Launch Argument

Default Value

Description

rosbag

None

Path to recording.

enabled_stereo_cameras

front_stereo_camera back_stereo_camera left_stereo_camera right_stereo_camera

Stereo cameras enabled for replay.

enabled_fisheye_cameras

front_fisheye_camera back_fisheye_camera left_fisheye_camera right_fisheye_camera

Fisheye cameras enabled for replay.

enable_3d_lidar

True

Enable 3D lidar for replay.

replay_loop

False

Loop replay.

replay_rate

1.0

Extraction rate; 1.0 for real-time, <1.0 for sub-real-time, >1.0 for super-real-time.

replay_delay

None

Delay to start replay.

replay_additional_args

--disable-keyboard-controls

Additional arguments for replay.

ROS Topics Published

ROS Topic

Interface

Description

/rosout

rcl_interfaces/msg/Log

Console logs.

/tf

tf2_msgs/msg/TFMessage

Movable transforms on the robot.

/tf_static

tf2_msgs/msg/TFMessage

Fixed transforms on the robot.

/front_stereo_camera/left/image_raw

sensor_msgs/msg/Image

Front stereo camera left camera stream.

/front_stereo_camera/left/camera_info

sensor_msgs/msg/CameraInfo

Front stereo camera left camera intrinsics.

/front_stereo_camera/right/image_raw

sensor_msgs/msg/Image

Front stereo camera right camera stream.

/front_stereo_camera/right/camera_info

sensor_msgs/msg/CameraInfo

Front stereo camera right camera intrinsics.

/back_stereo_camera/left/image_raw

sensor_msgs/msg/Image

Back stereo camera left camera stream.

/back_stereo_camera/left/camera_info

sensor_msgs/msg/CameraInfo

Back stereo camera left camera intrinsics.

/back_stereo_camera/right/image_raw

sensor_msgs/msg/Image

Back stereo camera right camera stream.

/back_stereo_camera/right/camera_info

sensor_msgs/msg/CameraInfo

Back stereo camera right camera intrinsics.

/left_stereo_camera/left/image_raw

sensor_msgs/msg/Image

Left stereo camera left camera stream.

/left_stereo_camera/left/camera_info

sensor_msgs/msg/CameraInfo

Left stereo camera left camera intrinsics.

/left_stereo_camera/right/image_raw

sensor_msgs/msg/Image

Left stereo camera right camera stream.

/left_stereo_camera/right/camera_info

sensor_msgs/msg/CameraInfo

Left stereo camera right camera intrinsics.

/right_stereo_camera/left/image_raw

sensor_msgs/msg/Image

Right stereo camera left camera stream.

/right_stereo_camera/left/camera_info

sensor_msgs/msg/CameraInfo

Right stereo camera left camera intrinsics.

/right_stereo_camera/right/image_raw

sensor_msgs/msg/Image

Right stereo camera right camera stream.

/right_stereo_camera/right/camera_info

sensor_msgs/msg/CameraInfo

Right stereo camera right camera intrinsics.

/front_fisheye_camera/left/image_raw

sensor_msgs/msg/Image

Front fisheye camera stream.

/front_fisheye_camera/left/camera_info

sensor_msgs/msg/CameraInfo

Front fisheye camera intrinsics.

/back_fisheye_camera/left/image_raw

sensor_msgs/msg/Image

Back fisheye camera stream.

/back_fisheye_camera/left/camera_info

sensor_msgs/msg/CameraInfo

Back fisheye camera intrinsics.

/left_fisheye_camera/left/image_raw

sensor_msgs/msg/Image

Left fisheye camera stream.

/left_fisheye_camera/left/camera_info

sensor_msgs/msg/CameraInfo

Left fisheye camera intrinsics.

/right_fisheye_camera/left/image_raw

sensor_msgs/msg/Image

Right fisheye camera stream.

/right_fisheye_camera/left/camera_info

sensor_msgs/msg/CameraInfo

Right fisheye camera intrinsics.

/front_2d_lidar/scan

sensor_msgs/msg/LaserScan

Front 2D lidar scan.

/back_2d_lidar/scan

sensor_msgs/msg/LaserScan

Back 2D lidar scan.

/front_3d_lidar/lidar_points

sensor_msgs/msg/PointCloud2

Front 3D lidar point cloud.

/front_stereo_imu/imu

sensor_msgs/msg/Imu

Front stereo camera inertial measurement unit.

/chassis/imu

sensor_msgs/msg/Imu

Chassis inertial measurement unit.

/chassis/ticks

isaac_ros_nova_interfaces/msg/EncoderTicks

Chassis encoder count.

/chassis/odom

nav_msgs/msg/Odometry

Chassis odometry.

/chassis/battery_state

sensor_msgs/msg/BatteryState

Chassis battery state.

Usage

ros2 run isaac_ros_data_replayer data_extraction.py --rosbag <rosbag> --camera <camera> --output <output>

ROS Run Arguments

ROS Run Argument

Default Value

Description

--rosbag

None

Path to recording.

--camera

None

Camera to extract i.e. front_stereo_camera.

--output

None

Directory to store extracted data.

--output_width

960

Rectified image width.

--output_height

576

Rectified image height.

--min_disparity

3.0

Minimum disparity value for normalization.

--max_disparity

200.0

Maximum disparity value for normalization.

--threshold

0.0

ESS threshold.

--engine_file_path

${ISAAC_ROS_WS}/src/isaac_ros_dnn_stereo_depth/resources/ess.engine

ESS engine file path.

ROS Topics Subscribed

ROS Topic

Interface

Description

/<camera>/left/image_compressed

sensor_msgs/msg/CompressedImage

Left camera stream.

/<camera>/left/camera_info

sensor_msgs/msg/CameraInfo

Left camera intrinsics.

/<camera>/right/image_compressed

sensor_msgs/msg/CompressedImage

Right camera stream.

/<camera>/right/camera_info

sensor_msgs/msg/CameraInfo

Right camera intrinsics.