introlab / rtabmap_ros

RTAB-Map's ROS package.
http://wiki.ros.org/rtabmap_ros
BSD 3-Clause "New" or "Revised" License
922 stars 549 forks source link

ros2 humble realsense d435i in gazebo #1070

Closed yuan-0816 closed 5 months ago

yuan-0816 commented 7 months ago

I want to simulate the RealSense D435i in Gazebo and use RTAB-Map for localization. But RTAB-Map is unable to receive the camera topic.

Here are my xacro and launch files.

<?xml version="1.0"?>
<!--
Aknolegment: This file was originally copied from the realsense repository of
pal-robotics-forks( https://github.com/pal-robotics-forks/realsense/ )
and then modified.

License: Apache 2.0. See LICENSE file in root directory.
Copyright(c) 2017 PAL Robotics, S.L. All Rights Reserved

This is the Gazebo URDF model for the Intel RealSense D435i camera
-->
<robot xmlns:xacro="http://ros.org/wiki/xacro">
    <xacro:macro name="gazebo_d435i" params=" reference_link
                                            camera_name:=camera
                                            topics_ns:=camera

                                            depth_optical_frame
                                            color_optical_frame
                                            infrared1_optical_frame
                                            infrared2_optical_frame
                                            accel_optical_frame
                                            gyro_optical_frame

                                            visualize:=false
                                            align_depth:=false
                                            enable_pointCloud:=false

                                            unite_imu_method:=false
                                            accel_fps:=250
                                            gyro_fps:=400

                                            clip_distance:=-1.0
                                            depth_width:=1280
                                            depth_height:=720
                                            depth_fps:=30

                                            infra_width:=640
                                            infra_height:=480
                                            infra_fps:=30

                                            color_width:=1920
                                            color_height:=1080
                                            color_fps:=30
                                            ">
        <!-- Load parameters to model's main link-->
        <xacro:property name="deg_to_rad" value="0.01745329251994329577"/>
        <gazebo reference="${reference_link}">
            <self_collide>0</self_collide>
            <enable_wind>0</enable_wind>
            <kinematic>0</kinematic>
            <!-- <gravity>1</gravity> -->
            <!--<mu>1</mu>-->
            <mu2>1</mu2>
            <fdir1>0 0 0</fdir1>
            <!--<slip1>0</slip1>
      <slip2>0</slip2>-->
            <kp>1e+13</kp>
            <kd>1</kd>
            <!--<max_vel>0.01</max_vel>
      <min_depth>0</min_depth>-->
            <sensor name="${camera_name}color" type="camera">
                <camera name="${camera_name}">
                    <horizontal_fov>${69.4*deg_to_rad}</horizontal_fov>
                    <image>
                        <width>${color_width}</width>
                        <height>${color_height}</height>
                        <format>RGB_INT8</format>
                    </image>
                    <clip>
                        <near>0.1</near>
                        <far>100</far>
                    </clip>
                    <noise>
                        <type>gaussian</type>
                        <mean>0.0</mean>
                        <stddev>0.007</stddev>
                    </noise>
                </camera>
                <always_on>1</always_on>
                <update_rate>${color_fps}</update_rate>
                <visualize>${visualize}</visualize>
            </sensor>
            <sensor name="${camera_name}ired1" type="camera">
                <camera name="${camera_name}">
                    <horizontal_fov>${85.2*deg_to_rad}</horizontal_fov>
                    <image>
                        <width>${infra_width}</width>
                        <height>${infra_height}</height>
                        <format>L_INT8</format>
                    </image>
                    <clip>
                        <near>0.1</near>
                        <far>100</far>
                    </clip>
                    <noise>
                        <type>gaussian</type>
                        <mean>0.0</mean>
                        <stddev>0.05</stddev>
                    </noise>
                </camera>
                <always_on>1</always_on>
                <update_rate>${infra_fps}</update_rate>
                <visualize>false</visualize>
            </sensor>
            <sensor name="${camera_name}ired2" type="camera">
                <camera name="${camera_name}">
                    <horizontal_fov>${85.2*deg_to_rad}</horizontal_fov>
                    <image>
                        <width>${infra_width}</width>
                        <height>${infra_height}</height>
                        <format>L_INT8</format>
                    </image>
                    <clip>
                        <near>0.1</near>
                        <far>100</far>
                    </clip>
                    <noise>
                        <type>gaussian</type>
                        <mean>0.0</mean>
                        <stddev>0.05</stddev>
                    </noise>
                </camera>
                <always_on>1</always_on>
                <update_rate>${infra_fps}</update_rate>
                <visualize>false</visualize>
            </sensor>
            <sensor name="${camera_name}depth" type="depth">
                <camera name="${camera_name}">
                    <!-- align-depth settings -->
                    <xacro:unless value="${align_depth}">
                        <horizontal_fov>${85.2*deg_to_rad}</horizontal_fov>
                        <image>
                            <width>${depth_width}</width>
                            <height>${depth_height}</height>
                        </image>
                    </xacro:unless>
                    <xacro:if value="${align_depth}">
                        <horizontal_fov>${69.4*deg_to_rad}</horizontal_fov>
                        <image>
                            <width>${color_width}</width>
                            <height>${color_height}</height>
                        </image>
                    </xacro:if>
                    <clip>
                        <near>0.1</near>
                        <xacro:unless value="${clip_distance > 0.0}">
                            <far>100</far>
                        </xacro:unless>
                        <xacro:if value="${clip_distance > 0.0}">
                            <far>${clip_distance}</far>
                        </xacro:if>
                    </clip>
                    <noise>
                        <type>gaussian</type>
                        <mean>0.0</mean>
                        <stddev>0.100</stddev>
                    </noise>
                </camera>
                <always_on>1</always_on>
                <xacro:unless value="${align_depth}">
                    <update_rate>${depth_fps}</update_rate>
                </xacro:unless>
                <xacro:if value="${align_depth}">
                    <update_rate>${color_fps}</update_rate>
                </xacro:if>
                <visualize>false</visualize>
            </sensor>
            <!-- IMU -->
            <sensor name="${camera_name}imu" type="imu">
                <always_on>true</always_on>
                <update_rate>${gyro_fps}</update_rate>
                <!-- <topic>${camera_name}/imu/sample</topic> -->
                <topic>__default_topic__</topic>
                <plugin name="${camera_name}imu" filename="libgazebo_ros_imu_sensor.so">
                    <ros>
                        <!-- Will publish to /camera/imu -->
                        <!-- <namespace>${camera_name}/imu</namespace> -->
                        <namespace>/camera</namespace>
                        <remapping>~/out:=imu</remapping>
                    </ros>
                    <bodyName>${camera_name}_link</bodyName>
                    <frameName>${gyro_optical_frame}</frameName>
                    <updateRateHZ>${gyro_fps}</updateRateHZ>
                    <gaussianNoise>0.1</gaussianNoise>
                    <xyzOffset>0 0 0</xyzOffset>
                    <rpyOffset>0 0 0</rpyOffset>
                </plugin>
            </sensor>
        </gazebo>
        <gazebo>
            <plugin name="${topics_ns}" filename="librealsense_gazebo_plugin.so">
                <prefix>${camera_name}</prefix>
                <!-- Color camera settings -->
                <colorUpdateRate>${color_fps}</colorUpdateRate>
                <colorTopicName>camera/color/image_raw</colorTopicName>
                <colorOpticalframeName>${color_optical_frame}</colorOpticalframeName>
                <colorCameraInfoTopicName>color/camera_info</colorCameraInfoTopicName>
                <!-- Infrared camera settings -->
                <infraredUpdateRate>${infra_fps}</infraredUpdateRate>
                <infrared1TopicName>camera/infra1/image_rect_raw</infrared1TopicName>
                <infrared2TopicName>camera/infra2/image_rect_raw</infrared2TopicName>
                <infrared1CameraInfoTopicName>camera/infra1/camera_info</infrared1CameraInfoTopicName>
                <infrared2CameraInfoTopicName>camera/infra2/camera_info</infrared2CameraInfoTopicName>
                <infrared1OpticalframeName>${infrared1_optical_frame}</infrared1OpticalframeName>
                <infrared2OpticalframeName>${infrared2_optical_frame}</infrared2OpticalframeName>
                <!-- Depth camera settings -->
                <rangeMinDepth>0.2</rangeMinDepth>
                <xacro:unless value="${clip_distance > 0.0}">
                    <rangeMaxDepth>10.0</rangeMaxDepth>
                </xacro:unless>
                <xacro:if value="${clip_distance > 0.0}">
                    <rangeMaxDepth>${clip_distance}</rangeMaxDepth>
                </xacro:if>
                <xacro:unless value="${align_depth}">
                    <depthUpdateRate>${depth_fps}</depthUpdateRate>
                    <depthTopicName>camera/depth/image_rect_raw</depthTopicName>
                    <depthCameraInfoTopicName>camera/depth/camera_info</depthCameraInfoTopicName>
                    <depthOpticalframeName>${depth_optical_frame}</depthOpticalframeName>
                </xacro:unless>
                <xacro:if value="${align_depth}">
                    <depthUpdateRate>${color_fps}</depthUpdateRate>
                    <depthTopicName>camera/aligned_depth_to_color/image_raw</depthTopicName>
                    <depthCameraInfoTopicName>camera/aligned_depth_to_color/camera_info</depthCameraInfoTopicName>
                    <depthOpticalframeName>${color_optical_frame}</depthOpticalframeName>
                </xacro:if>
                <!-- Pointlcloud settings -->
                <pointCloud>${enable_pointCloud}</pointCloud>
                <pointCloudTopicName>depth/color/points</pointCloudTopicName>
                <pointCloudCutoff>0.5</pointCloudCutoff>
                <!-- <ros>
                    <namespace>/camera</namespace>
                </ros> -->
            </plugin>
        </gazebo>
    </xacro:macro>
</robot>

launch file

# Requirements:
#   A realsense D435i
#   Install realsense2 ros2 package (ros-$ROS_DISTRO-realsense2-camera)
#
#   RTAB-Map in mapping mode

import os

from launch import LaunchDescription, Substitution, LaunchContext
from launch.actions import DeclareLaunchArgument, SetEnvironmentVariable, LogInfo, OpaqueFunction
from launch.substitutions import LaunchConfiguration, ThisLaunchFileDir, PythonExpression
from launch.conditions import IfCondition, UnlessCondition
from launch_ros.actions import Node
from launch_ros.actions import SetParameter
from typing import Text
from ament_index_python.packages import get_package_share_directory

class ConditionalText(Substitution):
    def __init__(self, text_if, text_else, condition):
        self.text_if = text_if
        self.text_else = text_else
        self.condition = condition

    def perform(self, context: 'LaunchContext') -> Text:
        if self.condition == True or self.condition == 'true' or self.condition == 'True':
            return self.text_if
        else:
            return self.text_else

def launch_setup(context, *args, **kwargs):     

    use_sim_time = LaunchConfiguration('use_sim_time')
    qos = LaunchConfiguration('qos')
    localization = LaunchConfiguration('localization')

    parameters={
    'frame_id':'camera_link',
    # 'frame_id':'camera_color_optical_frame',
    'use_sim_time':use_sim_time,
    'subscribe_depth':True,
    'subscribe_odom_info':True,
    'approx_sync':False,
    'qos_image':qos,
    'qos_imu':qos,
    'wait_imu_to_init':True
    }

    # /camera/infra1/image_rect_raw,
    # /camera/depth/image_rect_raw,
    # /camera/infra1/camera_info

    remappings=[
          ('imu', '/imu/data'),
          ('rgb/image', '/camera/infra1/image_rect_raw'),
          ('rgb/camera_info', '/camera/infra1/camera_info'),
          ('depth/image', '/camera/depth/image_rect_raw')] 

    # remappings=[
    #     ('rgb/image', '/camera/camera/image_raw'),
    #     ('rgb/camera_info', '/camera/camera/camera_info'),
    #     ('depth/image', '/camera/camera/depth/image_raw')]

    return [

        DeclareLaunchArgument('args',  default_value=LaunchConfiguration('rtabmap_args'), 
                              description='Can be used to pass RTAB-Map\'s parameters or other flags like --udebug and --delete_db_on_start/-d'),

        Node(
            package='rtabmap_odom', executable='rgbd_odometry', output='screen',
            parameters=[parameters],
            remappings=remappings),

        # SLAM mode:
        Node(
            condition=UnlessCondition(localization),
            package='rtabmap_slam', executable='rtabmap', output='screen',
            parameters=[parameters],
            remappings=remappings,
            arguments=['-d']), # This will delete the previous database (~/.ros/rtabmap.db)

        # Localization mode:
        Node(
            condition=IfCondition(localization),
            package='rtabmap_slam', executable='rtabmap', output='screen',
            parameters=[parameters,
              {'Mem/IncrementalMemory':'False',
               'Mem/InitWMWithAllNodes':'True'}],
            remappings=remappings),

        Node(
            package='rtabmap_viz', executable='rtabmap_viz', output='screen',
            parameters=[parameters],
            condition=IfCondition(LaunchConfiguration("rtabmap_viz")),
            remappings=remappings),

        Node(
            package='rviz2', executable='rviz2', output='screen',
            condition=IfCondition(LaunchConfiguration("rviz")),
            arguments=[["-d"], [LaunchConfiguration("rviz_cfg")]]
            ),

        Node(
            package='rtabmap_util', executable='point_cloud_xyzrgb', output='screen',
            condition=IfCondition(LaunchConfiguration("rviz")),
            parameters=[{
                "decimation": 4,
                "voxel_size": 0.0,
                "approx_sync": LaunchConfiguration('approx_sync'),
                "approx_sync_max_interval": LaunchConfiguration('approx_sync_max_interval')
            }],
            remappings=remappings),

        # Compute quaternion of the IMU
        Node(
            package='imu_filter_madgwick', executable='imu_filter_madgwick_node', output='screen',
            parameters=[{'use_mag': False, 
                         'world_frame':'enu', 
                         'publish_tf':False}],
            remappings=[('imu/data_raw', '/camera/imu')]),

        # The IMU frame is missing in TF tree, add it:
        # Node(
        #     package='tf2_ros', executable='static_transform_publisher', output='screen',
        #     arguments=['0', '0', '0', '0', '0', '0', 'camera_gyro_optical_frame', 'camera_imu_optical_frame']),
    ]

def generate_launch_description():

    config_rviz = os.path.join(
        get_package_share_directory('AirLab_in_gazebo'), 'configs', 'sim.rviz')   

    return LaunchDescription([

        # Declare Launch Argument
        DeclareLaunchArgument('approx_sync', default_value='false', 
                              description='If timestamps of the input topics should be synchronized using approximate or exact time policy.'),

        DeclareLaunchArgument('approx_sync_max_interval', default_value='0.0', 
                              description='(sec) 0 means infinite interval duration (used with approx_sync=true)'),

        DeclareLaunchArgument('database_path', default_value='~/ros2_ws/src/drone_vslam/map_database/rtabmap.db',  
                              description='Where is the map saved/loaded.'),

        DeclareLaunchArgument('localization', default_value='false', 
                              description='Launch in localization mode.'),

        DeclareLaunchArgument('rtabmap_viz', default_value='false',  
                              description='Launch RTAB-Map UI (optional).'),

        DeclareLaunchArgument('rviz', default_value='true', 
                              description='Launch RVIZ (optional).'),

        DeclareLaunchArgument('rviz_cfg', default_value=config_rviz, 
                              description='Configuration path of rviz2.'),

        DeclareLaunchArgument('initial_pose', default_value='', 
                              description='Set an initial pose (only in localization mode). Format: "x y z roll pitch yaw" or "x y z qx qy qz qw". Default: see "RGBD/StartAtOrigin" doc'),

        DeclareLaunchArgument('rtabmap_args',   default_value='',                   
                              description='Backward compatibility, use "args" instead.'),

        DeclareLaunchArgument('use_sim_time', default_value='true',
                              description='Use simulation (Gazebo) clock if true'),

        DeclareLaunchArgument('qos', default_value='2',
                              description='QoS used for input sensor topics'),

        OpaqueFunction(function=launch_setup)

    ])

I can see the topic for the RealSense D435i using ros2 topic list, but RTAB-Map displays an error.

ros2 launch AirLab_in_gazebo rtabmap.launch.py 
[INFO] [launch]: All log files can be found below /home/yuan/.ros/log/2023-11-23-23-09-47-685092-airlab-ubuntu-48020
[INFO] [launch]: Default logging verbosity is set to INFO
[INFO] [rgbd_odometry-1]: process started with pid [48021]
[INFO] [rtabmap-2]: process started with pid [48023]
[INFO] [rviz2-3]: process started with pid [48025]
[INFO] [point_cloud_xyzrgb-4]: process started with pid [48027]
[INFO] [imu_filter_madgwick_node-5]: process started with pid [48029]
[rviz2-3] Warning: Ignoring XDG_SESSION_TYPE=wayland on Gnome. Use QT_QPA_PLATFORM=wayland to run on Wayland anyway.
[imu_filter_madgwick_node-5] [INFO] [1700752187.906796975] [imu_filter_madgwick]: Starting ImuFilter
[imu_filter_madgwick_node-5] [INFO] [1700752187.907461693] [imu_filter_madgwick]: Using dt computed from message headers
[imu_filter_madgwick_node-5] [INFO] [1700752187.907903148] [imu_filter_madgwick]: The gravity vector is kept in the IMU message.
[imu_filter_madgwick_node-5] [INFO] [1700752187.908067206] [imu_filter_madgwick]: Imu filter gain set to 0.100000
[imu_filter_madgwick_node-5] [INFO] [1700752187.908220104] [imu_filter_madgwick]: Gyro drift bias set to 0.000000
[imu_filter_madgwick_node-5] [INFO] [1700752187.908376629] [imu_filter_madgwick]: Magnetometer bias values: 0.000000 0.000000 0.000000
[imu_filter_madgwick_node-5] [INFO] [1700752187.951302037] [imu_filter_madgwick]: First IMU message received.
[point_cloud_xyzrgb-4] [INFO] [1700752188.383917664] [point_cloud_xyzrgb]: Approximate time sync = false
[rviz2-3] [INFO] [1700752188.410883286] [rviz2]: Stereo is NOT SUPPORTED
[rviz2-3] [INFO] [1700752188.414315875] [rviz2]: OpenGl version: 4.3 (GLSL 4.3)
[rgbd_odometry-1] [INFO] [1700752188.414934083] [rgbd_odometry]: Odometry: frame_id               = camera_link
[rgbd_odometry-1] [INFO] [1700752188.416136494] [rgbd_odometry]: Odometry: odom_frame_id          = odom
[rgbd_odometry-1] [INFO] [1700752188.416373735] [rgbd_odometry]: Odometry: publish_tf             = true
[rgbd_odometry-1] [INFO] [1700752188.416484769] [rgbd_odometry]: Odometry: wait_for_transform     = 0.100000
[rgbd_odometry-1] [INFO] [1700752188.416590021] [rgbd_odometry]: Odometry: log_to_rosout_level    = 4
[rgbd_odometry-1] [INFO] [1700752188.416710049] [rgbd_odometry]: Odometry: initial_pose           = xyz=0.000000,0.000000,0.000000 rpy=0.000000,-0.000000,0.000000
[rgbd_odometry-1] [INFO] [1700752188.416803205] [rgbd_odometry]: Odometry: ground_truth_frame_id  = 
[rgbd_odometry-1] [INFO] [1700752188.417031991] [rgbd_odometry]: Odometry: ground_truth_base_frame_id = camera_link
[rgbd_odometry-1] [INFO] [1700752188.417293246] [rgbd_odometry]: Odometry: config_path            = 
[rgbd_odometry-1] [INFO] [1700752188.417418053] [rgbd_odometry]: Odometry: publish_null_when_lost = true
[rgbd_odometry-1] [INFO] [1700752188.417525544] [rgbd_odometry]: Odometry: guess_frame_id         = 
[rgbd_odometry-1] [INFO] [1700752188.417676668] [rgbd_odometry]: Odometry: guess_min_translation  = 0.000000
[rgbd_odometry-1] [INFO] [1700752188.417786843] [rgbd_odometry]: Odometry: guess_min_rotation     = 0.000000
[rgbd_odometry-1] [INFO] [1700752188.417979396] [rgbd_odometry]: Odometry: guess_min_time         = 0.000000
[rgbd_odometry-1] [INFO] [1700752188.418092004] [rgbd_odometry]: Odometry: expected_update_rate   = 0.000000 Hz
[rgbd_odometry-1] [INFO] [1700752188.418207894] [rgbd_odometry]: Odometry: max_update_rate        = 0.000000 Hz
[rgbd_odometry-1] [INFO] [1700752188.418310645] [rgbd_odometry]: Odometry: min_update_rate        = 0.000000 Hz
[rgbd_odometry-1] [INFO] [1700752188.418412511] [rgbd_odometry]: Odometry: wait_imu_to_init       = true
[rgbd_odometry-1] [INFO] [1700752188.418527562] [rgbd_odometry]: Odometry: stereoParams_=0 visParams_=1 icpParams_=0
[rgbd_odometry-1] [INFO] [1700752188.517090366] [rgbd_odometry]: odometry: Subscribing to IMU topic /imu/data
[rgbd_odometry-1] [INFO] [1700752188.517746443] [rgbd_odometry]: odometry: qos_imu = 2
[rgbd_odometry-1] [INFO] [1700752188.520287700] [rgbd_odometry]: RGBDOdometry: approx_sync    = false
[rgbd_odometry-1] [INFO] [1700752188.520651535] [rgbd_odometry]: RGBDOdometry: queue_size     = 5
[rgbd_odometry-1] [INFO] [1700752188.520814326] [rgbd_odometry]: RGBDOdometry: qos            = 0
[rgbd_odometry-1] [INFO] [1700752188.520932233] [rgbd_odometry]: RGBDOdometry: qos_camera_info = 0
[rgbd_odometry-1] [INFO] [1700752188.521042385] [rgbd_odometry]: RGBDOdometry: subscribe_rgbd = false
[rgbd_odometry-1] [INFO] [1700752188.521151625] [rgbd_odometry]: RGBDOdometry: rgbd_cameras   = 1
[rgbd_odometry-1] [INFO] [1700752188.521260708] [rgbd_odometry]: RGBDOdometry: keep_color     = false
[rgbd_odometry-1] [INFO] [1700752188.525943058] [rgbd_odometry]: 
[rgbd_odometry-1] rgbd_odometry subscribed to (exact sync):
[rgbd_odometry-1]    /camera/infra1/image_rect_raw,
[rgbd_odometry-1]    /camera/depth/image_rect_raw,
[rgbd_odometry-1]    /camera/infra1/camera_info
[rviz2-3] [INFO] [1700752188.527412921] [rviz2]: Stereo is NOT SUPPORTED
[rtabmap-2] [INFO] [1700752188.582625663] [rtabmap]: rtabmap(maps): map_filter_radius          = 0.000000
[rtabmap-2] [INFO] [1700752188.582792715] [rtabmap]: rtabmap(maps): map_filter_angle           = 30.000000
[rtabmap-2] [INFO] [1700752188.582799918] [rtabmap]: rtabmap(maps): map_cleanup                = true
[rtabmap-2] [INFO] [1700752188.582802260] [rtabmap]: rtabmap(maps): map_always_update          = false
[rtabmap-2] [INFO] [1700752188.582805453] [rtabmap]: rtabmap(maps): map_empty_ray_tracing      = true
[rtabmap-2] [INFO] [1700752188.582807494] [rtabmap]: rtabmap(maps): cloud_output_voxelized     = true
[rtabmap-2] [INFO] [1700752188.582809449] [rtabmap]: rtabmap(maps): cloud_subtract_filtering   = false
[rtabmap-2] [INFO] [1700752188.582811434] [rtabmap]: rtabmap(maps): cloud_subtract_filtering_min_neighbors = 2
[rtabmap-2] [INFO] [1700752188.582842066] [rtabmap]: rtabmap(maps): octomap_tree_depth         = 16
[rtabmap-2] [INFO] [1700752188.636528314] [rtabmap]: rtabmap: frame_id      = camera_link
[rtabmap-2] [INFO] [1700752188.636949700] [rtabmap]: rtabmap: map_frame_id  = map
[rtabmap-2] [INFO] [1700752188.637108394] [rtabmap]: rtabmap: log_to_rosout_level  = 4
[rtabmap-2] [INFO] [1700752188.637222744] [rtabmap]: rtabmap: initial_pose  = 
[rtabmap-2] [INFO] [1700752188.637332906] [rtabmap]: rtabmap: use_action_for_goal  = false
[rtabmap-2] [INFO] [1700752188.637567326] [rtabmap]: rtabmap: tf_delay      = 0.050000
[rtabmap-2] [INFO] [1700752188.637710874] [rtabmap]: rtabmap: tf_tolerance  = 0.100000
[rtabmap-2] [INFO] [1700752188.637820028] [rtabmap]: rtabmap: odom_sensor_sync   = false
[rtabmap-2] [INFO] [1700752188.638086276] [rtabmap]: rtabmap: gen_scan  = false
[rtabmap-2] [INFO] [1700752188.638210921] [rtabmap]: rtabmap: gen_depth  = false
[rtabmap-2] [INFO] [1700752188.757793219] [rtabmap]: RTAB-Map detection rate = 1.000000 Hz
[rtabmap-2] [INFO] [1700752188.761995410] [rtabmap]: rtabmap: Deleted database "/home/yuan/.ros/rtabmap.db" (--delete_db_on_start or -d are set).
[rtabmap-2] [INFO] [1700752188.762342135] [rtabmap]: rtabmap: Using database from "/home/yuan/.ros/rtabmap.db" (0 MB).
[rtabmap-2] [INFO] [1700752188.824142561] [rtabmap]: rtabmap: Database version = "0.21.1".
[rtabmap-2] [INFO] [1700752188.827641152] [rtabmap]: rtabmap: SLAM mode (Mem/IncrementalMemory=true)
[rtabmap-2] [INFO] [1700752188.962759328] [rtabmap]: Setup callbacks
[rtabmap-2] [INFO] [1700752188.963959838] [rtabmap]: rtabmap: subscribe_depth = true
[rtabmap-2] [INFO] [1700752188.963991957] [rtabmap]: rtabmap: subscribe_rgb = true
[rtabmap-2] [INFO] [1700752188.963995694] [rtabmap]: rtabmap: subscribe_stereo = false
[rtabmap-2] [INFO] [1700752188.963998212] [rtabmap]: rtabmap: subscribe_rgbd = false (rgbd_cameras=1)
[rtabmap-2] [INFO] [1700752188.964000885] [rtabmap]: rtabmap: subscribe_odom_info = true
[rtabmap-2] [INFO] [1700752188.964003078] [rtabmap]: rtabmap: subscribe_user_data = false
[rtabmap-2] [INFO] [1700752188.964005392] [rtabmap]: rtabmap: subscribe_scan = false
[rtabmap-2] [INFO] [1700752188.964007749] [rtabmap]: rtabmap: subscribe_scan_cloud = false
[rtabmap-2] [INFO] [1700752188.964009725] [rtabmap]: rtabmap: subscribe_scan_descriptor = false
[rtabmap-2] [INFO] [1700752188.964012034] [rtabmap]: rtabmap: queue_size      = 10
[rtabmap-2] [INFO] [1700752188.964014303] [rtabmap]: rtabmap: qos_image       = 2
[rtabmap-2] [INFO] [1700752188.964016414] [rtabmap]: rtabmap: qos_camera_info = 2
[rtabmap-2] [INFO] [1700752188.964018362] [rtabmap]: rtabmap: qos_scan        = 0
[rtabmap-2] [INFO] [1700752188.964020425] [rtabmap]: rtabmap: qos_odom        = 0
[rtabmap-2] [INFO] [1700752188.964022449] [rtabmap]: rtabmap: qos_user_data   = 0
[rtabmap-2] [INFO] [1700752188.964024395] [rtabmap]: rtabmap: approx_sync     = false
[rtabmap-2] [INFO] [1700752188.964032230] [rtabmap]: Setup depth callback
[rtabmap-2] [INFO] [1700752188.995505127] [rtabmap]: 
[rtabmap-2] rtabmap subscribed to (exact sync):
[rtabmap-2]    /odom \
[rtabmap-2]    /camera/infra1/image_rect_raw \
[rtabmap-2]    /camera/depth/image_rect_raw \
[rtabmap-2]    /camera/infra1/camera_info \
[rtabmap-2]    /odom_info
[rviz2-3] [INFO] [1700752189.378253714] [rviz2]: Stereo is NOT SUPPORTED
[rviz2-3] [INFO] [1700752189.382556392] [rviz2]: Stereo is NOT SUPPORTED
[rgbd_odometry-1] [WARN] [1700752193.530089150] [rgbd_odometry]: rgbd_odometry: Did not receive data since 5 seconds! Make sure the input topics are published ("$ rostopic hz my_topic") and the timestamps in their header are set. Parameter "approx_sync" is false, which means that input topics should have all the exact timestamp for the callback to be called.
[rgbd_odometry-1] rgbd_odometry subscribed to (exact sync):
[rgbd_odometry-1]    /camera/infra1/image_rect_raw,
[rgbd_odometry-1]    /camera/depth/image_rect_raw,
[rgbd_odometry-1]    /camera/infra1/camera_info
[rtabmap-2] [WARN] [1700752194.019042033] [rtabmap]: rtabmap: Did not receive data since 5 seconds! Make sure the input topics are published ("$ rostopic hz my_topic") and the timestamps in their header are set. If topics are coming from different computers, make sure the clocks of the computers are synchronized ("ntpdate"). If topics are not published at the same rate, you could increase "queue_size" parameter (current=10). Parameter "approx_sync" is false, which means that input topics should have all the exact timestamp for the callback to be called.
[rtabmap-2] rtabmap subscribed to (exact sync):
[rtabmap-2]    /odom \
[rtabmap-2]    /camera/infra1/image_rect_raw \
[rtabmap-2]    /camera/depth/image_rect_raw \
[rtabmap-2]    /camera/infra1/camera_info \
[rtabmap-2]    /odom_info
^C[WARNING] [launch]: user interrupted with ctrl-c (SIGINT)
[rgbd_odometry-1] [INFO] [1700752195.880895495] [rclcpp]: signal_handler(signum=2)
[point_cloud_xyzrgb-4] [INFO] [1700752195.880898587] [rclcpp]: signal_handler(signum=2)
[rtabmap-2] [INFO] [1700752195.881748431] [rclcpp]: signal_handler(signum=2)
[rtabmap-2] [WARN] [1700752195.882585332] [rtabmap]: rtabmap: Did not receive data since 5 seconds! Make sure the input topics are published ("$ rostopic hz my_topic") and the timestamps in their header are set. If topics are coming from different computers, make sure the clocks of the computers are synchronized ("ntpdate"). If topics are not published at the same rate, you could increase "queue_size" parameter (current=10). Parameter "approx_sync" is false, which means that input topics should have all the exact timestamp for the callback to be called.
[rtabmap-2] rtabmap subscribed to (exact sync):
[rtabmap-2]    /odom \
[rtabmap-2]    /camera/infra1/image_rect_raw \
[rtabmap-2]    /camera/depth/image_rect_raw \
[rtabmap-2]    /camera/infra1/camera_info \
[rtabmap-2]    /odom_info
[rviz2-3] [INFO] [1700752195.882848604] [rclcpp]: signal_handler(signum=2)
[imu_filter_madgwick_node-5] [INFO] [1700752195.884572765] [rclcpp]: signal_handler(signum=2)
[rgbd_odometry-1] [WARN] [1700752195.888917444] [rgbd_odometry]: rgbd_odometry: Did not receive data since 5 seconds! Make sure the input topics are published ("$ rostopic hz my_topic") and the timestamps in their header are set. 
[rgbd_odometry-1] rgbd_odometry subscribed to (exact sync):
[rgbd_odometry-1]    /camera/infra1/image_rect_raw,
[rgbd_odometry-1]    /camera/depth/image_rect_raw,
[rgbd_odometry-1]    /camera/infra1/camera_info
[rtabmap-2] [INFO] [1700752195.932880938] [rtabmap]: Parameters are not saved (No configuration file provided...)
[INFO] [imu_filter_madgwick_node-5]: process has finished cleanly [pid 48029]
[INFO] [point_cloud_xyzrgb-4]: process has finished cleanly [pid 48027]
[INFO] [rviz2-3]: process has finished cleanly [pid 48025]
[ERROR] [rtabmap-2]: process[rtabmap-2] failed to terminate '5' seconds after receiving 'SIGINT', escalating to 'SIGTERM'
[ERROR] [rgbd_odometry-1]: process[rgbd_odometry-1] failed to terminate '5' seconds after receiving 'SIGINT', escalating to 'SIGTERM'
[INFO] [rtabmap-2]: sending signal 'SIGTERM' to process[rtabmap-2]
[INFO] [rgbd_odometry-1]: sending signal 'SIGTERM' to process[rgbd_odometry-1]
[rtabmap-2] [INFO] [1700752200.887038270] [rclcpp]: signal_handler(signum=15)
[rgbd_odometry-1] [INFO] [1700752200.887479670] [rclcpp]: signal_handler(signum=15)
[rtabmap-2] rtabmap: Saving database/long-term memory... (located at /home/yuan/.ros/rtabmap.db)
[rtabmap-2] rtabmap: Saving database/long-term memory...done! (located at /home/yuan/.ros/rtabmap.db, 0 MB)
[INFO] [rtabmap-2]: process has finished cleanly [pid 48023]
[INFO] [rgbd_odometry-1]: process has finished cleanly [pid 48021]

"I'm using ROS2 Humble on Ubuntu 22.04."

yuan-0816 commented 7 months ago

Screenshot from 2023-11-23 23-11-30

matlabbe commented 7 months ago

I suggest to do rostopic hz instead of rostopic list to acutally know that the topics are published.

rostopic hz /camera/infra1/image_rect_raw
rostopic hz /camera/depth/image_rect_raw
rostopic hz /camera/infra1/camera_info

I see you are also using approx_sync set to false (exact sync), are the image topics published with same stamp?

yuan-0816 commented 7 months ago

I used ros2 topic hz, and all three topics are being published.

yuan@airlab-ubuntu:~$ ros2 topic hz /camera/infra1/image_rect_raw
average rate: 26.126
    min: 0.032s max: 0.047s std dev: 0.00314s window: 28
average rate: 26.148
    min: 0.032s max: 0.050s std dev: 0.00367s window: 55
average rate: 26.629
    min: 0.032s max: 0.050s std dev: 0.00329s window: 83
average rate: 26.471
    min: 0.032s max: 0.050s std dev: 0.00355s window: 109
average rate: 26.757
    min: 0.031s max: 0.050s std dev: 0.00340s window: 137
average rate: 26.751
    min: 0.031s max: 0.054s std dev: 0.00365s window: 164
average rate: 26.904
    min: 0.031s max: 0.054s std dev: 0.00349s window: 192
average rate: 26.845
    min: 0.031s max: 0.054s std dev: 0.00359s window: 219
^Cyuan@airlab-ubuntu:~$ ros2 topic hz /camera/depth/image_rect_raw
average rate: 20.165
    min: 0.033s max: 0.112s std dev: 0.02065s window: 22
average rate: 19.930
    min: 0.033s max: 0.144s std dev: 0.02396s window: 42
average rate: 19.556
    min: 0.033s max: 0.144s std dev: 0.02437s window: 61
average rate: 18.718
    min: 0.033s max: 0.181s std dev: 0.02850s window: 78
average rate: 18.535
    min: 0.033s max: 0.181s std dev: 0.02846s window: 96
average rate: 18.546
    min: 0.033s max: 0.181s std dev: 0.02738s window: 116
^Cyuan@airlab-ubuntu:~$ ros2 topic hz camera/infra1/camera_info
average rate: 28.262
    min: 0.031s max: 0.040s std dev: 0.00247s window: 30
average rate: 27.359
    min: 0.031s max: 0.050s std dev: 0.00369s window: 57
average rate: 27.674
    min: 0.031s max: 0.050s std dev: 0.00323s window: 86
average rate: 27.647
    min: 0.031s max: 0.053s std dev: 0.00361s window: 115
average rate: 27.510
    min: 0.031s max: 0.053s std dev: 0.00351s window: 142
average rate: 27.419
    min: 0.031s max: 0.053s std dev: 0.00356s window: 169

I set use sim time to true, so the camera topic should be published with the same timestamp as the simulation time. And I also used ros2 run rqt_image_view rqt_image_view to subscribe to the camera topic, and there is a visual feed.

Screenshot from 2023-11-24 19-39-05 Screenshot from 2023-11-24 19-38-51

matlabbe commented 7 months ago

The topics don't seem to be published at the same time, set approx_sync to true for all rtabmap nodes. The infra1 and depth images are not the same resolution, make sure they are using same focal length with same resolution from same link in your URDF, so that depth is perfectly aligned with infra1.

yuan-0816 commented 7 months ago

It works !!! messageImage_1701228925253


But I still want to know, If I set use sim time to true in the Gazebo launch file and also in RTAB-Map, why is the depth camera information still not synchronized?

matlabbe commented 6 months ago

Is use_sim_time added to all rtabmap nodes? With how the new warning works, it won't use the simulated clock if use_sim_time is not set, then will complain that the topics are not received from the past 5 seconds. As the simulation time would start at epoch=0, all topics will be always in the past from the point of view of that check. Just tested with turtebot3 example and it seems to do what I just described (no warning when use_sim_time:=true, warning when use_sim_time:=false but the nodes are working correctly).

yuan-0816 commented 6 months ago

Yes, I set the use_sim_time=True in all rtabmap nodes This is my rtabmap launch file

# Requirements:
#   A realsense D435i
#   Install realsense2 ros2 package (ros-$ROS_DISTRO-realsense2-camera)
#
#   RTAB-Map in mapping mode

import os

from launch import LaunchDescription, Substitution, LaunchContext
from launch.actions import DeclareLaunchArgument, SetEnvironmentVariable, LogInfo, OpaqueFunction
from launch.substitutions import LaunchConfiguration, ThisLaunchFileDir, PythonExpression
from launch.conditions import IfCondition, UnlessCondition
from launch_ros.actions import Node
from launch_ros.actions import SetParameter
from typing import Text
from ament_index_python.packages import get_package_share_directory

class ConditionalText(Substitution):
    def __init__(self, text_if, text_else, condition):
        self.text_if = text_if
        self.text_else = text_else
        self.condition = condition

    def perform(self, context: 'LaunchContext') -> Text:
        if self.condition == True or self.condition == 'true' or self.condition == 'True':
            return self.text_if
        else:
            return self.text_else

def launch_setup(context, *args, **kwargs):     

    use_sim_time = LaunchConfiguration('use_sim_time')
    qos = LaunchConfiguration('qos')
    localization = LaunchConfiguration('localization')

    parameters={
    # 'frame_id':'camera_link',
    'frame_id':'base_link',
    'use_sim_time':use_sim_time,
    'subscribe_depth':True,
    'subscribe_odom_info':True,
    'approx_sync':True,
    'qos_image':qos,
    'qos_imu':qos,
    'wait_imu_to_init':False
    }

    # use infra camera
    # remappings=[
    #       ('imu', '/imu/data'),
    #       ('rgb/image', '/camera/infra1/image_rect_raw'),
    #       ('rgb/camera_info', '/camera/infra1/camera_info'),
    #       ('depth/image', '/camera/depth/image_rect_raw')] 

    # use color camera 
    # remappings=[
    #     ('imu', '/imu/data'),
    #     ('rgb/image', '/camera/color/image_raw'),
    #     ('rgb/camera_info', '/camera/color/camera_info'),
    #     ('depth/image', '/camera/depth/image_rect_raw')] 

    # use color camera 
    remappings=[
        ('imu', '/imu/data'),
        ('rgb/image', '/camera/image_raw'),
        ('rgb/camera_info', '/camera/camera_info'),
        ('depth/image', '/camera/depth/image_raw')] 

    return [

        DeclareLaunchArgument('args',  default_value=LaunchConfiguration('rtabmap_args'), 
                              description='Can be used to pass RTAB-Map\'s parameters or other flags like --udebug and --delete_db_on_start/-d'),

        Node(
            package='rtabmap_odom', executable='rgbd_odometry', output='screen',
            parameters=[parameters],
            remappings=remappings),

        # TODO: database 路徑
        # SLAM mode:
        Node(
            condition=UnlessCondition(localization),
            package='rtabmap_slam', executable='rtabmap', output='screen',
            parameters=[parameters],
            remappings=remappings,
            arguments=['-d']), # This will delete the previous database (~/.ros/rtabmap.db)

        # Localization mode:
        Node(
            condition=IfCondition(localization),
            package='rtabmap_slam', executable='rtabmap', output='screen',
            parameters=[parameters,
              {'Mem/IncrementalMemory':'False',
               'Mem/InitWMWithAllNodes':'True'}],
            remappings=remappings),

        Node(
            package='rtabmap_viz', executable='rtabmap_viz', output='screen',
            parameters=[parameters],
            condition=IfCondition(LaunchConfiguration("rtabmap_viz")),
            remappings=remappings),

        Node(
            package='rviz2', executable='rviz2', output='screen',
            condition=IfCondition(LaunchConfiguration("rviz")),
            arguments=[["-d"], [LaunchConfiguration("rviz_cfg")]]
            ),

        Node(
            package='rtabmap_util', executable='point_cloud_xyzrgb', output='screen',
            condition=IfCondition(LaunchConfiguration("rviz")),
            parameters=[{
                "decimation": 4,
                "voxel_size": 0.0,
                "approx_sync": LaunchConfiguration('approx_sync'),
                "approx_sync_max_interval": LaunchConfiguration('approx_sync_max_interval')
            }],
            remappings=remappings),

        # Compute quaternion of the IMU
        Node(
            package='imu_filter_madgwick', executable='imu_filter_madgwick_node', output='screen',
            parameters=[{'use_mag': False, 
                         'world_frame':'enu', 
                         'publish_tf':False}],
            remappings=[('imu/data_raw', '/camera/imu')]),

        # The IMU frame is missing in TF tree, add it:
        # Node(
        #     package='tf2_ros', executable='static_transform_publisher', output='screen',
        #     arguments=['0', '0', '0', '0', '0', '0', 'camera_gyro_optical_frame', 'camera_imu_optical_frame']),
    ]

def generate_launch_description():

    config_rviz = os.path.join(
        get_package_share_directory('AirLab_in_gazebo'), 'configs', 'sim.rviz')   

    return LaunchDescription([

        # Declare Launch Argument
        DeclareLaunchArgument('approx_sync', default_value='false', 
                              description='If timestamps of the input topics should be synchronized using approximate or exact time policy.'),

        DeclareLaunchArgument('approx_sync_max_interval', default_value='0.0', 
                              description='(sec) 0 means infinite interval duration (used with approx_sync=true)'),

        DeclareLaunchArgument('database_path', default_value='~/ros2_ws/src/drone_vslam/map_database/rtabmap.db',  
                              description='Where is the map saved/loaded.'),

        DeclareLaunchArgument('localization', default_value='false', 
                              description='Launch in localization mode.'),

        DeclareLaunchArgument('rtabmap_viz', default_value='true',  
                              description='Launch RTAB-Map UI (optional).'),

        DeclareLaunchArgument('rviz', default_value='true', 
                              description='Launch RVIZ (optional).'),

        DeclareLaunchArgument('rviz_cfg', default_value=config_rviz, 
                              description='Configuration path of rviz2.'),

        DeclareLaunchArgument('initial_pose', default_value='', 
                              description='Set an initial pose (only in localization mode). Format: "x y z roll pitch yaw" or "x y z qx qy qz qw". Default: see "RGBD/StartAtOrigin" doc'),

        DeclareLaunchArgument('rtabmap_args',   default_value='',                   
                              description='Backward compatibility, use "args" instead.'),

        DeclareLaunchArgument('use_sim_time', default_value='true',
                              description='Use simulation (Gazebo) clock if true'),

        DeclareLaunchArgument('qos', default_value='2',
                              description='QoS used for input sensor topics'),

        OpaqueFunction(function=launch_setup)

    ])
matlabbe commented 6 months ago

Can you doublecheck if the parameter is correctly set?

ros2 param list
ros2 param get rtabmap use_sim_time
Boolean value is: True

Which rtabmap version are you using?

yuan-0816 commented 6 months ago

I run ros2 param list

yuan@airlab-ubuntu:~$ ros2 param list
/camera_controller:
  camera.depth.image_raw.format
  camera.depth.image_raw.jpeg_quality
  camera.depth.image_raw.png_level
  camera.depth.image_raw.tiff.res_unit
  camera.depth.image_raw.tiff.xdpi
  camera.depth.image_raw.tiff.ydpi
  camera.image_raw.format
  camera.image_raw.jpeg_quality
  camera.image_raw.png_level
  camera.image_raw.tiff.res_unit
  camera.image_raw.tiff.xdpi
  camera.image_raw.tiff.ydpi
  qos_overrides./clock.subscription.depth
  qos_overrides./clock.subscription.durability
  qos_overrides./clock.subscription.history
  qos_overrides./clock.subscription.reliability
  qos_overrides./parameter_events.publisher.depth
  qos_overrides./parameter_events.publisher.durability
  qos_overrides./parameter_events.publisher.history
  qos_overrides./parameter_events.publisher.reliability
  update_rate
  use_sim_time
/diff_drive:
  qos_overrides./clock.subscription.depth
  qos_overrides./clock.subscription.durability
  qos_overrides./clock.subscription.history
  qos_overrides./clock.subscription.reliability
  qos_overrides./parameter_events.publisher.depth
  qos_overrides./parameter_events.publisher.durability
  qos_overrides./parameter_events.publisher.history
  qos_overrides./parameter_events.publisher.reliability
  qos_overrides./tf.publisher.depth
  qos_overrides./tf.publisher.durability
  qos_overrides./tf.publisher.history
  qos_overrides./tf.publisher.reliability
  use_sim_time
/gazebo:
  enable_performance_metrics
  publish_rate
  qos_overrides./clock.subscription.depth
  qos_overrides./clock.subscription.durability
  qos_overrides./clock.subscription.history
  qos_overrides./clock.subscription.reliability
  qos_overrides./parameter_events.publisher.depth
  qos_overrides./parameter_events.publisher.durability
  qos_overrides./parameter_events.publisher.history
  qos_overrides./parameter_events.publisher.reliability
  use_sim_time
/imu_filter_madgwick:
  constant_dt
  declination
  fixed_frame
  gain
  mag_bias_x
  mag_bias_y
  mag_bias_z
  orientation_stddev
  publish_debug_topics
  publish_tf
  qos_overrides./parameter_events.publisher.depth
  qos_overrides./parameter_events.publisher.durability
  qos_overrides./parameter_events.publisher.history
  qos_overrides./parameter_events.publisher.reliability
  qos_overrides./tf.publisher.depth
  qos_overrides./tf.publisher.durability
  qos_overrides./tf.publisher.history
  qos_overrides./tf.publisher.reliability
  remove_gravity_vector
  reverse_tf
  stateless
  use_mag
  use_sim_time
  world_frame
  yaw_offset
  zeta
/point_cloud_xyzrgb:
  StereoBM/BlockSize
  StereoBM/Disp12MaxDiff
  StereoBM/MinDisparity
  StereoBM/NumDisparities
  StereoBM/PreFilterCap
  StereoBM/PreFilterSize
  StereoBM/SpeckleRange
  StereoBM/SpeckleWindowSize
  StereoBM/TextureThreshold
  StereoBM/UniquenessRatio
  approx_sync
  approx_sync_max_interval
  decimation
  filter_nans
  max_depth
  min_depth
  noise_filter_min_neighbors
  noise_filter_radius
  normal_k
  normal_radius
  qos
  qos_camera_info
  qos_overrides./parameter_events.publisher.depth
  qos_overrides./parameter_events.publisher.durability
  qos_overrides./parameter_events.publisher.history
  qos_overrides./parameter_events.publisher.reliability
  queue_size
  roi_ratios
  use_sim_time
  voxel_size
/rgbd_odometry:
  BRIEF/Bytes
  BRISK/Octaves
  BRISK/PatternScale
  BRISK/Thresh
  FAST/CV
  FAST/Gpu
  FAST/GpuKeypointsRatio
  FAST/GridCols
  FAST/GridRows
  FAST/MaxThreshold
  FAST/MinThreshold
  FAST/NonmaxSuppression
  FAST/Threshold
  FREAK/NOctaves
  FREAK/OrientationNormalized
  FREAK/PatternScale
  FREAK/ScaleNormalized
  GFTT/BlockSize
  GFTT/K
  GFTT/MinDistance
  GFTT/QualityLevel
  GFTT/UseHarrisDetector
  GMS/ThresholdFactor
  GMS/WithRotation
  GMS/WithScale
  GTSAM/Optimizer
  KAZE/Diffusivity
  KAZE/Extended
  KAZE/NOctaveLayers
  KAZE/NOctaves
  KAZE/Threshold
  KAZE/Upright
  Kp/ByteToFloat
  ORB/EdgeThreshold
  ORB/FirstLevel
  ORB/Gpu
  ORB/NLevels
  ORB/PatchSize
  ORB/ScaleFactor
  ORB/ScoreType
  ORB/WTA_K
  Odom/AlignWithGround
  Odom/FillInfoData
  Odom/FilteringStrategy
  Odom/GuessMotion
  Odom/GuessSmoothingDelay
  Odom/Holonomic
  Odom/ImageBufferSize
  Odom/ImageDecimation
  Odom/KalmanMeasurementNoise
  Odom/KalmanProcessNoise
  Odom/KeyFrameThr
  Odom/ParticleLambdaR
  Odom/ParticleLambdaT
  Odom/ParticleNoiseR
  Odom/ParticleNoiseT
  Odom/ParticleSize
  Odom/ResetCountdown
  Odom/ScanKeyFrameThr
  Odom/Strategy
  Odom/VisKeyFrameThr
  OdomF2M/BundleAdjustment
  OdomF2M/BundleAdjustmentMaxFrames
  OdomF2M/MaxNewFeatures
  OdomF2M/MaxSize
  OdomF2M/ScanMaxSize
  OdomF2M/ScanRange
  OdomF2M/ScanSubtractAngle
  OdomF2M/ScanSubtractRadius
  OdomF2M/ValidDepthRatio
  OdomFovis/BucketHeight
  OdomFovis/BucketWidth
  OdomFovis/CliqueInlierThreshold
  OdomFovis/FastThreshold
  OdomFovis/FastThresholdAdaptiveGain
  OdomFovis/FeatureSearchWindow
  OdomFovis/FeatureWindowSize
  OdomFovis/InlierMaxReprojectionError
  OdomFovis/MaxKeypointsPerBucket
  OdomFovis/MaxMeanReprojectionError
  OdomFovis/MaxPyramidLevel
  OdomFovis/MinFeaturesForEstimate
  OdomFovis/MinPyramidLevel
  OdomFovis/StereoMaxDisparity
  OdomFovis/StereoMaxDistEpipolarLine
  OdomFovis/StereoMaxRefinementDisplacement
  OdomFovis/StereoRequireMutualMatch
  OdomFovis/TargetPixelsPerFeature
  OdomFovis/UpdateTargetFeaturesWithRefined
  OdomFovis/UseAdaptiveThreshold
  OdomFovis/UseBucketing
  OdomFovis/UseHomographyInitialization
  OdomFovis/UseImageNormalization
  OdomFovis/UseSubpixelRefinement
  OdomLOAM/AngVar
  OdomLOAM/LinVar
  OdomLOAM/LocalMapping
  OdomLOAM/Resolution
  OdomLOAM/ScanPeriod
  OdomLOAM/Sensor
  OdomMSCKF/FastThreshold
  OdomMSCKF/GridCol
  OdomMSCKF/GridMaxFeatureNum
  OdomMSCKF/GridMinFeatureNum
  OdomMSCKF/GridRow
  OdomMSCKF/InitCovAccBias
  OdomMSCKF/InitCovExRot
  OdomMSCKF/InitCovExTrans
  OdomMSCKF/InitCovGyroBias
  OdomMSCKF/InitCovVel
  OdomMSCKF/MaxCamStateSize
  OdomMSCKF/MaxIteration
  OdomMSCKF/NoiseAcc
  OdomMSCKF/NoiseAccBias
  OdomMSCKF/NoiseFeature
  OdomMSCKF/NoiseGyro
  OdomMSCKF/NoiseGyroBias
  OdomMSCKF/OptTranslationThreshold
  OdomMSCKF/PatchSize
  OdomMSCKF/PositionStdThreshold
  OdomMSCKF/PyramidLevels
  OdomMSCKF/RansacThreshold
  OdomMSCKF/RotationThreshold
  OdomMSCKF/StereoThreshold
  OdomMSCKF/TrackPrecision
  OdomMSCKF/TrackingRateThreshold
  OdomMSCKF/TranslationThreshold
  OdomMono/InitMinFlow
  OdomMono/InitMinTranslation
  OdomMono/MaxVariance
  OdomMono/MinTranslation
  OdomOKVIS/ConfigPath
  OdomORBSLAM/Bf
  OdomORBSLAM/Fps
  OdomORBSLAM/MapSize
  OdomORBSLAM/MaxFeatures
  OdomORBSLAM/ThDepth
  OdomORBSLAM/VocPath
  OdomOpen3D/MaxDepth
  OdomOpen3D/Method
  OdomVINS/ConfigPath
  OdomViso2/BucketHeight
  OdomViso2/BucketMaxFeatures
  OdomViso2/BucketWidth
  OdomViso2/InlierThreshold
  OdomViso2/MatchBinsize
  OdomViso2/MatchDispTolerance
  OdomViso2/MatchHalfResolution
  OdomViso2/MatchMultiStage
  OdomViso2/MatchNmsN
  OdomViso2/MatchNmsTau
  OdomViso2/MatchOutlierDispTolerance
  OdomViso2/MatchOutlierFlowTolerance
  OdomViso2/MatchRadius
  OdomViso2/MatchRefinement
  OdomViso2/RansacIters
  OdomViso2/Reweighting
  Optimizer/Epsilon
  Optimizer/GravitySigma
  Optimizer/Iterations
  Optimizer/LandmarksIgnored
  Optimizer/PriorsIgnored
  Optimizer/Robust
  Optimizer/Strategy
  Optimizer/VarianceIgnored
  PyDetector/Cuda
  PyDetector/Path
  PyMatcher/Cuda
  PyMatcher/Iterations
  PyMatcher/Model
  PyMatcher/Path
  PyMatcher/Threshold
  Reg/Force3DoF
  Reg/RepeatOnce
  Reg/Strategy
  Rtabmap/ImagesAlreadyRectified
  Rtabmap/PublishRAMUsage
  SIFT/ContrastThreshold
  SIFT/EdgeThreshold
  SIFT/NFeatures
  SIFT/NOctaveLayers
  SIFT/RootSIFT
  SIFT/Sigma
  SURF/Extended
  SURF/GpuKeypointsRatio
  SURF/GpuVersion
  SURF/HessianThreshold
  SURF/OctaveLayers
  SURF/Octaves
  SURF/Upright
  SuperPoint/Cuda
  SuperPoint/ModelPath
  SuperPoint/NMS
  SuperPoint/NMSRadius
  SuperPoint/Threshold
  Vis/BundleAdjustment
  Vis/CorFlowEps
  Vis/CorFlowIterations
  Vis/CorFlowMaxLevel
  Vis/CorFlowWinSize
  Vis/CorGuessMatchToProjection
  Vis/CorGuessWinSize
  Vis/CorNNDR
  Vis/CorNNType
  Vis/CorType
  Vis/DepthAsMask
  Vis/EpipolarGeometryVar
  Vis/EstimationType
  Vis/FeatureType
  Vis/ForwardEstOnly
  Vis/GridCols
  Vis/GridRows
  Vis/InlierDistance
  Vis/Iterations
  Vis/MaxDepth
  Vis/MaxFeatures
  Vis/MeanInliersDistance
  Vis/MinDepth
  Vis/MinInliers
  Vis/MinInliersDistribution
  Vis/PnPFlags
  Vis/PnPMaxVariance
  Vis/PnPRefineIterations
  Vis/PnPReprojError
  Vis/RefineIterations
  Vis/RoiRatios
  Vis/SubPixEps
  Vis/SubPixIterations
  Vis/SubPixWinSize
  approx_sync
  approx_sync_max_interval
  config_path
  expected_update_rate
  frame_id
  g2o/Baseline
  g2o/Optimizer
  g2o/PixelVariance
  g2o/RobustKernelDelta
  g2o/Solver
  ground_truth_base_frame_id
  ground_truth_frame_id
  guess_frame_id
  guess_min_rotation
  guess_min_time
  guess_min_translation
  initial_pose
  keep_color
  log_to_rosout_level
  max_update_rate
  min_update_rate
  odom_frame_id
  publish_null_when_lost
  publish_tf
  qos
  qos_camera_info
  qos_overrides./clock.subscription.depth
  qos_overrides./clock.subscription.durability
  qos_overrides./clock.subscription.history
  qos_overrides./clock.subscription.reliability
  qos_overrides./parameter_events.publisher.depth
  qos_overrides./parameter_events.publisher.durability
  qos_overrides./parameter_events.publisher.history
  qos_overrides./parameter_events.publisher.reliability
  qos_overrides./tf.publisher.depth
  qos_overrides./tf.publisher.durability
  qos_overrides./tf.publisher.history
  qos_overrides./tf.publisher.reliability
  queue_size
  rgbd_cameras
  subscribe_rgbd
  use_sim_time
  wait_for_transform
  wait_imu_to_init
/robot_state_publisher:
  frame_prefix
  ignore_timestamp
  publish_frequency
  qos_overrides./joint_states.subscription.depth
  qos_overrides./joint_states.subscription.history
  qos_overrides./joint_states.subscription.reliability
  qos_overrides./parameter_events.publisher.depth
  qos_overrides./parameter_events.publisher.durability
  qos_overrides./parameter_events.publisher.history
  qos_overrides./parameter_events.publisher.reliability
  qos_overrides./tf.publisher.depth
  qos_overrides./tf.publisher.durability
  qos_overrides./tf.publisher.history
  qos_overrides./tf.publisher.reliability
  qos_overrides./tf_static.publisher.depth
  qos_overrides./tf_static.publisher.history
  qos_overrides./tf_static.publisher.reliability
  robot_description
  use_sim_time
/rtabmap:
  BRIEF/Bytes
  BRISK/Octaves
  BRISK/PatternScale
  BRISK/Thresh
  Bayes/FullPredictionUpdate
  Bayes/PredictionLC
  Bayes/VirtualPlacePriorThr
  Db/TargetVersion
  DbSqlite3/CacheSize
  DbSqlite3/InMemory
  DbSqlite3/JournalMode
  DbSqlite3/Synchronous
  DbSqlite3/TempStore
  FAST/CV
  FAST/Gpu
  FAST/GpuKeypointsRatio
  FAST/GridCols
  FAST/GridRows
  FAST/MaxThreshold
  FAST/MinThreshold
  FAST/NonmaxSuppression
  FAST/Threshold
  FREAK/NOctaves
  FREAK/OrientationNormalized
  FREAK/PatternScale
  FREAK/ScaleNormalized
  GFTT/BlockSize
  GFTT/K
  GFTT/MinDistance
  GFTT/QualityLevel
  GFTT/UseHarrisDetector
  GMS/ThresholdFactor
  GMS/WithRotation
  GMS/WithScale
  GTSAM/Optimizer
  Grid/3D
  Grid/CellSize
  Grid/ClusterRadius
  Grid/DepthDecimation
  Grid/DepthRoiRatios
  Grid/FlatObstacleDetected
  Grid/FootprintHeight
  Grid/FootprintLength
  Grid/FootprintWidth
  Grid/GroundIsObstacle
  Grid/MapFrameProjection
  Grid/MaxGroundAngle
  Grid/MaxGroundHeight
  Grid/MaxObstacleHeight
  Grid/MinClusterSize
  Grid/MinGroundHeight
  Grid/NoiseFilteringMinNeighbors
  Grid/NoiseFilteringRadius
  Grid/NormalK
  Grid/NormalsSegmentation
  Grid/PreVoxelFiltering
  Grid/RangeMax
  Grid/RangeMin
  Grid/RayTracing
  Grid/Scan2dUnknownSpaceFilled
  Grid/ScanDecimation
  Grid/Sensor
  GridGlobal/AltitudeDelta
  GridGlobal/Eroded
  GridGlobal/FloodFillDepth
  GridGlobal/FootprintRadius
  GridGlobal/FullUpdate
  GridGlobal/MaxNodes
  GridGlobal/MinSize
  GridGlobal/OccupancyThr
  GridGlobal/ProbClampingMax
  GridGlobal/ProbClampingMin
  GridGlobal/ProbHit
  GridGlobal/ProbMiss
  GridGlobal/UpdateError
  Icp/CCFilterOutFarthestPoints
  Icp/CCMaxFinalRMS
  Icp/CCSamplingLimit
  Icp/CorrespondenceRatio
  Icp/DebugExportFormat
  Icp/DownsamplingStep
  Icp/Epsilon
  Icp/Force4DoF
  Icp/Iterations
  Icp/MaxCorrespondenceDistance
  Icp/MaxRotation
  Icp/MaxTranslation
  Icp/OutlierRatio
  Icp/PMConfig
  Icp/PMMatcherEpsilon
  Icp/PMMatcherIntensity
  Icp/PMMatcherKnn
  Icp/PointToPlane
  Icp/PointToPlaneGroundNormalsUp
  Icp/PointToPlaneK
  Icp/PointToPlaneLowComplexityStrategy
  Icp/PointToPlaneMinComplexity
  Icp/PointToPlaneRadius
  Icp/RangeMax
  Icp/RangeMin
  Icp/ReciprocalCorrespondences
  Icp/Strategy
  Icp/VoxelSize
  ImuFilter/ComplementaryBiasAlpha
  ImuFilter/ComplementaryDoAdpativeGain
  ImuFilter/ComplementaryDoBiasEstimation
  ImuFilter/ComplementaryGainAcc
  ImuFilter/MadgwickGain
  ImuFilter/MadgwickZeta
  KAZE/Diffusivity
  KAZE/Extended
  KAZE/NOctaveLayers
  KAZE/NOctaves
  KAZE/Threshold
  KAZE/Upright
  Kp/BadSignRatio
  Kp/ByteToFloat
  Kp/DetectorStrategy
  Kp/DictionaryPath
  Kp/FlannRebalancingFactor
  Kp/GridCols
  Kp/GridRows
  Kp/IncrementalDictionary
  Kp/IncrementalFlann
  Kp/MaxDepth
  Kp/MaxFeatures
  Kp/MinDepth
  Kp/NNStrategy
  Kp/NewWordsComparedTogether
  Kp/NndrRatio
  Kp/Parallelized
  Kp/RoiRatios
  Kp/SubPixEps
  Kp/SubPixIterations
  Kp/SubPixWinSize
  Kp/TfIdfLikelihoodUsed
  Marker/CornerRefinementMethod
  Marker/Dictionary
  Marker/Length
  Marker/MaxDepthError
  Marker/MaxRange
  Marker/MinRange
  Marker/Priors
  Marker/PriorsVarianceAngular
  Marker/PriorsVarianceLinear
  Marker/VarianceAngular
  Marker/VarianceLinear
  Mem/BadSignaturesIgnored
  Mem/BinDataKept
  Mem/CompressionParallelized
  Mem/CovOffDiagIgnored
  Mem/DepthAsMask
  Mem/GenerateIds
  Mem/ImageCompressionFormat
  Mem/ImageKept
  Mem/ImagePostDecimation
  Mem/ImagePreDecimation
  Mem/IncrementalMemory
  Mem/InitWMWithAllNodes
  Mem/IntermediateNodeDataKept
  Mem/LaserScanDownsampleStepSize
  Mem/LaserScanNormalK
  Mem/LaserScanNormalRadius
  Mem/LaserScanVoxelSize
  Mem/LocalizationDataSaved
  Mem/MapLabelsAdded
  Mem/NotLinkedNodesKept
  Mem/RawDescriptorsKept
  Mem/RecentWmRatio
  Mem/ReduceGraph
  Mem/RehearsalIdUpdatedToNewOne
  Mem/RehearsalSimilarity
  Mem/RehearsalWeightIgnoredWhileMoving
  Mem/STMSize
  Mem/SaveDepth16Format
  Mem/StereoFromMotion
  Mem/TransferSortingByWeightId
  Mem/UseOdomFeatures
  Mem/UseOdomGravity
  ORB/EdgeThreshold
  ORB/FirstLevel
  ORB/Gpu
  ORB/NLevels
  ORB/PatchSize
  ORB/ScaleFactor
  ORB/ScoreType
  ORB/WTA_K
  Optimizer/Epsilon
  Optimizer/GravitySigma
  Optimizer/Iterations
  Optimizer/LandmarksIgnored
  Optimizer/PriorsIgnored
  Optimizer/Robust
  Optimizer/Strategy
  Optimizer/VarianceIgnored
  PyDetector/Cuda
  PyDetector/Path
  PyMatcher/Cuda
  PyMatcher/Iterations
  PyMatcher/Model
  PyMatcher/Path
  PyMatcher/Threshold
  RGBD/AngularSpeedUpdate
  RGBD/AngularUpdate
  RGBD/CreateOccupancyGrid
  RGBD/Enabled
  RGBD/GoalReachedRadius
  RGBD/GoalsSavedInUserData
  RGBD/InvertedReg
  RGBD/LinearSpeedUpdate
  RGBD/LinearUpdate
  RGBD/LocalBundleOnLoopClosure
  RGBD/LocalImmunizationRatio
  RGBD/LocalRadius
  RGBD/LoopClosureIdentityGuess
  RGBD/LoopClosureReextractFeatures
  RGBD/LoopCovLimited
  RGBD/MarkerDetection
  RGBD/MaxLocalRetrieved
  RGBD/MaxLoopClosureDistance
  RGBD/MaxOdomCacheSize
  RGBD/NeighborLinkRefining
  RGBD/NewMapOdomChangeDistance
  RGBD/OptimizeFromGraphEnd
  RGBD/OptimizeMaxError
  RGBD/PlanAngularVelocity
  RGBD/PlanLinearVelocity
  RGBD/PlanStuckIterations
  RGBD/ProximityAngle
  RGBD/ProximityBySpace
  RGBD/ProximityByTime
  RGBD/ProximityGlobalScanMap
  RGBD/ProximityMaxGraphDepth
  RGBD/ProximityMaxPaths
  RGBD/ProximityMergedScanCovFactor
  RGBD/ProximityOdomGuess
  RGBD/ProximityPathFilteringRadius
  RGBD/ProximityPathMaxNeighbors
  RGBD/ProximityPathRawPosesUsed
  RGBD/ScanMatchingIdsSavedInLinks
  RGBD/StartAtOrigin
  Reg/Force3DoF
  Reg/RepeatOnce
  Reg/Strategy
  Rtabmap/ComputeRMSE
  Rtabmap/CreateIntermediateNodes
  Rtabmap/DetectionRate
  Rtabmap/ImageBufferSize
  Rtabmap/ImagesAlreadyRectified
  Rtabmap/LoopGPS
  Rtabmap/LoopRatio
  Rtabmap/LoopThr
  Rtabmap/MaxRepublished
  Rtabmap/MaxRetrieved
  Rtabmap/MemoryThr
  Rtabmap/PublishLastSignature
  Rtabmap/PublishLikelihood
  Rtabmap/PublishPdf
  Rtabmap/PublishRAMUsage
  Rtabmap/PublishStats
  Rtabmap/RectifyOnlyFeatures
  Rtabmap/SaveWMState
  Rtabmap/StartNewMapOnGoodSignature
  Rtabmap/StartNewMapOnLoopClosure
  Rtabmap/StatisticLogged
  Rtabmap/StatisticLoggedHeaders
  Rtabmap/StatisticLogsBufferedInRAM
  Rtabmap/TimeThr
  Rtabmap/WorkingDirectory
  SIFT/ContrastThreshold
  SIFT/EdgeThreshold
  SIFT/NFeatures
  SIFT/NOctaveLayers
  SIFT/RootSIFT
  SIFT/Sigma
  SURF/Extended
  SURF/GpuKeypointsRatio
  SURF/GpuVersion
  SURF/HessianThreshold
  SURF/OctaveLayers
  SURF/Octaves
  SURF/Upright
  Stereo/DenseStrategy
  Stereo/Eps
  Stereo/Iterations
  Stereo/MaxDisparity
  Stereo/MaxLevel
  Stereo/MinDisparity
  Stereo/OpticalFlow
  Stereo/SSD
  Stereo/WinHeight
  Stereo/WinWidth
  StereoBM/BlockSize
  StereoBM/Disp12MaxDiff
  StereoBM/MinDisparity
  StereoBM/NumDisparities
  StereoBM/PreFilterCap
  StereoBM/PreFilterSize
  StereoBM/SpeckleRange
  StereoBM/SpeckleWindowSize
  StereoBM/TextureThreshold
  StereoBM/UniquenessRatio
  StereoSGBM/BlockSize
  StereoSGBM/Disp12MaxDiff
  StereoSGBM/MinDisparity
  StereoSGBM/Mode
  StereoSGBM/NumDisparities
  StereoSGBM/P1
  StereoSGBM/P2
  StereoSGBM/PreFilterCap
  StereoSGBM/SpeckleRange
  StereoSGBM/SpeckleWindowSize
  StereoSGBM/UniquenessRatio
  SuperPoint/Cuda
  SuperPoint/ModelPath
  SuperPoint/NMS
  SuperPoint/NMSRadius
  SuperPoint/Threshold
  VhEp/Enabled
  VhEp/MatchCountMin
  VhEp/RansacParam1
  VhEp/RansacParam2
  Vis/BundleAdjustment
  Vis/CorFlowEps
  Vis/CorFlowIterations
  Vis/CorFlowMaxLevel
  Vis/CorFlowWinSize
  Vis/CorGuessMatchToProjection
  Vis/CorGuessWinSize
  Vis/CorNNDR
  Vis/CorNNType
  Vis/CorType
  Vis/DepthAsMask
  Vis/EpipolarGeometryVar
  Vis/EstimationType
  Vis/FeatureType
  Vis/ForwardEstOnly
  Vis/GridCols
  Vis/GridRows
  Vis/InlierDistance
  Vis/Iterations
  Vis/MaxDepth
  Vis/MaxFeatures
  Vis/MeanInliersDistance
  Vis/MinDepth
  Vis/MinInliers
  Vis/MinInliersDistribution
  Vis/PnPFlags
  Vis/PnPMaxVariance
  Vis/PnPRefineIterations
  Vis/PnPReprojError
  Vis/RefineIterations
  Vis/RoiRatios
  Vis/SubPixEps
  Vis/SubPixIterations
  Vis/SubPixWinSize
  approx_sync
  cloud_output_voxelized
  cloud_subtract_filtering
  cloud_subtract_filtering_min_neighbors
  config_path
  database_path
  frame_id
  g2o/Baseline
  g2o/Optimizer
  g2o/PixelVariance
  g2o/RobustKernelDelta
  g2o/Solver
  gen_depth
  gen_depth_decimation
  gen_depth_fill_holes_error
  gen_depth_fill_holes_size
  gen_depth_fill_iterations
  gen_scan
  gen_scan_max_depth
  gen_scan_min_depth
  ground_truth_base_frame_id
  ground_truth_frame_id
  initial_pose
  is_rtabmap_paused
  landmark_angular_variance
  landmark_linear_variance
  latch
  log_to_rosout_level
  map_always_update
  map_cleanup
  map_empty_ray_tracing
  map_filter_angle
  map_filter_radius
  map_frame_id
  octomap_tree_depth
  odom_frame_id
  odom_frame_id_init
  odom_sensor_sync
  odom_tf_angular_variance
  odom_tf_linear_variance
  publish_tf
  qos
  qos_camera_info
  qos_gps
  qos_image
  qos_imu
  qos_odom
  qos_overrides./clock.subscription.depth
  qos_overrides./clock.subscription.durability
  qos_overrides./clock.subscription.history
  qos_overrides./clock.subscription.reliability
  qos_overrides./parameter_events.publisher.depth
  qos_overrides./parameter_events.publisher.durability
  qos_overrides./parameter_events.publisher.history
  qos_overrides./parameter_events.publisher.reliability
  qos_overrides./tf.publisher.depth
  qos_overrides./tf.publisher.durability
  qos_overrides./tf.publisher.history
  qos_overrides./tf.publisher.reliability
  qos_scan
  qos_user_data
  queue_size
  rgbd_cameras
  scan_cloud_is_2d
  scan_cloud_max_points
  stereo_to_depth
  subscribe_depth
  subscribe_odom
  subscribe_odom_info
  subscribe_rgb
  subscribe_rgbd
  subscribe_scan
  subscribe_scan_cloud
  subscribe_scan_descriptor
  subscribe_stereo
  subscribe_user_data
  tf_delay
  tf_tolerance
  use_action_for_goal
  use_saved_map
  use_sim_time
  wait_for_transform
/rtabmap_viz:
  approx_sync
  camera_node_name
  frame_id
  init_cache_path
  is_rtabmap_paused
  max_odom_update_rate
  odom_frame_id
  odom_sensor_sync
  qos
  qos_camera_info
  qos_image
  qos_odom
  qos_overrides./clock.subscription.depth
  qos_overrides./clock.subscription.durability
  qos_overrides./clock.subscription.history
  qos_overrides./clock.subscription.reliability
  qos_overrides./parameter_events.publisher.depth
  qos_overrides./parameter_events.publisher.durability
  qos_overrides./parameter_events.publisher.history
  qos_overrides./parameter_events.publisher.reliability
  qos_scan
  qos_user_data
  queue_size
  rgbd_cameras
  rtabmap
  subscribe_depth
  subscribe_odom
  subscribe_odom_info
  subscribe_rgb
  subscribe_rgbd
  subscribe_scan
  subscribe_scan_cloud
  subscribe_scan_descriptor
  subscribe_stereo
  subscribe_user_data
  use_sim_time
  wait_for_transform
/rviz:
  qos_overrides./parameter_events.publisher.depth
  qos_overrides./parameter_events.publisher.durability
  qos_overrides./parameter_events.publisher.history
  qos_overrides./parameter_events.publisher.reliability
  tf_buffer_cache_time_ms
  use_sim_time

and ros2 param get rtabmap use_sim_time Boolean value is: True

matlabbe commented 6 months ago

Are you using ros2 rtabmap binaries? I see version 0.21.1. There were some refactoring done to change when this message is shown. You may try latest code.

yuan-0816 commented 6 months ago

How to update the latest code.

matlabbe commented 6 months ago

See build from source here: https://github.com/introlab/rtabmap_ros/tree/ros2#from-source

yuan-0816 commented 5 months ago

It still the same, but I think the problem is from realsense gazebo plugin. When I try to use gazebo depth camera plugin, it is working! Thank you><