Learn how to use this package by watching our on-demand webinar: Pinpoint, 250 fps, ROS 2 Localization with vSLAM on Jetson
This repository provides a high-performance, best-in-class ROS 2 package for VSLAM (visual simultaneous localization and mapping). This package uses a stereo camera with an IMU to estimate odometry as an input to navigation. It is GPU accelerated to provide real-time, low-latency results in a robotics application. VSLAM provides an additional odometry source for mobile robots (ground based) and can be the primary odometry source for drones.
VSLAM provides a method for visually estimating the position of a robot relative to its start position, known as VO (visual odometry). This is particularly useful in environments where GPS is not available (such as indoors) or intermittent (such as urban locations with structures blocking line of sight to GPS satellites). This method is designed to use left and right stereo camera frames and an IMU (inertial measurement unit) as input. It uses input stereo image pairs to find matching key points in the left and right images; using the baseline between the left and right camera, it can estimate the distance to the key point. Using two consecutive input stereo image pairs, VSLAM can track the 3D motion of key points between the two consecutive images to estimate the 3D motion of the camera--which is then used to compute odometry as an output to navigation. Compared to the classic approach to VSLAM, this method uses GPU acceleration to find and match more key points in real-time, with fine tuning to minimize overall reprojection error.
Key points depend on distinctive features in the left and right camera image that can be repeatedly detected with changes in size, orientation, perspective, lighting, and image noise. In some instances, the number of key points may be limited or entirely absent; for example, if the camera field of view is only looking at a large solid colored wall, no key points may be detected. If there are insufficient key points, this module uses motion sensed with the IMU to provide a sensor for motion, which, when measured, can provide an estimate for odometry. This method, known as VIO (visual-inertial odometry), improves estimation performance when there is a lack of distinctive features in the scene to track motion visually.
SLAM (simultaneous localization and mapping) is built on top of VIO, creating a map of key points that can be used to determine if an area is previously seen. When VSLAM determines that an area is previously seen, it reduces uncertainty in the map estimate, which is known as loop closure. VSLAM uses a statistical approach to loop closure that is more compute efficient to provide a real time solution, improving convergence in loop closure.
There are multiple methods for estimating odometry as an input to navigation. None of these methods are perfect; each has limitations because of systematic flaws in the sensor providing measured observations, such as missing LIDAR returns absorbed by black surfaces, inaccurate wheel ticks when the wheel slips on the ground, or a lack of distinctive features in a scene limiting key points in a camera image. A practical approach to tracking odometry is to use multiple sensors with diverse methods so that systemic issues with one method can be compensated for by another method. With three separate estimates of odometry, failures in a single method can be detected, allowing for fusion of the multiple methods into a single higher quality result. VSLAM provides a vision- and IMU-based solution to estimating odometry that is different from the common practice of using LIDAR and wheel odometry. VSLAM can even be used to improve diversity, with multiple stereo cameras positioned in different directions to provide multiple, concurrent visual estimates of odometry.
To learn more about VSLAM, refer to the Elbrus SLAM documentation.
VSLAM is a best-in-class package with the lowest translation and rotational error as measured on KITTI Visual Odometry / SLAM Evaluation 2012 for real-time applications.
Method | Runtime | Translation | Rotation | Platform |
---|---|---|---|---|
VSLAM | 0.007s | 0.94% | 0.0019 deg/m | Jetson AGX Xavier aarch64 |
ORB-SLAM2 | 0.06s | 1.15% | 0.0027 deg/m | 2 cores @ >3.5 Ghz x86_64 |
In addition to results from standard benchmarks, we test loop closure for VSLAM on sequences of over 1000 meters, with coverage for indoor and outdoor scenes.
The following table summarizes the per-platform performance statistics of sample graphs that use this package, with links included to the full benchmark output. These benchmark configurations are taken from the Isaac ROS Benchmark collection, based on the ros2_benchmark
framework.
Sample Graph | Input Size | AGX Orin | Orin NX | Orin Nano 8GB | x86_64 w/ RTX 3060 Ti |
---|---|---|---|---|---|
Visual SLAM Node | 720p | 228 fps 36 ms |
124 fps 39 ms |
116 fps 85 ms |
238 fps 50 ms |
For commercial support and access to source code, please contact NVIDIA.
- Isaac ROS Visual SLAM
Update 2022-03-23: Update Elbrus library and performance improvements
This package is designed and tested to be compatible with ROS 2 Humble running on Jetson or an x86_64 system with an NVIDIA GPU.
Note: Versions of ROS 2 earlier than Humble are not supported. This package depends on specific ROS 2 implementation features that were only introduced beginning with the Humble release.
Platform | Hardware | Software | Notes |
---|---|---|---|
Jetson | Jetson Orin Jetson Xavier |
JetPack 5.1.1 | For best performance, ensure that power settings are configured appropriately. |
x86_64 | NVIDIA GPU | Ubuntu 20.04+ CUDA 11.8+ |
To simplify development, we strongly recommend leveraging the Isaac ROS Dev Docker images by following these steps. This will streamline your development environment setup with the correct versions of dependencies on both Jetson and x86_64 platforms.
Note: All Isaac ROS Quickstarts, tutorials, and examples have been designed with the Isaac ROS Docker images as a prerequisite.
This section describes the coordinate frames that are involved in the VisualSlamNode
. The frames discussed below are oriented as follows:
input_base_frame
: The name of the frame used to calculate transformation between baselink and left camera. The default value is empty (''), which means the value ofbase_frame_
will be used. Ifinput_base_frame_
andbase_frame_
are both empty, the left camera is assumed to be in the robot's center.input_left_camera_frame
: The frame associated with left eye of the stereo camera. Note that this is not the same as the optical frame. The default value is empty (''), which means the left camera is in the robot's center andleft_pose_right
will be calculated from the CameraInfo message.input_right_camera_frame
: The frame associated with the right eye of the stereo camera. Note that this is not the same as the optical frame. The default value is empty (''), which means left and right cameras have identity rotation and are horizontally aligned, soleft_pose_right
will be calculated from CameraInfo.input_imu_frame
: The frame associated with the IMU sensor (if available). It is used to calculateleft_pose_imu
.
-
Set up your development environment by following the instructions here.
Note:
${ISAAC_ROS_WS}
is defined to point to either/ssd/workspaces/isaac_ros-dev/
or~/workspaces/isaac_ros-dev/
. -
Clone this repository and its dependencies under
${ISAAC_ROS_WS}/src
.cd ${ISAAC_ROS_WS}/src git clone https://github.com/NVIDIA-ISAAC-ROS/isaac_ros_visual_slam git clone https://github.com/NVIDIA-ISAAC-ROS/isaac_ros_common git clone https://github.com/NVIDIA-ISAAC-ROS/isaac_ros_nitros
-
[Terminal 1] Launch the Docker container
cd ${ISAAC_ROS_WS}/src/isaac_ros_common && \ ./scripts/run_dev.sh ${ISAAC_ROS_WS}
-
[Terminal 1] Inside the container, build and source the workspace:
cd /workspaces/isaac_ros-dev && \ colcon build --symlink-install && \ source install/setup.bash
(Optional) Run tests to verify complete and correct installation:
colcon test --executor sequential
Run the following launch files in the current terminal (Terminal 1):
ros2 launch isaac_ros_visual_slam isaac_ros_visual_slam.launch.py
-
[Terminal 2] Attach another terminal to the running container for Rviz2
Attach another terminal to the running container for RViz2.
cd ${ISAAC_ROS_WS}/src/isaac_ros_common && \ ./scripts/run_dev.sh ${ISAAC_ROS_WS}
From this second terminal, run Rviz2 to display the output:
source /workspaces/isaac_ros-dev/install/setup.bash && \ rviz2 -d src/isaac_ros_visual_slam/isaac_ros_visual_slam/rviz/default.cfg.rviz
If you are SSH-ing in from a remote machine, the Rviz2 window should be forwarded to your remote machine.
-
[Terminal 3] Attach the 3rd terminal to start the rosbag
cd ${ISAAC_ROS_WS}/src/isaac_ros_common && \ ./scripts/run_dev.sh ${ISAAC_ROS_WS}
Run the rosbag file to start the demo.
source /workspaces/isaac_ros-dev/install/setup.bash && \ ros2 bag play src/isaac_ros_visual_slam/isaac_ros_visual_slam/test/test_cases/rosbags/small_pol_test/
-
Result:
Rviz should start displaying the point clouds and poses like below:
Note: By default, IMU data is ignored. To use IMU data in Isaac ROS Visual Slam, please set
enable_imu
param in your launch file toTrue
. See example below.
To continue your exploration, check out the following suggested examples:
To customize your development environment, reference this guide.
ros2 launch isaac_ros_visual_slam isaac_ros_visual_slam.launch.py
ROS Parameter | Type | Default | Description |
---|---|---|---|
denoise_input_images |
bool |
false |
If enabled, input images are denoised. It can be enabled when images are noisy because of low-light conditions. |
rectified_images |
bool |
true |
Flag to mark if the incoming images are rectified or raw. |
enable_imu |
bool |
false |
If enabled, IMU data is used. |
enable_debug_mode |
bool |
false |
If enabled, a debug dump (image frames, timestamps, and camera info) is saved on to the disk at the path indicated by debug_dump_path |
debug_dump_path |
std::string |
/tmp/elbrus |
The path to the directory to store the debug dump data. |
input_base_frame |
std::string |
"" |
Name of the frame (baselink) to calculate transformation between the baselink and the left camera. Default is empty, which means the value of the base_frame will be used. If input_base_frame and base_frame are both empty, the left camera is assumed to be in the robot's center. |
input_left_camera_frame |
std::string |
"" |
The name of the left camera frame. the default value is empty, which means the left camera is in the robot's center and left_pose_right will be calculated from CameraInfo. |
input_right_camera_frame |
std::string |
"" |
The name of the right camera frame. The default value is empty, which means left and right cameras have identity rotation and are horizontally aligned. left_pose_right will be calculated from CameraInfo. |
input_imu_frame |
std::string |
imu |
Defines the name of the IMU frame used to calculate left_camera_pose_imu . |
gravitational_force |
std::vector<double> |
{0.0, 0, -9.8} |
The initial gravity vector defined in the odometry frame. If the IMU sensor is not parallel to the floor, update all the axes with appropriate values. |
publish_tf |
bool |
true |
If enabled, it will publish output frame hierarchy to TF tree. |
map_frame |
std::string |
map |
The frame name associated with the map origin. |
odom_frame |
std::string |
odom |
The frame name associated with the odometry origin. |
base_frame |
std::string |
base_link |
The frame name associated with the robot. |
enable_observations_view |
bool |
false |
If enabled, 2D feature pointcloud will be available for visualization. |
enable_landmarks_view |
bool |
false |
If enabled, landmark pointcloud will be available for visualization. |
enable_slam_visualization |
bool |
false |
Main flag to enable or disable visualization. |
enable_localization_n_mapping |
bool |
true |
If enabled, SLAM mode is on. If diabled, only Visual Odometry is on. |
path_max_size |
int |
1024 |
The maximum size of the buffer for pose trail visualization. |
publish_odom_to_base_tf |
bool |
true |
Enable tf broadcaster for odom_frame->base_frame transform. |
publish_map_to_odom_tf |
bool |
true |
Enable tf broadcaster for map_frame->odom_frame transform. |
invert_odom_to_base_tf |
bool |
false |
Invert the odom_frame->base_frame transform before broadcasting to the tf tree. |
invert_map_to_odom_tf |
bool |
false |
Invert the map_frame->odom_frame transform before broadcasting to the tf tree. |
map_frame |
std::string |
map |
String name for the map_frame. |
odom_frame |
std::string |
odom |
String name for the odom_frame. |
base_frame |
std::string |
base_link |
String name for the base_frame. |
override_publishing_stamp |
bool |
false |
Override timestamp received from the left image with the timetsamp from rclcpp::Clock. |
msg_filter_queue_size |
int |
100 |
Image + Camera Info Synchronizer message filter queue size. |
image_qos |
std::string |
SENSOR_DATA |
QoS profile for the left and right image subscribers. |
ROS Topic | Interface | Description |
---|---|---|
/stereo_camera/left/image |
sensor_msgs/Image |
The image from the left eye of the stereo camera in grayscale. |
/stereo_camera/left/camera_info |
sensor_msgs/CameraInfo |
CameraInfo from the left eye of the stereo camera. |
/stereo_camera/right/image |
sensor_msgs/Image |
The image from the right eye of the stereo camera in grayscale. |
/stereo_camera/right/camera_info |
sensor_msgs/CameraInfo |
CameraInfo from the right eye of the stereo camera. |
visual_slam/imu |
sensor_msgs/Imu |
Sensor data from the IMU(optional). |
ROS Topic | Interface | Description |
---|---|---|
visual_slam/tracking/odometry |
nav_msgs/Odometry |
Odometry messages for the base_link . |
visual_slam/tracking/vo_pose_covariance |
geometry_msgs/PoseWithCovarianceStamped |
Current pose with covariance of the base_link . |
visual_slam/tracking/vo_pose |
geometry_msgs/PoseStamped |
Current pose of the base_link . |
visual_slam/tracking/slam_path |
nav_msgs/Path |
Trail of poses generated by SLAM. |
visual_slam/tracking/vo_path |
nav_msgs/Path |
Trail of poses generated by pure Visual Odometry. |
visual_slam/status |
isaac_ros_visual_slam_interfaces/VisualSlamStatus |
Status message for diagnostics. |
ROS Service | Interface | Description |
---|---|---|
visual_slam/reset |
isaac_ros_visual_slam_interfaces/Reset |
A service to reset the node. |
visual_slam/get_all_poses |
isaac_ros_visual_slam_interfaces/GetAllPoses |
A service to get the series of poses for the path traversed. |
visual_slam/set_odometry_pose |
isaac_ros_visual_slam_interfaces/SetOdometryPose |
A service to set the pose of the odometry frame. |
ROS Action | Interface | Description |
---|---|---|
visual_slam/save_map |
isaac_ros_visual_slam_interfaces/SaveMap |
An action to save the landmarks and pose graph into a map and onto the disk. |
visual_slam/load_map_and_localize |
isaac_ros_visual_slam_interfaces/LoadMapAndLocalize |
An action to load the map from the disk and localize within it given a prior pose. |
For solutions to problems with Isaac ROS, please check here.
-
If the target frames in rviz are being updated at a lower rate than the input image rate:
-
Check if the input image frame rate is equal to the value set in the launch file by opening a new terminal and running the command
ros2 topic hz --window 100 <image_topic_name>
-
-
If RViz is not showing the poses, check the Fixed Frame value.
-
If you are seeing
Tracker is lost.
messages frequently, it could be caused by the following issues:- Fast motion causing the motion blur in the frames
- Low-lighting conditions.
- The wrong
camerainfo
is being published.
-
For better performance:
- Increase the capture framerate from the camera to yield a better tracking result.
- If input images are noisy, you can use the
denoise_input_images
flag in the node.
-
For RealSense cameras-
- The firmware of the RealSense camera is 5.14.0 or newer. Check the RealSense firmware-update-tool page for details on how to check the version and update the camera firmware.
- You are using the 4.51.1 tagged release for the realsense-ros package.
- You are using the parameters set in the RealSense tutorial launch file
- If the pose estimate frames in RViz is drifting from actual real-world poses and you see white dots on nearby objects(refer to the screenshot below), this means that the emitter of the RealSense camera is on and it needs to be turned off.
- Left and right images being published are not compressed or encoded. Isaac ROS Visual Slam expects raw images.
Date | Changes |
---|---|
2023-04-05 | Update Elbrus library and performance improvements |
2022-10-19 | Updated OSS licensing |
2022-08-31 | Update to be compatible with JetPack 5.0.2 |
2022-06-30 | Support for ROS 2 Humble |
2022-03-17 | Documentation update for new features |
2022-03-11 | Renamed to isaac_ros_visual_slam |
2021-11-15 | Isaac Sim HIL documentation update |
2021-10-20 | Initial release |