I added WITH_ORB_SLAM=ON in the CMake options and compiled it. I also added the directory related to ORB-SLAM3 in my .bashrc, but the output shows:
CMake Warning: Manually-specified variables were not used by the project: WITH_ORB_SLAM and RTAB-Map: 0.21.5 PCL: 1.10.0 With VTK: 7.1.1 OpenCV: 4.2.0 With OpenCV xfeatures2d: false With OpenCV nonfree: false With ORB OcTree: true With SuperPoint Torch: false With Python3: false With FastCV: false With OpenGV: false With Madgwick: true With PDAL: false With TORO: true With g2o: false With GTSAM: false With Vertigo: true With CVSBA: false With Ceres: false With OpenNI: false With OpenNI2: true With Freenect: false With Freenect2: false With K4W2: false With K4A: false With DC1394: true With FlyCapture2: false With ZED: false With ZED Open Capture: false With RealSense: false With RealSense SLAM: false With RealSense2: false With MYNT EYE S: false With DepthAI: false With XVisio SDK: false With libpointmatcher: false With CCCoreLib: false With Open3D: false With OctoMap: false With GridMap: false With cpu-tsdf: false With open chisel: false With Alice Vision: false With LOAM: false With FLOAM: false With FOVIS: false With Viso2: false With DVO: false With ORB_SLAM: false With OKVIS: false With MSCKF_VIO: false With VINS-Fusion: false With OpenVINS: false Why is this happening? |
Administrator
|
Is it by compiling directly the repo or from the ros2 workspace (colcon)?
If you build outside the ros2 workspace, check that cmake options are correctly set before building it: $ cd rtabmap/build $ cmake .. [...] -- Odometry Approaches: -- With loam_velodyne = NO (WITH_LOAM=OFF) -- With floam = NO (WITH_FLOAM=OFF) -- With libfovis = NO (WITH_FOVIS=OFF) -- With libviso2 = NO (WITH_VISO2=OFF) -- With dvo_core = NO (WITH_DVO=OFF) -- With okvis = NO (WITH_OKVIS=OFF) -- With msckf_vio = NO (WITH_MSCKF_VIO=OFF) -- With VINS-Fusion = NO (WITH_VINS=OFF) -- With OpenVINS = NO (WITH_OPENVINS=OFF) -- With ORB_SLAM = YES <--------------------------------------------- -- Show all options with: cmake -LA | grep WITH_ -- -------------------------------------------- -- Configuring done -- Generating done |
This post was updated on .
Thank you. Now I have completed the compilation and can see that the option for ORB-SLAM3 shows "yes." I am testing the robot's mapping in gazebo(rgbd). Here is my launch file:
def generate_launch_description(): parameters={ 'frame_id':'base_footprint', 'use_sim_time':True, 'subscribe_rgbd':True, 'subscribe_odom':True, } remappings=[ ('rgb/image', '/camera/rgb_camera/image_raw'), ('rgb/camera_info', '/camera/rgb_camera/camera_info'), ('depth/image', '/camera/rgb_camera/depth/image_raw'), ('odom', '/odom')] return LaunchDescription([ Node( package='rtabmap_odom', executable='rgbd_odometry', output='screen', parameters=[parameters, {'Odom/Strategy':'5', 'OdomORBSLAM/VocPath' : '/home/zyh/orbslam3/src/ORB_SLAM3/Vocabulary/ORBvoc.txt', 'OdomORBSLAM/configPath' : '/home/zyh/rtab/rtabmap_orbslam.yaml' , }], remappings=remappings, namespace="rtabmap"), Node( package='rtabmap_slam', executable='rtabmap', output='screen', parameters=[parameters], remappings=remappings, arguments=['-d'], namespace="rtabmap"), Node( package='rtabmap_viz', executable='rtabmap_viz', output='screen', parameters=[parameters], remappings=remappings, namespace="rtabmap"), ]) and yaml: %YAML:1.0 File.version: "1.0" Camera.type: "PinHole" Camera1.fx: 554.3827128226441 Camera1.fy: 554.3827128226441 Camera1.cx: 320.5000000000000 Camera1.cy: 240.5000000000000 Camera1.k1: 0.0000000000000 Camera1.k2: 0.0000000000000 Camera1.p1: 0.0000000000000 Camera1.p2: 0.0000000000000 Camera1.k3: 0.0000000000000 Camera.bf: 40.00 Camera.width: 640 Camera.height: 480 Camera.RGB: 1 Camera.fps: 30 Stereo.ThDepth: 40.0000000000000 Stereo.b: 0.0760000000000 RGBD.DepthMapFactor: 1.0000000000000 ORBextractor.nFeatures: 1000 ORBextractor.scaleFactor: 2.0000000000000 ORBextractor.nLevels: 3 ORBextractor.iniThFAST: 20 ORBextractor.minThFAST: 7 loopClosing: 0 Viewer.KeyFrameSize: 0.0500000000000 Viewer.KeyFrameLineWidth: 1.0000000000000 Viewer.GraphLineWidth: 0.9000000000000 Viewer.PointSize: 2.0000000000000 Viewer.CameraSize: 0.0800000000000 Viewer.CameraLineWidth: 3.0000000000000 Viewer.ViewpointX: 0.0000000000000 Viewer.ViewpointY: -0.7000000000000 Viewer.ViewpointZ: -3.5000000000000 Viewer.ViewpointF: 500.0000000000000 However, I encountered this error.: [INFO] [launch]: All log files can be found below /home/zyh/.ros/log/2025-08-18-17-31-49-407309-zyh-MS-7D48-72343 [INFO] [launch]: Default logging verbosity is set to INFO [INFO] [rgbd_odometry-1]: process started with pid [72346] [INFO] [rtabmap-2]: process started with pid [72348] [INFO] [rtabmap_viz-3]: process started with pid [72350] [rgbd_odometry-1] [INFO] [1755509509.717369858] [rtabmap.rgbd_odometry]: Odometry: frame_id = base_footprint [rgbd_odometry-1] [INFO] [1755509509.717501828] [rtabmap.rgbd_odometry]: Odometry: odom_frame_id = odom [rgbd_odometry-1] [INFO] [1755509509.717511763] [rtabmap.rgbd_odometry]: Odometry: publish_tf = true [rgbd_odometry-1] [INFO] [1755509509.717516009] [rtabmap.rgbd_odometry]: Odometry: wait_for_transform = 0.100000 [rgbd_odometry-1] [INFO] [1755509509.717527437] [rtabmap.rgbd_odometry]: Odometry: log_to_rosout_level = 4 [rgbd_odometry-1] [INFO] [1755509509.717545190] [rtabmap.rgbd_odometry]: Odometry: initial_pose = xyz=0.000000,0.000000,0.000000 rpy=0.000000,-0.000000,0.000000 [rgbd_odometry-1] [INFO] [1755509509.717549816] [rtabmap.rgbd_odometry]: Odometry: ground_truth_frame_id = [rgbd_odometry-1] [INFO] [1755509509.717553783] [rtabmap.rgbd_odometry]: Odometry: ground_truth_base_frame_id = base_footprint [rgbd_odometry-1] [INFO] [1755509509.717557788] [rtabmap.rgbd_odometry]: Odometry: config_path = [rgbd_odometry-1] [INFO] [1755509509.717561879] [rtabmap.rgbd_odometry]: Odometry: publish_null_when_lost = true [rgbd_odometry-1] [INFO] [1755509509.717565806] [rtabmap.rgbd_odometry]: Odometry: publish_compressed_sensor_data = false [rgbd_odometry-1] [INFO] [1755509509.717569817] [rtabmap.rgbd_odometry]: Odometry: guess_frame_id = [rgbd_odometry-1] [INFO] [1755509509.717573712] [rtabmap.rgbd_odometry]: Odometry: guess_min_translation = 0.000000 [rgbd_odometry-1] [INFO] [1755509509.717578334] [rtabmap.rgbd_odometry]: Odometry: guess_min_rotation = 0.000000 [rgbd_odometry-1] [INFO] [1755509509.717582719] [rtabmap.rgbd_odometry]: Odometry: guess_min_time = 0.000000 [rgbd_odometry-1] [INFO] [1755509509.717587161] [rtabmap.rgbd_odometry]: Odometry: expected_update_rate = 0.000000 Hz [rgbd_odometry-1] [INFO] [1755509509.717591657] [rtabmap.rgbd_odometry]: Odometry: max_update_rate = 0.000000 Hz [rgbd_odometry-1] [INFO] [1755509509.717595902] [rtabmap.rgbd_odometry]: Odometry: min_update_rate = 0.000000 Hz [rgbd_odometry-1] [INFO] [1755509509.717600095] [rtabmap.rgbd_odometry]: Odometry: wait_imu_to_init = false [rgbd_odometry-1] [INFO] [1755509509.717605279] [rtabmap.rgbd_odometry]: Odometry: sensor_data_compression_format = .jpg [rgbd_odometry-1] [INFO] [1755509509.717609098] [rtabmap.rgbd_odometry]: Odometry: sensor_data_parallel_compression = true [rgbd_odometry-1] [INFO] [1755509509.717656318] [rtabmap.rgbd_odometry]: Odometry: stereoParams_=0 visParams_=1 icpParams_=0 [rgbd_odometry-1] [INFO] [1755509509.720252016] [rtabmap.rgbd_odometry]: Setting odometry parameter "Odom/Strategy"="5" [rgbd_odometry-1] [INFO] [1755509509.722925607] [rtabmap.rgbd_odometry]: Setting odometry parameter "OdomORBSLAM/VocPath"="/home/zyh/orbslam3/src/ORB_SLAM3/Vocabulary/ORBvoc.txt" [rgbd_odometry-1] [INFO] [1755509509.736687251] [rtabmap.rgbd_odometry]: RGBDOdometry: approx_sync = false [rgbd_odometry-1] [INFO] [1755509509.737179926] [rtabmap.rgbd_odometry]: RGBDOdometry: topic_queue_size = 1 [rgbd_odometry-1] [INFO] [1755509509.737361054] [rtabmap.rgbd_odometry]: RGBDOdometry: sync_queue_size = 5 [rgbd_odometry-1] [INFO] [1755509509.737494025] [rtabmap.rgbd_odometry]: RGBDOdometry: qos = 0 [rgbd_odometry-1] [INFO] [1755509509.737624329] [rtabmap.rgbd_odometry]: RGBDOdometry: qos_camera_info = 0 [rgbd_odometry-1] [INFO] [1755509509.737749187] [rtabmap.rgbd_odometry]: RGBDOdometry: subscribe_rgbd = true [rgbd_odometry-1] [INFO] [1755509509.737870784] [rtabmap.rgbd_odometry]: RGBDOdometry: rgbd_cameras = 1 [rgbd_odometry-1] [INFO] [1755509509.737990784] [rtabmap.rgbd_odometry]: RGBDOdometry: keep_color = false [rgbd_odometry-1] [INFO] [1755509509.739138046] [rtabmap.rgbd_odometry]: [rgbd_odometry-1] rgbd_odometry subscribed to: [rgbd_odometry-1] /rtabmap/rgbd_image [rtabmap-2] [INFO] [1755509509.778198813] [rtabmap.rtabmap]: rtabmap(maps): latch = true [rtabmap-2] [INFO] [1755509509.778511061] [rtabmap.rtabmap]: rtabmap(maps): map_filter_radius = 0.000000 [rtabmap-2] [INFO] [1755509509.778531765] [rtabmap.rtabmap]: rtabmap(maps): map_filter_angle = 30.000000 [rtabmap-2] [INFO] [1755509509.778539465] [rtabmap.rtabmap]: rtabmap(maps): map_cleanup = true [rtabmap-2] [INFO] [1755509509.778543866] [rtabmap.rtabmap]: rtabmap(maps): map_always_update = false [rtabmap-2] [INFO] [1755509509.778548126] [rtabmap.rtabmap]: rtabmap(maps): map_empty_ray_tracing = true [rtabmap-2] [INFO] [1755509509.778552149] [rtabmap.rtabmap]: rtabmap(maps): cloud_output_voxelized = true [rtabmap-2] [INFO] [1755509509.778557284] [rtabmap.rtabmap]: rtabmap(maps): cloud_subtract_filtering = false [rtabmap-2] [INFO] [1755509509.778561668] [rtabmap.rtabmap]: rtabmap(maps): cloud_subtract_filtering_min_neighbors = 2 [rtabmap-2] [INFO] [1755509509.778580980] [rtabmap.rtabmap]: rtabmap(maps): octomap_tree_depth = 16 [rtabmap-2] [INFO] [1755509509.786993925] [rtabmap.rtabmap]: rtabmap: frame_id = base_footprint [rtabmap-2] [INFO] [1755509509.787028666] [rtabmap.rtabmap]: rtabmap: map_frame_id = map [rtabmap-2] [INFO] [1755509509.787035634] [rtabmap.rtabmap]: rtabmap: log_to_rosout_level = 4 [rtabmap-2] [INFO] [1755509509.787040406] [rtabmap.rtabmap]: rtabmap: initial_pose = [rtabmap-2] [INFO] [1755509509.787044589] [rtabmap.rtabmap]: rtabmap: use_action_for_goal = false [rtabmap-2] [INFO] [1755509509.787049037] [rtabmap.rtabmap]: rtabmap: tf_delay = 0.050000 [rtabmap-2] [INFO] [1755509509.787059702] [rtabmap.rtabmap]: rtabmap: tf_tolerance = 0.100000 [rtabmap-2] [INFO] [1755509509.787064545] [rtabmap.rtabmap]: rtabmap: odom_sensor_sync = false [rtabmap-2] [INFO] [1755509509.787068530] [rtabmap.rtabmap]: rtabmap: pub_loc_pose_only_when_localizing = false [rtabmap-2] [INFO] [1755509509.787074702] [rtabmap.rtabmap]: rtabmap: gen_scan = false [rtabmap-2] [INFO] [1755509509.787079074] [rtabmap.rtabmap]: rtabmap: gen_depth = false [rtabmap-2] [INFO] [1755509509.853291791] [rtabmap.rtabmap]: RTAB-Map detection rate = 10.000000 Hz [rtabmap-2] [INFO] [1755509509.853453241] [rtabmap.rtabmap]: rtabmap: Deleted database "/home/zyh/.ros/rtabmap.db" (--delete_db_on_start or -d are set). [rtabmap-2] [INFO] [1755509509.853468124] [rtabmap.rtabmap]: rtabmap: Using database from "/home/zyh/.ros/rtabmap.db" (0 MB). [rtabmap_viz-3] [INFO] [1755509509.894496059] [rtabmap.rtabmap_viz]: rtabmap_viz: Using configuration from "/home/zyh/.ros/rtabmapGUI.ini" [rtabmap_viz-3] libpng warning: iCCP: known incorrect sRGB profile [rtabmap_viz-3] libpng warning: iCCP: known incorrect sRGB profile [rtabmap_viz-3] libpng warning: iCCP: known incorrect sRGB profile [rgbd_odometry-1] [WARN] [1755509510.741832720] [rtabmap.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: [rgbd_odometry-1] /rtabmap/rgbd_image [rtabmap_viz-3] [WARN] [1755509510.805529927] [rcl.logging_rosout]: Publisher already registered for provided node name. If this is due to multiple nodes with the same name then all logs for that logger name will go out over the existing publisher. As soon as any node with that name is destructed it will unregister the publisher, preventing any further logs for that name from being published on the rosout topic. [rtabmap_viz-3] [INFO] [1755509510.807080185] [rtabmap.rtabmap_viz]: Reading parameters from the ROS server... [rtabmap-2] [INFO] [1755509512.939720187] [rtabmap.rtabmap]: rtabmap: Database version = "0.21.5". [rtabmap-2] [INFO] [1755509512.939760979] [rtabmap.rtabmap]: rtabmap: SLAM mode (Mem/IncrementalMemory=true) [rtabmap-2] [INFO] [1755509512.953539179] [rtabmap.rtabmap]: Setup callbacks [rtabmap-2] [WARN] [1755509512.953651838] [rtabmap.rtabmap]: rtabmap: Parameters subscribe_depth and subscribe_rgbd cannot be true at the same time. Parameter subscribe_depth is set to false. [rtabmap-2] [INFO] [1755509512.953694136] [rtabmap.rtabmap]: rtabmap: subscribe_depth = false [rtabmap-2] [INFO] [1755509512.953702239] [rtabmap.rtabmap]: rtabmap: subscribe_rgb = false [rtabmap-2] [INFO] [1755509512.953709251] [rtabmap.rtabmap]: rtabmap: subscribe_stereo = false [rtabmap-2] [INFO] [1755509512.953714153] [rtabmap.rtabmap]: rtabmap: subscribe_rgbd = true (rgbd_cameras=1) [rtabmap-2] [INFO] [1755509512.953719974] [rtabmap.rtabmap]: rtabmap: subscribe_sensor_data = false [rtabmap-2] [INFO] [1755509512.953725890] [rtabmap.rtabmap]: rtabmap: subscribe_odom_info = false [rtabmap-2] [INFO] [1755509512.953731344] [rtabmap.rtabmap]: rtabmap: subscribe_user_data = false [rtabmap-2] [INFO] [1755509512.953735934] [rtabmap.rtabmap]: rtabmap: subscribe_scan = false [rtabmap-2] [INFO] [1755509512.953741005] [rtabmap.rtabmap]: rtabmap: subscribe_scan_cloud = false [rtabmap-2] [INFO] [1755509512.953744362] [rtabmap.rtabmap]: rtabmap: subscribe_scan_descriptor = false [rtabmap-2] [INFO] [1755509512.953749466] [rtabmap.rtabmap]: rtabmap: topic_queue_size = 1 [rtabmap-2] [INFO] [1755509512.953753824] [rtabmap.rtabmap]: rtabmap: sync_queue_size = 10 [rtabmap-2] [INFO] [1755509512.953758947] [rtabmap.rtabmap]: rtabmap: qos_image = 0 [rtabmap-2] [INFO] [1755509512.953763520] [rtabmap.rtabmap]: rtabmap: qos_camera_info = 0 [rtabmap-2] [INFO] [1755509512.953767673] [rtabmap.rtabmap]: rtabmap: qos_scan = 0 [rtabmap-2] [INFO] [1755509512.953770446] [rtabmap.rtabmap]: rtabmap: qos_odom = 0 [rtabmap-2] [INFO] [1755509512.953773532] [rtabmap.rtabmap]: rtabmap: qos_user_data = 0 [rtabmap-2] [INFO] [1755509512.953817543] [rtabmap.rtabmap]: rtabmap: approx_sync = false [rtabmap-2] [INFO] [1755509512.953826223] [rtabmap.rtabmap]: Setup rgbd callback [rtabmap-2] [INFO] [1755509512.956320017] [rtabmap.rtabmap]: [rtabmap-2] rtabmap subscribed to (exact sync): [rtabmap-2] /odom \ [rtabmap-2] /rtabmap/rgbd_image [rtabmap_viz-3] [INFO] [1755509513.068983742] [rtabmap.rtabmap_viz]: Parameters read = 377 [rtabmap_viz-3] [INFO] [1755509513.069033486] [rtabmap.rtabmap_viz]: Parameters successfully read. [rtabmap-2] [WARN] [1755509513.958281106] [rtabmap.rtabmap]: rtabmap: Did not receive data since 5 seconds! Make sure the input topics are published ("$ ros2 topic 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"). Parameter "approx_sync" is false, which means that input topics should have all the exact timestamp for the callback to be called. Why is this happening? |
Administrator
|
rgbd_odometry is subscribing to "/rtabmap/rgbd_image", which doesn't exist.
[rgbd_odometry-1] rgbd_odometry subscribed to: [rgbd_odometry-1] /rtabmap/rgbd_image Based on your remappings, set "subscribe_rgbd: False" or don't set it explicitly at all. It should then subscribe to RGB, depth and camera_info topics. |
Free forum by Nabble | Edit this page |