isaac_ros_data_validation
Source code on GitHub.
Overview
Tools to validate data from Nova. The isaac_ros_data_validation
package primarily contains a utility to check
ROSbags generated by isaac_ros_nova_recorder
for frame drops, desynchronization, and other issues.
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.2 https://github.com/NVIDIA-ISAAC-ROS/isaac_ros_common.git isaac_ros_common
(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 Isaac ROS Dev container during installation, which will interrupt the quickstart process.
Download Quickstart Assets
Download quickstart data from NGC:
Make sure required libraries are installed.
sudo apt-get install -y curl jq tar
Then, run these commands to download the asset from NGC:
NGC_ORG="nvidia" NGC_TEAM="isaac" PACKAGE_NAME="isaac_ros_data_validation" NGC_RESOURCE="isaac_ros_data_validation_assets" NGC_FILENAME="quickstart.tar.gz" MAJOR_VERSION=3 MINOR_VERSION=2 VERSION_REQ_URL="https://catalog.ngc.nvidia.com/api/resources/versions?orgName=$NGC_ORG&teamName=$NGC_TEAM&name=$NGC_RESOURCE&isPublic=true&pageNumber=0&pageSize=100&sortOrder=CREATED_DATE_DESC" AVAILABLE_VERSIONS=$(curl -s \ -H "Accept: application/json" "$VERSION_REQ_URL") LATEST_VERSION_ID=$(echo $AVAILABLE_VERSIONS | jq -r " .recipeVersions[] | .versionId as \$v | \$v | select(test(\"^\\\\d+\\\\.\\\\d+\\\\.\\\\d+$\")) | split(\".\") | {major: .[0]|tonumber, minor: .[1]|tonumber, patch: .[2]|tonumber} | select(.major == $MAJOR_VERSION and .minor <= $MINOR_VERSION) | \$v " | sort -V | tail -n 1 ) if [ -z "$LATEST_VERSION_ID" ]; then echo "No corresponding version found for Isaac ROS $MAJOR_VERSION.$MINOR_VERSION" echo "Found versions:" echo $AVAILABLE_VERSIONS | jq -r '.recipeVersions[].versionId' else mkdir -p ${ISAAC_ROS_WS}/isaac_ros_assets && \ FILE_REQ_URL="https://api.ngc.nvidia.com/v2/resources/$NGC_ORG/$NGC_TEAM/$NGC_RESOURCE/\ versions/$LATEST_VERSION_ID/files/$NGC_FILENAME" && \ curl -LO --request GET "${FILE_REQ_URL}" && \ tar -xf ${NGC_FILENAME} -C ${ISAAC_ROS_WS}/isaac_ros_assets && \ rm ${NGC_FILENAME} fi
Build isaac_ros_data_validation
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 update
sudo apt-get install -y ros-humble-isaac-ros-data-validation
Clone this repository under
${ISAAC_ROS_WS}/src
:cd ${ISAAC_ROS_WS}/src && \ git clone -b release-3.2 https://github.com/NVIDIA-ISAAC-ROS/isaac_ros_nova.git isaac_ros_nova
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:sudo apt-get update
rosdep update && rosdep install --from-paths ${ISAAC_ROS_WS}/src/isaac_ros_nova/isaac_ros_data_validation --ignore-src -y
Build the package from source:
cd ${ISAAC_ROS_WS} && \ colcon build --symlink-install --packages-up-to isaac_ros_data_validation --base-paths ${ISAAC_ROS_WS}/src/isaac_ros_nova/isaac_ros_data_validation
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
Run Launch File
Continuing inside the Docker container, run data validation:
python -m isaac_ros_data_validation.summarize_bag ${ISAAC_ROS_WS}/isaac_ros_assets/isaac_ros_data_validation/quickstart
This will generate a report. In the example below, the system was experiencing heavy load during startup that resulted in frame drops, but it recovered and recorded data normally in the second half of the recording.
======================================================== example.mcap ======================================================== Camera Drop Q Score: 97.7 Camera Bucket Q Score: 75.0 Intra Camera Sync Q score: 87.5 Hesai Drop Q Score: 100.0 Hawk Imu Drop Q Score: 96.8 Camera Drop Table [xxxxxxxxxxxxxxxx................................................] /back_stereo_camera/left [...xx..xxx.x....................................................] /back_stereo_camera/right [..xx..xxx.x.....................................................] /front_stereo_camera/left [...x...xx..xxxxx................................................] /front_stereo_camera/right [xx..xx.xxx......................................................] /left_stereo_camera/left [.xxx...xxxxx....................................................] /left_stereo_camera/right [xxx...xxxx......................................................] /right_stereo_camera/left [.xxx...xx.xx....................................................] /right_stereo_camera/right [..xxx...xx.xx...................................................] Intra Camera Sync Table [xxxxxxxx........................................................] /back_stereo_camera/camera_info [................................................................] /back_stereo_camera/image_compressed [xx..............................................................] /front_stereo_camera/camera_info [................................................................] /front_stereo_camera/image_compressed [xxxxxxxx........................................................] /left_stereo_camera/camera_info [................................................................] /left_stereo_camera/image_compressed [xx..............................................................] /right_stereo_camera/camera_info [................................................................] /right_stereo_camera/image_compressed [................................................................] Hesai Drop Table [................................................................] Camera Imu Drop Table [.............xxxxxxx............................................] Clock Sync Table [................................................................] Topics: /tf_static | frames_captured: 5 /robot_description | frames_captured: 1 /front_3d_lidar/lidar_packets | frames_captured: 338 /correlated_timestamp | frames_captured: 30 /front_stereo_camera/left/camera_info | frames_captured: 798 /front_stereo_camera/right/camera_info | frames_captured: 798 /front_stereo_imu/imu | frames_captured: 2507 /back_stereo_camera/left/camera_info | frames_captured: 781 /back_stereo_camera/right/camera_info | frames_captured: 781 /front_stereo_camera/left/image_compressed | frames_captured: 754 /left_stereo_camera/left/camera_info | frames_captured: 741 /left_stereo_camera/right/camera_info | frames_captured: 741 /right_stereo_camera/left/camera_info | frames_captured: 699 /right_stereo_camera/right/camera_info | frames_captured: 699 /right_stereo_camera/right/image_compressed | frames_captured: 699 /back_stereo_camera/left/image_compressed | frames_captured: 698 /left_stereo_camera/left/image_compressed | frames_captured: 689 /back_stereo_camera/right/image_compressed | frames_captured: 686 /right_stereo_camera/left/image_compressed | frames_captured: 684 /left_stereo_camera/right/image_compressed | frames_captured: 673 /front_stereo_camera/right/image_compressed | frames_captured: 668 /back_stereo_camera/camera_info/stereo_sync: - Num Desyncs : 0 - Percent Desynced: 0.0 - Mean Difference : 0.0 - Max Difference: 0.0 - Desync Table: [................................................................] /back_stereo_camera/image_compressed/stereo_sync: - Num Desyncs : 12 - Percent Desynced: 1.7191977077363898 - Mean Difference : 3724718.212034384 - Max Difference: 399980032.0 - Desync Table: [xx..............................................................] /back_stereo_camera/left: - Percent Dropped: 2.1037868162692845% - Number Dropped: 15 - Mean Frequency: 29.286435982250328 - Drop Table: [...xx..xxx.x....................................................] - Frames Captured: 698 - Total Jitter: 0.8195778173122901 ms - Jitter Excluding Drops: 0.006763697413371677 ms - Largest Frame Diff: 100.004096 ms /back_stereo_camera/right: - Percent Dropped: 2.1398002853067046% - Number Dropped: 15 - Mean Frequency: 29.274213019715965 - Drop Table: [..xx..xxx.x.....................................................] - Frames Captured: 686 - Total Jitter: 0.8338289985401454 ms - Jitter Excluding Drops: 0.006776051664182114 ms - Largest Frame Diff: 100.004096 ms /correlated_timestamp: - Percent Dropped: 3.225806451612903% - Number Dropped: 1 - Mean Frequency: 0.9954828957139445 - Drop Table: [..x.............................................................] - Frames Captured: 30 - Total Jitter: 41.53064496551724 ms - Jitter Excluding Drops: 23.856770285714287 ms - Largest Frame Diff: 1044.198489 ms /front_3d_lidar/lidar_packets: - Percent Dropped: 0.0% - Frames Dropped: 0 - Mean Frequency: 10.000164921414225 - Drop Table: [................................................................] - Frames Captured: 338 - Total Jitter: 0.009443133531157269 ms - Jitter Excluding Drops: 0.009443133531157269 ms /front_stereo_camera/camera_info/stereo_sync: - Num Desyncs : 0 - Percent Desynced: 0.0 - Mean Difference : 0.0 - Max Difference: 0.0 - Desync Table: [................................................................] /front_stereo_camera/image_compressed/stereo_sync: - Num Desyncs : 86 - Percent Desynced: 11.405835543766578 - Mean Difference : 167369934.76923078 - Max Difference: 2899928064.0 - Desync Table: [xxxxxxxx........................................................] /front_stereo_camera/left: - Percent Dropped: 2.33160621761658% - Number Dropped: 18 - Mean Frequency: 29.26238298615806 - Drop Table: [...x...xx..xxxxx................................................] - Frames Captured: 754 - Total Jitter: 0.8476621230633017 ms - Jitter Excluding Drops: 0.006719420289854367 ms - Largest Frame Diff: 100.00384 ms /front_stereo_camera/right: - Percent Dropped: 2.4817518248175183% - Number Dropped: 17 - Mean Frequency: 29.212402433133597 - Drop Table: [xx..xx.xxx......................................................] - Frames Captured: 668 - Total Jitter: 0.9061453273363311 ms - Jitter Excluding Drops: 0.0067258658474135275 ms - Largest Frame Diff: 100.00384 ms /front_stereo_imu/imu: - Percent Dropped: 0.03151176705225369% - Frames Dropped: 79 - Mean Frequency: 94.54147253627838 - Drop Table: [.............xxxxxxx............................................] - Frames Captured: 2507 - Total Jitter: 0.5773685682362331 ms - Jitter Excluding Drops: 0.017721011948908114 ms /left_stereo_camera/camera_info/stereo_sync: - Num Desyncs : 0 - Percent Desynced: 0.0 - Mean Difference : 0.0 - Max Difference: 0.0 - Desync Table: [................................................................] /left_stereo_camera/image_compressed/stereo_sync: - Num Desyncs : 16 - Percent Desynced: 2.3222060957910013 - Mean Difference : 6579357.538461538 - Max Difference: 533315840.0 - Desync Table: [xx..............................................................] /left_stereo_camera/left: - Percent Dropped: 2.545968882602546% - Number Dropped: 18 - Mean Frequency: 29.153263081074567 - Drop Table: [.xxx...xxxxx....................................................] - Frames Captured: 689 - Total Jitter: 0.9754047751937976 ms - Jitter Excluding Drops: 0.006660825396824694 ms - Largest Frame Diff: 100.004096 ms /left_stereo_camera/right: - Percent Dropped: 2.6049204052098407% - Number Dropped: 18 - Mean Frequency: 29.133662758664197 - Drop Table: [xxx...xxxx......................................................] - Frames Captured: 673 - Total Jitter: 0.9984822857142849 ms - Jitter Excluding Drops: 0.00667330081300743 ms - Largest Frame Diff: 100.004096 ms /right_stereo_camera/camera_info/stereo_sync: - Num Desyncs : 0 - Percent Desynced: 0.0 - Mean Difference : 0.0 - Max Difference: 0.0 - Desync Table: [................................................................] /right_stereo_camera/image_compressed/stereo_sync: - Num Desyncs : 0 - Percent Desynced: 0.0 - Mean Difference : 0.0 - Max Difference: 0.0 - Desync Table: [................................................................] /right_stereo_camera/left: - Percent Dropped: 2.005730659025788% - Number Dropped: 14 - Mean Frequency: 29.356030086938333 - Drop Table: [.xxx...xx.xx....................................................] - Frames Captured: 684 - Total Jitter: 0.7386018545632008 ms - Jitter Excluding Drops: 0.0066999402985067616 ms - Largest Frame Diff: 100.004096 ms /right_stereo_camera/right: - Percent Dropped: 1.9635343618513323% - Number Dropped: 14 - Mean Frequency: 29.36959810115494 - Drop Table: [..xxx...xx.xx...................................................] - Frames Captured: 699 - Total Jitter: 0.7228756599808971 ms - Jitter Excluding Drops: 0.006702341605838715 ms - Largest Frame Diff: 100.004096 ms clock_sync: - Num Desyncs : 0 - Percent Desynced: 0.0 - Mean Difference : 2574.8 ns - Max Difference: 9520 ns - Mean PHC TSC Difference: 4765.2 ns - Mean PHC SYS Difference: 384.4 ns - Max PHC TSC Difference: 9520 ns - Max PHC SYS Difference: 1263 ns - Desync Table: [................................................................]
The drop tables use an “X” table to show where in the recording a problem was found, in there is an issue with the batter_state not publishing at a constant rate.
Q Scores File
Data Validation generates a q_scores.json
file within each rosbag. This file contains the Q scores calculated
during data validation and some metadata for the recording. You can also find these Q scores at the top of the printed report.
Example q_scores.json
file:
{
"robotId": "carter-v24-b7",
"config": "nova-carter_hawk-4",
"qscore_camera_buckets": 75.0,
"qscore_camera_intra_sync": 87.5,
"qscore_camera_drops": 97.7,
"qscore_hesai_drops": 100.0,
"qscore_hawk_imu_drops": 96.8
}
If the MCAP file includes information about the robot ID and recording configuration, their values will be assigned to their respective metadata fields. Otherwise, the default value is “unknown”.
The Camera Bucket Q Score is the percentage of equally spaced buckets on the timeline that have no data loss. The Intra Camera Sync Q Score is the percentage of equally spaced buckets on the timeline that have no timestamp desynchronization.
The Hesai Drop Q Score is 1 - (percent of indices dropped from the 3D lidar) and the Hawk Imu Drop Q Score is 1 - (percent of indices dropped from the front stereo IMU). Similarly, the Camera Drop Q Score is 1 - (frames dropped / total frames).
For example, if the system drops 1 frame every second, you could get a Camera Drop Q Score of 90% and a Camera Bucket Q Score of 0%. This is because there are a lot of frames captured every second so dropping 1 frame per second isn’t much over the entirety of the recording. However, since frames are dropped consistently, there would probably not be any “buckets” of time where there are no drops.
A value of -1.0 means data validation was not able to calculate the Q score. For example, if the configuration used to record the rosbag does not include any Hesai sensors, the value of the Hesai Drop Q Score would be -1.0. A Q score may also be -1.0 if there was an error when calculating the Q score.
If you want to start doing further analysis you can look at the
isaac_ros_data_validation/example
directory. read_mcap_example.py
is a good place
to start or ess_disparities_example.py
if you have a db3 file.
Troubleshooting
Isaac ROS Troubleshooting
For solutions to problems with Isaac ROS, see troubleshooting.
API
Usage
python -m isaac_ros_data_validation.summarize_bag input_file
Command Line Arguments
Command Line Argument |
Default Value |
Description |
---|---|---|
|
None |
Path to rosbag. |
|
|
Verbosity level. Can be |