What are the camera requirements for testing mapping and localization using the isaac_ros_visual_slam package? Is it possible to use a single RGB-D camera for mapping and localization tests, and how should it be configured?
Hello @3061069227,
Thanks for posting in the forum!
If you would like to use the isaac_ros_visual_slam package, you can reference this page. This method is designed to use multiple stereo camera frames and an IMU (inertial measurement unit) as input. It finds matching key points in stereo image pairs and uses the baseline between the cameras to estimate the distance to each key point. Therefore, a stereo camera with an IMU is the preferred option if you have one available. You can check here for camera system requirement and QuickStart guide.
I am currently testing version 3.2 of isaac_ros_visual_slam and have run into some frustrating issues. What kind of performance should I aim for when debugging isaac_ros_visual_slam? Is there any reference? Also, I don’t quite understand the meaning of some of the parameters. Is there a more detailed tutorial that can serve as a reference or guide?
When debugging isaac_ros_visual_slam, you could first aim for stable image and pose rates.
You can check these using:
ros2 topic hz /visual_slam/image_0
ros2 topic hz /visual_slam/tracking/vo_pose
ros2 topic hz /visual_slam/tracking/odometry
This will help you verify if the topics are running at the expected rates.
Additionally, make sure the image and IMU timestamp deltas stay well below the image_jitter_threshold_ms and imu_jitter_threshold_ms parameters most of the time.
As for more details on parameter meanings, please refer here.
How does the `isaac_ros_visual_slam` node publish map, odom, and base_link? What are the underlying assumptions? Does it assume that there is already a transformation from base_link to camera_link? The input is in the camera’s optical frame coordinate system, while the node publishes map->odom->base_link. The problem I’m facing is that the directions and positions of the camera optical frame and the IMU frame are different from camera_link. However, my camera driver provides a transformation from the optical frame to camera_link. When I create a map, I see multiple layers of point clouds for the same wall. I suspect this might be due to incorrect coordinate transformations. Could you please provide guidance? Thank you very much!
The node publishes a TF chain: map -> odom -> base_frame when both publish_map_to_odom_tf and publish_odom_to_base_tf are set to true. Typically, base_frame refers to base_link, and it is assumed that all cameras are rigidly mounted to this frame, so the transforms between base_frame and the camera optical frames can be considered static. For more details, please refer to the coordinate frames documentation.
You must provide a consistent static TF tree linking:
base_frame/input_base_frame- Camera frames (
input_left_camera_frame,input_right_camera_frame) - IMU frame (
input_imu_frame)
Those transforms must exist and be valid in TF at runtime, as the node does not calibrate or infer them.
You could verify with ros2 run tf2_tools view_frames to check if you get a single tree, and that no other node is also publishing map->odom or odom->base_link.
Alternatively, you could check individual transforms with:
ros2 run tf2_ros tf2_echo <source frame> <target frame>
# SPDX-FileCopyrightText: NVIDIA CORPORATION & AFFILIATES
# Copyright (c) 2021-2024 NVIDIA CORPORATION & AFFILIATES. All rights reserved.
#
# Licensed under the Apache License, Version 2.0 (the “License”);
# you may not use this file except in compliance with the License.
# You may obtain a copy of the License at
#
# Apache License, Version 2.0 | Apache Software Foundation
#
# Unless required by applicable law or agreed to in writing, software
# distributed under the License is distributed on an “AS IS” BASIS,
# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
# See the License for the specific language governing permissions and
# limitations under the License.
#
# SPDX-License-Identifier: Apache-2.0
import launch
from launch_ros.actions import ComposableNodeContainer, Node
from launch_ros.descriptions import ComposableNode
from launch.actions import TimerAction
def generate_launch_description():
"""Launch file to bring up visual slam node standalone."""
visual_slam_node = ComposableNode(
name='visual_slam_node',
package='isaac_ros_visual_slam',
plugin='nvidia::isaac_ros::visual_slam::VisualSlamNode',
parameters=\[{
\# 相机系统参数
'num_cameras': 2, # 相机数量(立体相机)
'multicam_mode': 1, # 多相机模式(0:顺序,1:同步,2:自适应)
'min_num_images': 2, # 最小图像数与num_cameras保持一致
'sync_matching_threshold_ms': 10.0, # 同步匹配阈值(单位:ms)
\# 图像预处理参数
'img_mask_top': 0, # 忽略顶部多少行像素
'img_mask_bottom': 0, # 忽略底部多少行像素
'img_mask_left': 0, # 忽略左部多少列像素
'img_mask_right': 0, # 忽略右部多少列像素
'enable_image_denoising': False, # 启用图像降噪,增加计算开销,可能丢失细节
'rectified_images': True, # 输入图像是否已经校正过,不开启节点将使用相机标定参数进行校正
\# SLAM算法核心参数
'enable_ground_constraint_in_odometry': False, # 在视觉里程计中启用地面约束(建议先关闭,避免跳变)
'enable_ground_constraint_in_slam': True, # 在完整SLAM优化中启用地面约束
'enable_localization_n_mapping': True, # 同时启用定位和建图, 否则只进行定位
\# IMU融合参数
'enable_imu_fusion': True, # 启用IMU融合
'debug_imu_mode': False, # IMU调试模式,启用额外的IMU数据记录和验证
'gyro_noise_density': 0.000032, # 陀螺仪噪声密度(单位:rad/s/√Hz)白噪声强度
'gyro_random_walk': 0.000002, # 陀螺仪随机游走(单位:rad/s/√Hz)零偏不稳定性
'accel_noise_density': 0.0004, # 加速度噪声密度(单位:m/s²/√Hz)加速度计噪声强度
'accel_random_walk': 0.00008, # 加速度随机游走(单位:m/s³/√Hz)加速度零偏不稳定性
'calibration_frequency': 202.0, # IMU校准频率(单位:Hz)
\# 时间处理参数
'image_jitter_threshold_ms': 34.0, # 图像时间抖动阈值(单位:ms,建议设为 1/fps\*1000)
'imu_jitter_threshold_ms': 10.0, # IMU时间抖动阈值(单位:ms)
\# 地图管理参数
'save_map_folder_path': '/home/wheeltec/create_map/', # 保存地图的路径,节点退出时自动保存地图到此路径
'load_map_folder_path': '/home/wheeltec/create_map/', # 加载地图的路径,节点启动时从此路径加载预建地图
'slam_max_map_size': 1000, # 最大地图尺寸(单位:帧)
'slam_throttling_time_ms': 100, # SLAM频率限制(单位:ms)两次全局优化之间的最小时间间隔
\# 定位参数
'localize_on_startup': False, # 节点启动时是否进行定位
'enable_request_hint': True, # 启用请求提示,当自动定位失败时,发布请求获取初始位置提示
\# 定位搜索参数
'localizer_horizontal_radius': 1.5, # 水平搜索半径(单位:米)
'localizer_vertical_radius': 0.5, # 垂直搜索半径(单位:米)
'localizer_horizontal_step': 0.5, # 水平搜索步长(单位:米)
'localizer_vertical_step': 0.25, # 垂直搜索步长(单位:米)
'localizer_angular_step': 0.1745, # 角度搜索步长(单位:弧度)
\# 坐标系参数
'map_frame': "map", # 地图坐标系
'odom_frame': "odom", # 里程计坐标系
'base_frame': "base_link", # 基坐标系
'camera_optical_frames': \[
'camera_left_ir_optical_frame', # 左红外相机光学帧ID
'camera_right_ir_optical_frame', # 右红外相机光学帧ID
\], # 相机光学坐标系列表
'imu_frame': 'camera_accel_gyro_optical_frame', # IMU坐标系,只有启用IMU融合时才需要
\# 消息处理参数
'image_buffer_size': 10, # 图像消息缓冲区大小,存储待处理图像消息的队列长度
'imu_buffer_size': 50, # IMU消息缓冲区大小,存储待处理IMU消息的队列长度
'image_qos': 'SENSOR_DATA', # 图像消息QoS
'imu_qos': 'SENSOR_DATA', # IMU消息QoS
\# 输出控制参数
'override_publishing_stamp': False, # 是否覆盖发布的时间戳,使用处理时间而非原始消息时间戳
'publish_map_to_odom_tf': True, # 发布map到odom的TF变换
'publish_odom_to_base_tf': True, # 发布odom到base_link的TF变换
'invert_map_to_odom_tf': False, # 反转map到odom的TF变换
'invert_odom_to_base_tf': False, # 反转odom到base_link的TF变换
'path_max_size': 1024, # 路径最大长度,限制发布的轨迹路径中的点数
\# 调试与可视化参数
'enable_slam_visualization': True, # 启用SLAM可视化,发布各种可视化消息用于调试,包含: 地标、观测、位姿图等
'enable_observations_view': False, # 启用观测点云可视化(关闭可提高性能)
'enable_landmarks_view': False, # 启用地标点云可视化(关闭可提高性能)
'verbosity': 2, # 日志级别,0:只输出错误信息,1:输出警告信息,2:输出详细信息,3:输出调试信息
'enable_debug_mode': False, # 启用调试模式(关闭可提高性能)
'debug_dump_path': '/tmp/cuvslam' # 调试信息输出路径,仅在enable_debug_mode=True时有效
}\],
remappings=\[
('visual_slam/image_0', '/camera/left_ir/image_raw'), # 左相机图像话题映射
('visual_slam/camera_info_0', '/camera/left_ir/camera_info'), # 左相机相机信息话题映射
('visual_slam/image_1', '/camera/right_ir/image_raw'), # 右相机图像话题映射
('visual_slam/camera_info_1', '/camera/right_ir/camera_info'), # 右相机相机信息话题映射
('visual_slam/imu', '/camera/gyro_accel/sample'), # IMU数据话题映射
\],
)
visual_slam_launch_container = ComposableNodeContainer(
name='visual_slam_launch_container',
namespace='',
package='rclcpp_components',
executable='component_container',
composable_node_descriptions=\[visual_slam_node\],
output='screen',
)
\# ==================== TF变换节点 ====================
\# 1. 机器人底座 -> 相机底座(根据实际安装位置调整 x, y, z 值)
\# 参数:x y z yaw pitch roll frame_id child_frame_id
base_link_to_camera_base_node = Node(
package='tf2_ros',
executable='static_transform_publisher',
name='base_link_to_camera_base_frame',
arguments=\['0.32', '0', '0.1', '0', '0', '0', 'base_link', 'camera_base'\],
output='screen'
)
\# 2. 相机底座 -> 左红外相机光学坐标系
\# 旋转参数:roll pitch yaw (弧度) 或使用四元数
\# -1.571 约等于 -90度,这是从相机物理坐标系到光学坐标系的转换
camera_base_to_left_node = Node(
package='tf2_ros',
executable='static_transform_publisher',
name='camera_base_to_left_frame',
arguments=\['0.0', '0.0', '0.0', '-1.571', '0.0', '-1.571',
'camera_base', 'camera_left_ir_optical_frame'\],
output='screen'
)
\# 3. 相机底座 -> 右红外相机光学坐标系
\# 右相机相对于左相机有基线偏移(通常是Y方向,根据实际相机安装调整)
camera_base_to_right_node = Node(
package='tf2_ros',
executable='static_transform_publisher',
name='camera_base_to_right_frame',
arguments=\['0.0', '-0.095', '0.0', '-1.571', '0.0', '-1.571',
'camera_base', 'camera_right_ir_optical_frame'\],
output='screen'
)
\# 4. 相机底座 -> 陀螺仪光学坐标系
\# IMU相对于相机底座的位置和方向(根据实际安装位置调整)
camera_base_to_gyro_node = Node(
package='tf2_ros',
executable='static_transform_publisher',
name='camera_base_to_gyro_frame',
arguments=\['-0.014', '-0.008', '-0.001', '-1.571', '0.0', '-1.571',
'camera_base', 'camera_gyro_optical_frame'\],
output='screen'
)
\# 5. 基于陀螺仪光学坐标系创建零变换的IMU合并坐标系别名
imu_merged_frame_node = Node(
package='tf2_ros',
executable='static_transform_publisher',
name='static_tf_create_imu_merged_frame',
arguments=\['0.0', '0.0', '0.0', '0.0', '0.0', '0.0', '1.0',
'camera_gyro_optical_frame', 'camera_accel_gyro_optical_frame'\],
output='screen'
)
\# ==================== TF变换节点 ====================
\# 延迟启动VSLAM,确保TF先就绪
delayed_vslam = TimerAction(
period=5.0, # 等待5秒确保TF发布完成
actions=\[visual_slam_launch_container\]
)
return launch.LaunchDescription(\[
\# 第一步:启动必要的TF节点(按依赖顺序)
base_link_to_camera_base_node, # base_link -> camera_base
camera_base_to_left_node, # camera_base -> camera_left_ir_optical_frame
camera_base_to_right_node, # camera_base -> camera_right_ir_optical_frame
camera_base_to_gyro_node, # camera_base -> camera_gyro_optical_frame
imu_merged_frame_node, # camera_gyro_optical -> camera_accel_gyro_optical
\# 第二步:延迟启动VSLAM
delayed_vslam,
\])
This is my TF tree and rviz2 coordinate system display, as well as the launch file parameter configuration. I can’t determine where the problem is; mapping can’t proceed normally!
This topic was automatically closed 14 days after the last reply. New replies are no longer allowed.


