introlab / rtabmap_ros

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

D435+ROS Noetic+RTABMap does not start #1175

Open TDVL opened 1 week ago

TDVL commented 1 week ago

Dear Support Team, I have installed the D435 RealSense ROS Wrapper and it works well (using .udo apt-get install ros-noetic-realsense2-camera). Also, I have installed RTABMap using sudo apt-get install ros-noetic-rtabmap-ros and it starts. however I cannot see the mapping procedure and I have warnings.

aci@laci-Inspiron-3881:~/catkin_ws$ roslaunch rtabmap_launch rtabmap.launch \ rtabmap_args:="--delete_db_on_start" \depth_topic:=/camera/aligned_depth_to_color/image_raw \ rgb_topic:=/camera/color/image_raw \ camera_info_topic:=/camera/color/camera_inf \ approx_sync:=false
... logging to /home/laci/.ros/log/b26f8ca6-2c1a-11ef-81f6-87be2e758d6d/roslaunch-laci-Inspiron-3881-34997.log
Checking log directory for disk usage. This may take a while.
Press Ctrl-C to interrupt
Done checking log file disk usage. Usage is <1GB.

started roslaunch server http://laci-Inspiron-3881:38563/

SUMMARY
========

CLEAR PARAMETERS
 * /rtabmap/rgbd_odometry/
 * /rtabmap/rtabmap/
 * /rtabmap/rtabmap_viz/

PARAMETERS
 * /rosdistro: noetic
 * /rosversion: 1.16.0
 * /rtabmap/rgbd_odometry/approx_sync: True
 * /rtabmap/rgbd_odometry/approx_sync_max_interval: 0.0
 * /rtabmap/rgbd_odometry/config_path: 
 * /rtabmap/rgbd_odometry/expected_update_rate: 0.0
 * /rtabmap/rgbd_odometry/frame_id: camera_link
 * /rtabmap/rgbd_odometry/ground_truth_base_frame_id: 
 * /rtabmap/rgbd_odometry/ground_truth_frame_id: 
 * /rtabmap/rgbd_odometry/guess_frame_id: 
 * /rtabmap/rgbd_odometry/guess_min_rotation: 0.0
 * /rtabmap/rgbd_odometry/guess_min_translation: 0.0
 * /rtabmap/rgbd_odometry/keep_color: False
 * /rtabmap/rgbd_odometry/max_update_rate: 0.0
 * /rtabmap/rgbd_odometry/odom_frame_id: odom
 * /rtabmap/rgbd_odometry/publish_tf: True
 * /rtabmap/rgbd_odometry/queue_size: 10
 * /rtabmap/rgbd_odometry/subscribe_rgbd: False
 * /rtabmap/rgbd_odometry/wait_for_transform_duration: 0.2
 * /rtabmap/rgbd_odometry/wait_imu_to_init: False
 * /rtabmap/rtabmap/Mem/IncrementalMemory: true
 * /rtabmap/rtabmap/Mem/InitWMWithAllNodes: false
 * /rtabmap/rtabmap/approx_sync: True
 * /rtabmap/rtabmap/config_path: 
 * /rtabmap/rtabmap/database_path: ~/.ros/rtabmap.db
 * /rtabmap/rtabmap/frame_id: camera_link
 * /rtabmap/rtabmap/gen_depth: False
 * /rtabmap/rtabmap/gen_depth_decimation: 1
 * /rtabmap/rtabmap/gen_depth_fill_holes_error: 0.1
 * /rtabmap/rtabmap/gen_depth_fill_holes_size: 0
 * /rtabmap/rtabmap/gen_depth_fill_iterations: 1
 * /rtabmap/rtabmap/gen_scan: False
 * /rtabmap/rtabmap/ground_truth_base_frame_id: 
 * /rtabmap/rtabmap/ground_truth_frame_id: 
 * /rtabmap/rtabmap/initial_pose: 
 * /rtabmap/rtabmap/landmark_angular_variance: 9999.0
 * /rtabmap/rtabmap/landmark_linear_variance: 0.0001
 * /rtabmap/rtabmap/loc_thr: 0.0
 * /rtabmap/rtabmap/map_frame_id: map
 * /rtabmap/rtabmap/odom_frame_id: 
 * /rtabmap/rtabmap/odom_frame_id_init: 
 * /rtabmap/rtabmap/odom_sensor_sync: False
 * /rtabmap/rtabmap/odom_tf_angular_variance: 0.001
 * /rtabmap/rtabmap/odom_tf_linear_variance: 0.001
 * /rtabmap/rtabmap/publish_tf: True
 * /rtabmap/rtabmap/queue_size: 10
 * /rtabmap/rtabmap/scan_cloud_max_points: 0
 * /rtabmap/rtabmap/subscribe_depth: True
 * /rtabmap/rtabmap/subscribe_odom_info: True
 * /rtabmap/rtabmap/subscribe_rgb: True
 * /rtabmap/rtabmap/subscribe_rgbd: False
 * /rtabmap/rtabmap/subscribe_scan: False
 * /rtabmap/rtabmap/subscribe_scan_cloud: False
 * /rtabmap/rtabmap/subscribe_scan_descriptor: False
 * /rtabmap/rtabmap/subscribe_stereo: False
 * /rtabmap/rtabmap/subscribe_user_data: False
 * /rtabmap/rtabmap/wait_for_transform_duration: 0.2
 * /rtabmap/rtabmap_viz/approx_sync: True
 * /rtabmap/rtabmap_viz/frame_id: camera_link
 * /rtabmap/rtabmap_viz/odom_frame_id: 
 * /rtabmap/rtabmap_viz/queue_size: 10
 * /rtabmap/rtabmap_viz/subscribe_depth: True
 * /rtabmap/rtabmap_viz/subscribe_odom_info: True
 * /rtabmap/rtabmap_viz/subscribe_rgb: True
 * /rtabmap/rtabmap_viz/subscribe_rgbd: False
 * /rtabmap/rtabmap_viz/subscribe_scan: False
 * /rtabmap/rtabmap_viz/subscribe_scan_cloud: False
 * /rtabmap/rtabmap_viz/subscribe_scan_descriptor: False
 * /rtabmap/rtabmap_viz/subscribe_stereo: False
 * /rtabmap/rtabmap_viz/wait_for_transform_duration: 0.2

NODES
  /rtabmap/
    rgbd_odometry (rtabmap_odom/rgbd_odometry)
    rtabmap (rtabmap_slam/rtabmap)
    rtabmap_viz (rtabmap_viz/rtabmap_viz)

ROS_MASTER_URI=http://localhost:11311

process[rtabmap/rgbd_odometry-1]: started with pid [35012]
process[rtabmap/rtabmap-2]: started with pid [35013]
process[rtabmap/rtabmap_viz-3]: started with pid [35014]
[ INFO] [1718567890.746315510]: Starting node...
[ INFO] [1718567890.776264985]: Initializing nodelet with 16 worker threads.
[ INFO] [1718567890.800199097]: Initializing nodelet with 16 worker threads.
[ INFO] [1718567890.842930110]: Starting node...
[ INFO] [1718567890.844351330]: Odometry: frame_id               = camera_link
[ INFO] [1718567890.844377823]: Odometry: odom_frame_id          = odom
[ INFO] [1718567890.844388915]: Odometry: publish_tf             = true
[ INFO] [1718567890.844398687]: Odometry: wait_for_transform     = true
[ INFO] [1718567890.844413975]: Odometry: wait_for_transform_duration  = 0.200000
[ INFO] [1718567890.844424581]: Odometry: log_to_rosout_level    = 4
[ INFO] [1718567890.844448705]: Odometry: initial_pose           = xyz=0.000000,0.000000,0.000000 rpy=0.000000,-0.000000,0.000000
[ INFO] [1718567890.844459495]: Odometry: ground_truth_frame_id  = 
[ INFO] [1718567890.844469063]: Odometry: ground_truth_base_frame_id = 
[ INFO] [1718567890.844478164]: Odometry: config_path            = 
[ INFO] [1718567890.844487191]: Odometry: publish_null_when_lost = true
[ INFO] [1718567890.844496153]: Odometry: publish_compressed_sensor_data = false
[ INFO] [1718567890.844505421]: Odometry: guess_frame_id         = 
[ INFO] [1718567890.844515495]: Odometry: guess_min_translation  = 0.000000
[ INFO] [1718567890.844528022]: Odometry: guess_min_rotation     = 0.000000
[ INFO] [1718567890.844537675]: Odometry: guess_min_time         = 0.000000
[ INFO] [1718567890.844547349]: Odometry: expected_update_rate   = 0.000000 Hz
[ INFO] [1718567890.844558701]: Odometry: max_update_rate        = 0.000000 Hz
[ INFO] [1718567890.844568565]: Odometry: min_update_rate        = 0.000000 Hz
[ INFO] [1718567890.844577760]: Odometry: wait_imu_to_init       = false
[ INFO] [1718567890.844588339]: Odometry: sensor_data_compression_format   = .jpg
[ INFO] [1718567890.844597767]: Odometry: sensor_data_parallel_compression = true
[ INFO] [1718567890.844618262]: Odometry: stereoParams_=0 visParams_=1 icpParams_=0
[ INFO] [1718567890.907355964]: /rtabmap/rtabmap(maps): map_filter_radius          = 0.000000
[ INFO] [1718567890.907391993]: /rtabmap/rtabmap(maps): map_filter_angle           = 30.000000
[ INFO] [1718567890.907422914]: /rtabmap/rtabmap(maps): map_cleanup                = true
[ INFO] [1718567890.907446335]: /rtabmap/rtabmap(maps): map_always_update          = false
[ INFO] [1718567890.907453183]: /rtabmap/rtabmap(maps): map_empty_ray_tracing      = true
[ INFO] [1718567890.907459565]: /rtabmap/rtabmap(maps): cloud_output_voxelized     = true
[ INFO] [1718567890.907465740]: /rtabmap/rtabmap(maps): cloud_subtract_filtering   = false
[ INFO] [1718567890.907487102]: /rtabmap/rtabmap(maps): cloud_subtract_filtering_min_neighbors = 2
[ INFO] [1718567890.907761581]: /rtabmap/rtabmap(maps): octomap_tree_depth         = 16
[ INFO] [1718567890.934982265]: rtabmap: frame_id      = camera_link
[ INFO] [1718567890.935038889]: rtabmap: map_frame_id  = map
[ INFO] [1718567890.935057998]: rtabmap: log_to_rosout_level = 4
[ INFO] [1718567890.935091467]: rtabmap: initial_pose  = 
[ INFO] [1718567890.935121623]: rtabmap: use_action_for_goal  = false
[ INFO] [1718567890.935160415]: rtabmap: tf_delay      = 0.050000
[ INFO] [1718567890.935175848]: rtabmap: tf_tolerance  = 0.100000
[ INFO] [1718567890.935221373]: rtabmap: odom_sensor_sync   = false
[ INFO] [1718567890.935253258]: rtabmap: pub_loc_pose_only_when_localizing = false
[ INFO] [1718567890.935849208]: rtabmap: gen_scan  = false
[ INFO] [1718567890.935868513]: rtabmap: gen_depth  = false
[ INFO] [1718567891.014756450]: rtabmap_viz: Using configuration from "/home/laci/.ros/rtabmap_gui.ini"
[ INFO] [1718567891.123532365]: Setting RTAB-Map parameter "Mem/IncrementalMemory"="true"
[ INFO] [1718567891.123877835]: Setting RTAB-Map parameter "Mem/InitWMWithAllNodes"="false"
[ INFO] [1718567891.348218181]: RGBDOdometry: approx_sync    = true
[ INFO] [1718567891.348259300]: RGBDOdometry: approx_sync_max_interval = 0.000000
[ INFO] [1718567891.348267436]: RGBDOdometry: queue_size     = 10
[ INFO] [1718567891.348291860]: RGBDOdometry: subscribe_rgbd = false
[ INFO] [1718567891.348298546]: RGBDOdometry: rgbd_cameras   = 1
[ INFO] [1718567891.348322438]: RGBDOdometry: keep_color     = false
[ INFO] [1718567891.357180770]: 
/rtabmap/rgbd_odometry subscribed to (approx sync):
   /camera/rgb/image_rect_color \
   /camera/aligned_depth_to_color/image_raw \
   /camera/rgb/camera_info
[ INFO] [1718567891.425620238]: Update RTAB-Map parameter "Kp/DetectorStrategy"="6" from database
[ INFO] [1718567891.425669086]: Update RTAB-Map parameter "Mem/ImagePostDecimation"="2" from database
[ INFO] [1718567891.425679727]: Update RTAB-Map parameter "Mem/ImagePreDecimation"="2" from database
[ INFO] [1718567891.425692197]: Update RTAB-Map parameter "Mem/UseOdomFeatures"="false" from database
[ INFO] [1718567891.425755315]: Update RTAB-Map parameter "Vis/MaxFeatures"="500" from database
[ INFO] [1718567891.425899731]: RTAB-Map detection rate = 1.000000 Hz
[ INFO] [1718567891.426117230]: rtabmap: Using database from "/home/laci/.ros/rtabmap.db" (0 MB).
[ WARN] (2024-06-16 21:58:11.427) Features2d.cpp:561::create() BRIEF, FREAK and DAISY features cannot be used because OpenCV was not built with xfeatures2d module. GFTT/ORB is used instead.
[ WARN] (2024-06-16 21:58:11.429) Features2d.cpp:561::create() BRIEF, FREAK and DAISY features cannot be used because OpenCV was not built with xfeatures2d module. GFTT/ORB is used instead.
[ WARN] (2024-06-16 21:58:11.431) Features2d.cpp:561::create() BRIEF, FREAK and DAISY features cannot be used because OpenCV was not built with xfeatures2d module. GFTT/ORB is used instead.
[ WARN] (2024-06-16 21:58:11.433) Features2d.cpp:561::create() BRIEF, FREAK and DAISY features cannot be used because OpenCV was not built with xfeatures2d module. GFTT/ORB is used instead.
[ INFO] [1718567891.435439484]: rtabmap: Database version = "0.21.4".
[ INFO] [1718567891.435471254]: rtabmap: SLAM mode (Mem/IncrementalMemory=true)
[ INFO] [1718567891.450560737]: /rtabmap/rtabmap: subscribe_depth = true
[ INFO] [1718567891.450586663]: /rtabmap/rtabmap: subscribe_rgb = true
[ INFO] [1718567891.450596916]: /rtabmap/rtabmap: subscribe_stereo = false
[ INFO] [1718567891.450629695]: /rtabmap/rtabmap: subscribe_rgbd = false (rgbd_cameras=1)
[ INFO] [1718567891.450645676]: /rtabmap/rtabmap: subscribe_sensor_data = false
[ INFO] [1718567891.450654724]: /rtabmap/rtabmap: subscribe_odom_info = true
[ INFO] [1718567891.450663811]: /rtabmap/rtabmap: subscribe_user_data = false
[ INFO] [1718567891.450674410]: /rtabmap/rtabmap: subscribe_scan = false
[ INFO] [1718567891.450687766]: /rtabmap/rtabmap: subscribe_scan_cloud = false
[ INFO] [1718567891.450697763]: /rtabmap/rtabmap: subscribe_scan_descriptor = false
[ INFO] [1718567891.450708964]: /rtabmap/rtabmap: queue_size    = 10
[ INFO] [1718567891.450718600]: /rtabmap/rtabmap: approx_sync   = true
[ INFO] [1718567891.450784380]: Setup depth callback
[ INFO] [1718567891.458912516]: 
/rtabmap/rtabmap subscribed to (approx sync):
   /rtabmap/odom \
   /camera/rgb/image_rect_color \
   /camera/aligned_depth_to_color/image_raw \
   /camera/rgb/camera_info \
   /rtabmap/odom_info
[ INFO] [1718567891.539093461]: rtabmap 0.21.4 started...
libpng warning: iCCP: known incorrect sRGB profile
libpng warning: iCCP: known incorrect sRGB profile
libpng warning: iCCP: known incorrect sRGB profile
[ INFO] [1718567891.890981282]: rtabmap_viz: Reading parameters from the ROS server...
[ INFO] [1718567892.033137350]: rtabmap_viz: Parameters read = 365
[ INFO] [1718567892.033157854]: rtabmap_viz: Parameters successfully read.
[ INFO] [1718567892.291799598]: /rtabmap/rtabmap_viz: subscribe_depth = true
[ INFO] [1718567892.291824382]: /rtabmap/rtabmap_viz: subscribe_rgb = true
[ INFO] [1718567892.291834728]: /rtabmap/rtabmap_viz: subscribe_stereo = false
[ INFO] [1718567892.291845044]: /rtabmap/rtabmap_viz: subscribe_rgbd = false (rgbd_cameras=1)
[ INFO] [1718567892.291854635]: /rtabmap/rtabmap_viz: subscribe_sensor_data = false
[ INFO] [1718567892.291864484]: /rtabmap/rtabmap_viz: subscribe_odom_info = true
[ INFO] [1718567892.291874713]: /rtabmap/rtabmap_viz: subscribe_user_data = false
[ INFO] [1718567892.291888000]: /rtabmap/rtabmap_viz: subscribe_scan = false
[ INFO] [1718567892.291900274]: /rtabmap/rtabmap_viz: subscribe_scan_cloud = false
[ INFO] [1718567892.291911975]: /rtabmap/rtabmap_viz: subscribe_scan_descriptor = false
[ INFO] [1718567892.291923043]: /rtabmap/rtabmap_viz: queue_size    = 10
[ INFO] [1718567892.291934337]: /rtabmap/rtabmap_viz: approx_sync   = true
[ INFO] [1718567892.292001355]: Setup depth callback
[ INFO] [1718567892.316797541]: 
/rtabmap/rtabmap_viz subscribed to (approx sync):
   /rtabmap/odom \
   /camera/rgb/image_rect_color \
   /camera/aligned_depth_to_color/image_raw \
   /camera/rgb/camera_info \
   /rtabmap/odom_info
[ INFO] [1718567892.318205829]: rtabmap_viz started.
[ WARN] [1718567895.358782087]: /rtabmap/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. 
/rtabmap/rgbd_odometry subscribed to (approx sync):
   /camera/rgb/image_rect_color \
   /camera/aligned_depth_to_color/image_raw \
   /camera/rgb/camera_info
[ WARN] [1718567895.459850084]: /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).
/rtabmap/rtabmap subscribed to (approx sync):
   /rtabmap/odom \
   /camera/rgb/image_rect_color \
   /camera/aligned_depth_to_color/image_raw \
   /camera/rgb/camera_info \
   /rtabmap/odom_info
[ WARN] [1718567896.318221676]: /rtabmap/rtabmap_viz: 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).
/rtabmap/rtabmap_viz subscribed to (approx sync):
   /rtabmap/odom \
   /camera/rgb/image_rect_color \
   /camera/aligned_depth_to_color/image_raw \
   /camera/rgb/camera_info \
   /rtabmap/odom_info

This is the rostopic list:

rostopic list

/camera/align_to_color/parameter_descriptions
/camera/align_to_color/parameter_updates
/camera/aligned_depth_to_color/camera_info
/camera/aligned_depth_to_color/image_raw
/camera/aligned_depth_to_color/image_raw/compressed
/camera/aligned_depth_to_color/image_raw/compressed/parameter_descriptions
/camera/aligned_depth_to_color/image_raw/compressed/parameter_updates
/camera/aligned_depth_to_color/image_raw/compressedDepth
/camera/aligned_depth_to_color/image_raw/compressedDepth/parameter_descriptions
/camera/aligned_depth_to_color/image_raw/compressedDepth/parameter_updates
/camera/aligned_depth_to_color/image_raw/theora
/camera/aligned_depth_to_color/image_raw/theora/parameter_descriptions
/camera/aligned_depth_to_color/image_raw/theora/parameter_updates
/camera/color/camera_info
/camera/color/image_raw
/camera/color/image_raw/compressed
/camera/color/image_raw/compressed/parameter_descriptions
/camera/color/image_raw/compressed/parameter_updates
/camera/color/image_raw/compressedDepth
/camera/color/image_raw/compressedDepth/parameter_descriptions
/camera/color/image_raw/compressedDepth/parameter_updates
/camera/color/image_raw/theora
/camera/color/image_raw/theora/parameter_descriptions
/camera/color/image_raw/theora/parameter_updates
/camera/color/metadata
/camera/depth/camera_info
/camera/depth/color/points
/camera/depth/image_rect_raw
/camera/depth/image_rect_raw/compressed
/camera/depth/image_rect_raw/compressed/parameter_descriptions
/camera/depth/image_rect_raw/compressed/parameter_updates
/camera/depth/image_rect_raw/compressedDepth
/camera/depth/image_rect_raw/compressedDepth/parameter_descriptions
/camera/depth/image_rect_raw/compressedDepth/parameter_updates
/camera/depth/image_rect_raw/theora
/camera/depth/image_rect_raw/theora/parameter_descriptions
/camera/depth/image_rect_raw/theora/parameter_updates
/camera/depth/metadata
/camera/extrinsics/depth_to_color
/camera/pointcloud/parameter_descriptions
/camera/pointcloud/parameter_updates
/camera/realsense2_camera_manager/bond
/camera/rgb/camera_info
/camera/rgb/image_rect_color
/camera/rgb_camera/auto_exposure_roi/parameter_descriptions
/camera/rgb_camera/auto_exposure_roi/parameter_updates
/camera/rgb_camera/parameter_descriptions
/camera/rgb_camera/parameter_updates
/camera/stereo_module/auto_exposure_roi/parameter_descriptions
/camera/stereo_module/auto_exposure_roi/parameter_updates
/camera/stereo_module/parameter_descriptions
/camera/stereo_module/parameter_updates
/diagnostics
/gps/fix
/imu/data
/rosout
/rosout_agg
/rtabmap/cloud_ground
/rtabmap/cloud_map
/rtabmap/cloud_obstacles
/rtabmap/elevation_map
/rtabmap/global_path
/rtabmap/global_path_nodes
/rtabmap/global_pose
/rtabmap/goal
/rtabmap/goal_node
/rtabmap/goal_out
/rtabmap/goal_reached
/rtabmap/grid_map
/rtabmap/grid_prob_map
/rtabmap/info
/rtabmap/initialpose
/rtabmap/labels
/rtabmap/landmarks
/rtabmap/local_grid_empty
/rtabmap/local_grid_ground
/rtabmap/local_grid_obstacle
/rtabmap/local_path
/rtabmap/local_path_nodes
/rtabmap/localization_pose
/rtabmap/mapData
/rtabmap/mapGraph
/rtabmap/mapOdomCache
/rtabmap/mapPath
/rtabmap/octomap_binary
/rtabmap/octomap_empty_space
/rtabmap/octomap_full
/rtabmap/octomap_global_frontier_space
/rtabmap/octomap_grid
/rtabmap/octomap_ground
/rtabmap/octomap_obstacles
/rtabmap/octomap_occupied_space
/rtabmap/odom
/rtabmap/odom_info
/rtabmap/odom_info_lite
/rtabmap/odom_last_frame
/rtabmap/odom_local_map
/rtabmap/odom_local_scan_map
/rtabmap/odom_rgbd_image
/rtabmap/odom_sensor_data/compressed
/rtabmap/odom_sensor_data/features
/rtabmap/odom_sensor_data/raw
/rtabmap/proj_map
/rtabmap/republish_node_data
/rtabmap/scan_map
/tag_detections
/tf
/tf_static
/user_data_async

Please, what could be the problem? How can I start the mapping and save the result? Thank you in advance. Kind regards

matlabbe commented 1 week ago

It seems the remapping didn't work:

/camera/rgb/image_rect_color \
/camera/aligned_depth_to_color/image_raw \
/camera/rgb/camera_info

should be:

/camera/color/image_raw \
/camera/aligned_depth_to_color/image_raw \
/camera/color/camera_info

Can you try removing the "slashes" in the command and do something like this: roslaunch rtabmap_launch rtabmap.launch rtabmap_args:="--delete_db_on_start" depth_topic:=/camera/aligned_depth_to_color/image_raw rgb_topic:=/camera/color/image_raw camera_info_topic:=/camera/color/camera_info approx_sync:=false

TDVL commented 1 week ago

Thank you. Now the mapping has been started. However, I still have an error. Also, where are stored these maps, since I noticed that the drive free space is rapidly decreazing? How can I delete the data from memory and how can I reduce the memory usage? In this way the hdd will be full in a few minutes!!! Also, how can I strore a map in order to later process it, analyze it, etc.?

[ WARN] (2024-06-17 07:22:17.440) OdometryF2M.cpp:562::computeTransform() Registration failed: "Not enough inliers 0/20 (matches=11) between -1 and 2155" [ INFO] [1718601737.441288268]: Odom: quality=0, std dev=0.000000m|0.000000rad, update time=0.052256s [ WARN] (2024-06-17 07:22:17.499) OdometryF2M.cpp:562::computeTransform() Registration failed: "Not enough inliers 0/20 (matches=15) between -1 and 2156" [ INFO] [1718601737.499849708]: Odom: quality=0, std dev=0.000000m|0.000000rad, update time=0.053314s [ WARN] (2024-06-17 07:22:17.559) OdometryF2M.cpp:562::computeTransform() Registration failed: "Not enough inliers 0/20 (matches=16) between -1 and 2157" [ INFO] [1718601737.560560431]: Odom: quality=0, std dev=0.000000m|0.000000rad, update time=0.058925s [ WARN] (2024-06-17 07:22:17.617) OdometryF2M.cpp:562::computeTransform() Registration failed: "Not enough inliers 0/20 (matches=14) between -1 and 2158" [ INFO] [1718601737.618138764]: Odom: quality=0, std dev=0.000000m|0.000000rad, update time=0.053185s [ WARN] [1718601737.648171641]: Could not get transform from odom to camera_link after 0.200000 seconds (for stamp=1718601736.926017)! Error="Lookup would require extrapolation 125.820122957s into the future. Requested time 1718601736.926017046 but the latest data is at time 1718601611.105894089, when looking up transform from frame [camera_link] to frame [odom]. canTransform returned after 0.200221 timeout was 0.2.". [ WARN] (2024-06-17 07:22:17.669) OdometryF2M.cpp:562::computeTransform() Registration failed: "Not enough inliers 0/20 (matches=13) between -1 and 2159" [ INFO] [1718601737.669939704]: Odom: quality=0, std dev=0.000000m|0.000000rad, update time=0.050450s [ERROR] (2024-06-17 07:22:17.672) Rtabmap.cpp:1348::process() RGB-D SLAM mode is enabled, memory is incremental but no odometry is provided. Image 3908 is ignored!

[ WARN] (2024-06-17 07:22:17.726) OdometryF2M.cpp:562::computeTransform() Registration failed: "Not enough inliers 0/20 (matches=12) between -1 and 2160" [ INFO] [1718601737.726448570]: Odom: quality=0, std dev=0.000000m|0.000000rad, update time=0.053264s [ WARN] (2024-06-17 07:22:17.781) OdometryF2M.cpp:562::computeTransform() Registration failed: "Not enough inliers 0/20 (matches=12) between -1 and 2161" [ INFO] [1718601737.781381990]: Odom: quality=0, std dev=0.000000m|0.000000rad, update time=0.053204s [ WARN] (2024-06-17 07:22:17.831) OdometryF2M.cpp:562::computeTransform() Registration failed: "Not enough inliers 0/20 (matches=10) between -1 and 2162" [ INFO] [1718601737.831914929]: Odom: quality=0, std dev=0.000000m|0.000000rad, update time=0.049199s [ WARN] [1718601737.852298874]: Could not get transform from odom to camera_link after 0.200000 seconds (for stamp=1718601736.992727)! Error="Lookup would require extrapolation 125.886832475s into the future. Requested time 1718601736.992726564 but the latest data is at time 1718601611.105894089, when looking up transform from frame [camera_link] to frame [odom]. canTransform returned after 0.201891 timeout was 0.2.". [ WARN] [1718601737.857434445]: /rtabmap/rtabmap_viz: 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"). Parameter "approx_sync" is false, which means that input topics should have all the exact timestamp for the callback to be called. /rtabmap/rtabmap_viz subscribed to (exact sync): /rtabmap/odom \ /camera/color/image_raw \ /camera/aligned_depth_to_color/image_raw \ /camera/color/camera_info \ /rtabmap/odom_info

Screenshot from 2024-06-17 07-23-45 [ WARN] (2024-06-17 07:22:17.440) OdometryF2M.cpp:562::computeTransform() Registration failed: "Not enough inliers 0/20 (matches=11) between -1 and 2155" [ INFO] [1718601737.441288268]: Odom: quality=0, std dev=0.000000m|0.000000rad, update time=0.052256s [ WARN] (2024-06-17 07:22:17.499) OdometryF2M.cpp:562::computeTransform() Registration failed: "Not enough inliers 0/20 (matches=15) between -1 and 2156" [ INFO] [1718601737.499849708]: Odom: quality=0, std dev=0.000000m|0.000000rad, update time=0.053314s [ WARN] (2024-06-17 07:22:17.559) OdometryF2M.cpp:562::computeTransform() Registration failed: "Not enough inliers 0/20 (matches=16) between -1 and 2157" [ INFO] [1718601737.560560431]: Odom: quality=0, std dev=0.000000m|0.000000rad, update time=0.058925s [ WARN] (2024-06-17 07:22:17.617) OdometryF2M.cpp:562::computeTransform() Registration failed: "Not enough inliers 0/20 (matches=14) between -1 and 2158" [ INFO] [1718601737.618138764]: Odom: quality=0, std dev=0.000000m|0.000000rad, update time=0.053185s [ WARN] [1718601737.648171641]: Could not get transform from odom to camera_link after 0.200000 seconds (for stamp=1718601736.926017)! Error="Lookup would require extrapolation 125.820122957s into the future. Requested time 1718601736.926017046 but the latest data is at time 1718601611.105894089, when looking up transform from frame [camera_link] to frame [odom]. canTransform returned after 0.200221 timeout was 0.2.". [ WARN] (2024-06-17 07:22:17.669) OdometryF2M.cpp:562::computeTransform() Registration failed: "Not enough inliers 0/20 (matches=13) between -1 and 2159" [ INFO] [1718601737.669939704]: Odom: quality=0, std dev=0.000000m|0.000000rad, update time=0.050450s [ERROR] (2024-06-17 07:22:17.672) Rtabmap.cpp:1348::process() RGB-D SLAM mode is enabled, memory is incremental but no odometry is provided. Image 3908 is ignored!

[ WARN] (2024-06-17 07:22:17.726) OdometryF2M.cpp:562::computeTransform() Registration failed: "Not enough inliers 0/20 (matches=12) between -1 and 2160" [ INFO] [1718601737.726448570]: Odom: quality=0, std dev=0.000000m|0.000000rad, update time=0.053264s [ WARN] (2024-06-17 07:22:17.781) OdometryF2M.cpp:562::computeTransform() Registration failed: "Not enough inliers 0/20 (matches=12) between -1 and 2161" [ INFO] [1718601737.781381990]: Odom: quality=0, std dev=0.000000m|0.000000rad, update time=0.053204s [ WARN] (2024-06-17 07:22:17.831) OdometryF2M.cpp:562::computeTransform() Registration failed: "Not enough inliers 0/20 (matches=10) between -1 and 2162" [ INFO] [1718601737.831914929]: Odom: quality=0, std dev=0.000000m|0.000000rad, update time=0.049199s [ WARN] [1718601737.852298874]: Could not get transform from odom to camera_link after 0.200000 seconds (for stamp=1718601736.992727)! Error="Lookup would require extrapolation 125.886832475s into the future. Requested time 1718601736.992726564 but the latest data is at time 1718601611.105894089, when looking up transform from frame [camera_link] to frame [odom]. canTransform returned after 0.201891 timeout was 0.2.". [ WARN] [1718601737.857434445]: /rtabmap/rtabmap_viz: 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"). Parameter "approx_sync" is false, which means that input topics should have all the exact timestamp for the callback to be called. /rtabmap/rtabmap_viz subscribed to (exact sync): /rtabmap/odom \ /camera/color/image_raw \ /camera/aligned_depth_to_color/image_raw \ /camera/color/camera_info \ /rtabmap/odom_info

Screenshot from 2024-06-17 07-29-17

TDVL commented 1 week ago

Is it possible, that some log files are filling after the rtabmap is stopped? Now, the hdd consumption is continuous. How can I delete these data, log files? How can I stop this process? Thank you in advance

matlabbe commented 5 days ago

In this way the hdd will be full in a few minutes!!!

That should not be possible, unless your HDD is a couple of hundred of MB. Do you mean the RAM?

After killing the rtabmap nodes, there should be nothing logged from rtabmap remaining. Could it be from the camera node? When running, rtabmap would log to terminal by default (unless you redirect the log output to a file). The only thing it writes by default is the database, which is written to ~/.ros/rtabmap.db by default. For your HDD issue, you may check if the database is increasing in size as fast as you are observing.

To clear space taken from rtabmap, manually delete the database under ~/.ros/rtabmap.db. If you use rtabmap_args:="--delete_db_on_start" with rtabmap.launch, the previous database will be always erased so you don't need to manually erase it.

Based on the log above, rtabmap's odometry could not track features for some reason (see Lost Odometry section), and failed outputting a pose. Rtabmap then produce an error that odometry is null, discarding the data. The resulting database is mostly empty (only 2 MB).

Note that with D435 camera, I prefer using IR cameras instead of RGB for better and more robust feature tracking. See D435 examples here using only IR cameras (either in stereo mode or IR-Depth mode).

TDVL commented 4 days ago

Thank you Mathieu, After the re-installation everything works well. I hope it will be in future too. I don't know what was the problem, but the HDD was full in a few minutes. I have tried the IR cameras too. The result looks OK so far. I will test it further. Another question. If the D435 is mounted on collaborative robot. What is the recommended robot moving speed in a horizontal motion for a good mapping procedure? The max. cobot speed of 250mm/s is OK? The DetectionRate parameter is set to 30Hz. Also, maybe the camera will be mounted on a small car that will be moving horizontally on tracks.

matlabbe commented 1 day ago

Don't set Rtabmap/DetectionRate to 30 (default is 1 Hz!). That rate is for map updates, not visual odometry. Unless your robot is super fast and you don't want holes in the map, generally 1 or 2 Hz is enough for the map updates. In contrast, you would want visual odometry to run as fast as possible, which would be doing by default.

For the max speed, it depends how fast visual odometry can run. Note that if your robot arm base fixed, you should not need visual odometry at all, and just use arm kinematics to know where the camera is at any time. If the robot arm is moving on a vehicle, you may avoid very fast rotations, unless visual odometry can run fast (depending on your computation power). However, even with the most powerful computer, the speed may be limited by the maximum speed you can go without motion blur in the images.

The maximum speed would be dependent on how easy is to track features over multiple frames. For example, the kitti dataset features a sequence where a car is driving over 70 Km/h with stereo images taken at 10 Hz and there is no problem for rtabmap's visual odometry. In contrast, in euroc dataset there is a sequence with very aggressive motion (drone flying indoor) that makes rtabmap lose tracking even if images are taken at 20 Hz (by lack of shared features between consecutive frames, and it is kinda blurry on fast rotation).

TDVL commented 23 hours ago

OK, thank you for the suggestions. I will use the default 1Hz DetectionRate. The robot will moving on a car on tracks, and it will mapping the parking lot with cars. Now, I am using 5 FPS with D435, should I use the default 30 FPS for D435?

These are my launch parameters for D435 and RTABMp: roslaunch realsense2_camera rs_camera.launch depth_width:=1280 depth_height:=720 depth_fps:=5 color_width:=1280 color_height:=720 color_fps:=5 clip_distance:=6 align_depth:=true filters:=pointcloud initial_reset:=true

roslaunch rtabmap_launch rtabmap.launch rtabmap_args:="--delete_db_on_start" depth_topic:=/camera/aligned_depth_to_color/image_raw rgb_topic:=/camera/color/image_raw camera_info_topic:=/camera/color/camera_info approx_sync:=false/localization:=true/ DetectionRate:=1

Maybe you can suggest other launch settings? Also I have used the clip_distance:=2 to limit the depth range estimation in depth map since the depth map and the poindcloud quality decrease with higher clip distance. Also, you have suggested the infra cameras. Are they useful for parking lot mapping (with parked cars)?