introlab / rtabmap_ros

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

Can't get stereo camera to work with lidar #1103

Open GilMe opened 8 months ago

GilMe commented 8 months ago

Hi, I have a setup with a lidar and a stereo camera. I am using an external algorithm to provide the vo through a tf. I want rtabmap to use the lidar in order to build the 3d occupancy grid, and the camera to do the loop closure. When I set stereo to true and subscribe_scan_cloud also to true, I get that rtabmap is only trying to subscribe to the stereo camera topics. If I set stereo to false, then the rtabmap sets up as rgbd and it does subscribe to my lidar topic. I get the following:

  1. If stereo=true:

    [ INFO] [1705416018.016790865]: /rtabmap/rtabmap: subscribe_depth = false
    [ INFO] [1705416018.016790865]: /rtabmap/rtabmap: subscribe_rgb = false
    [ INFO] [1705416018.016823283]: /rtabmap/rtabmap: subscribe_stereo = true
    [ INFO] [1705416018.016951511]: /rtabmap/rtabmap: subscribe_rgbd = false (rgbd_cameras=1)
    [ INFO] [1705416018.016986712]: /rtabmap/rtabmap: subscribe_sensor_data = false
    [ INFO] [1705416018.017019257]: /rtabmap/rtabmap: subscribe_odom_info = false
    [ INFO] [1705416018.017046010]: /rtabmap/rtabmap: subscribe_user_data = false
    [ INFO] [1705416018.017072859]: /rtabmap/rtabmap: subscribe_scan = false
    [ INFO] [1705416018.017093788]: /rtabmap/rtabmap: subscribe_scan_cloud = true
    [ INFO] [1705416018.017162078]: /rtabmap/rtabmap: subscribe_scan_descriptor = false
    [ INFO] [1705416018.017198239]: /rtabmap/rtabmap: queue_size    = 30
    [ INFO] [1705416018.017226752]: /rtabmap/rtabmap: approx_sync   = true
    [ INFO] [1705416018.017432551]: Setup stereo callback
    [ INFO] [1705416018.254581449]: 
    /rtabmap/rtabmap subscribed to (approx sync):
    /stereo_camera/left/image_rect \
    /stereo_camera/right/image_rect \
    /stereo/fisheye_left/camera_info \
    /stereo/fisheye_right/camera_info
  2. If stereo=false:

[ INFO] [1705415857.943216690]: /rtabmap/rtabmap: subscribe_depth = true
[ INFO] [1705415857.943626144]: /rtabmap/rtabmap: subscribe_rgb = true
[ INFO] [1705415857.943756996]: /rtabmap/rtabmap: subscribe_stereo = false
[ INFO] [1705415857.943878761]: /rtabmap/rtabmap: subscribe_rgbd = false (rgbd_cameras=1)
[ INFO] [1705415857.943976236]: /rtabmap/rtabmap: subscribe_sensor_data = false
[ INFO] [1705415857.944064463]: /rtabmap/rtabmap: subscribe_odom_info = false
[ INFO] [1705415857.944149298]: /rtabmap/rtabmap: subscribe_user_data = false
[ INFO] [1705415857.944232885]: /rtabmap/rtabmap: subscribe_scan = false
[ INFO] [1705415857.944331704]: /rtabmap/rtabmap: subscribe_scan_cloud = true
[ INFO] [1705415857.944423835]: /rtabmap/rtabmap: subscribe_scan_descriptor = false
[ INFO] [1705415857.944511678]: /rtabmap/rtabmap: queue_size    = 10
[ INFO] [1705415857.944596769]: /rtabmap/rtabmap: approx_sync   = true
[ INFO] [1705415857.944759302]: Setup depth callback
[ INFO] [1705415858.188638324]: 
/rtabmap/rtabmap subscribed to (approx sync):
   /camera/rgb/image_rect_color \
   /camera/depth_registered/image_raw \
   /camera/rgb/camera_info \
   /lidar/scan_3D
[ INFO] [1705415858.469397786]: rtabmap 0.21.3 started...

What am I doing wrong?

GilMe commented 8 months ago

Here is my launch file:

<launch>

<arg name="stereo_namespace" default="/stereo_camera"/>

<arg name="left_cam_topic" default="/stereo/fisheye_left/image_raw"/>
<arg name="left_cam_info_topic" default="/stereo/fisheye_left/camera_info"/>
<arg name="right_cam_topic" default="/stereo/fisheye_right/image_raw"/>
<arg name="right_cam_info_topic" default="/stereo/fisheye_right/camera_info"/>

<!-- Fixed frame id, you may set "base_link" or "base_footprint" if they are published -->
<arg name="frame_id" default="base_link"/>

<!-- If set, TF is used to get odometry instead of the topic -->
<arg name="odom_frame_id" default="odom"/>

<!-- Lidar -->
<arg name="lidar_topic" default="/lidar/scan_3D"/>

<arg name="feature_type" default="6"/>
<arg name="gravity_opt" default="false"/> <!-- Rtabmap will use IMU data to add gravity constraints to graph -->

<arg name="args" default=""/>
<arg     if="$(arg gravity_opt)" name="common_args" default="-d --RGBD/CreateOccupancyGrid false  --Kp/DetectorStrategy $(arg feature_type) --Optimizer/GravitySigma 0.3 $(arg args)"/>
<arg unless="$(arg gravity_opt)" name="common_args" default="-d --RGBD/CreateOccupancyGrid false  --Kp/DetectorStrategy $(arg feature_type) $(arg args) "/>

<!-- <arg     if="$(arg gravity_opt)" name="common_args" default="-d -/-RGBD/CreateOccupancyGrid false -/-Odom/FeatureType $(arg feature_type) -/-Kp/DetectorStrategy $(arg feature_type) -/-Optimizer/GravitySigma 0.3 $(arg args)"/> 
<arg unless="$(arg gravity_opt)" name="common_args" default="-d -/-RGBD/CreateOccupancyGrid false -/-Odom/FeatureType $(arg feature_type) -/-Kp/DetectorStrategy $(arg feature_type) $(arg args) "/> -->

<arg name="cfg" default=""/>
<arg name="rectify_stereo" default="true"/>
<arg name="rtabmap_viz" default="false"/>
<arg name="rviz" default="false"/>

<!--******************************************
**    Start launching nodes and launch files
**********************************************-->

<!-- Image rectification and publishing synchronized camera_info-->
<group ns="$(arg stereo_namespace)">

  <node if="$(arg rectify_stereo)" pkg="stereo_image_proc" type="stereo_image_proc" name="stereo_image_proc">
    <remap from="left/image_raw"      to="$(arg left_cam_topic)"/>
    <remap from="left/camera_info"    to="$(arg left_cam_info_topic)"/>
    <remap from="right/image_raw"     to="$(arg right_cam_topic)"/>
    <remap from="right/camera_info"   to="$(arg right_cam_info_topic)"/>
  </node>

</group>

<param name="/rtabmap/rtabmap/Grid/3D" type="bool" value="true"/>
<param name="/rtabmap/rtabmap/Grid/FromDepth" type="bool" value="false"/>  
<param name="/rtabmap/rtabmap/Grid/Sensor" type="int" value="0"/>

<include file="$(find rtabmap_launch)/launch/rtabmap.launch">
   <arg unless="$(arg rectify_stereo)" name="rtabmap_args" value="$(arg common_args) --Rtabmap/ImagesAlreadyRectified false"/>
   <arg     if="$(arg rectify_stereo)" name="rtabmap_args" value="$(arg common_args)"/>

   <arg unless="$(arg rectify_stereo)" name="left_image_topic"        value="$(arg left_cam_topic)"/>
   <arg unless="$(arg rectify_stereo)" name="left_camera_info_topic"  value="$(arg left_cam_info_topic)" />

   <arg     if="$(arg rectify_stereo)" name="left_image_topic"        value="/stereo_camera/left/image_rect"/>
   <arg     if="$(arg rectify_stereo)" name="left_camera_info_topic"  value="$(arg left_cam_info_topic)"/>

   <arg unless="$(arg rectify_stereo)" name="right_image_topic"       value="$(arg right_cam_topic)"/>
   <arg unless="$(arg rectify_stereo)" name="right_camera_info_topic" value="$(arg right_cam_info_topic)" />

   <arg     if="$(arg rectify_stereo)" name="right_image_topic" value="/stereo_camera/right/image_rect"/>
   <arg     if="$(arg rectify_stereo)" name="right_camera_info_topic" value="$(arg right_cam_info_topic)" />

   <arg name="stereo" value="true"/>
   <arg name="frame_id" value="$(arg frame_id)"/>

   <arg name="wait_for_transform" value="0.1"/>
   <arg name="cfg" value="$(arg cfg)"/>
   <!--<arg name="imu_topic" value="/imu/data"/>-->
   <arg name="rtabmap_viz" value="$(arg rtabmap_viz)"/>
   <arg name="rviz" value="$(arg rviz)"/>
   <!--<arg name="wait_imu_to_init" value="true"/>-->
   <arg name="stereo_namespace" value="$(arg stereo_namespace)"/>

   <arg name="subscribe_scan_cloud" value="true"/>
   <arg name="scan_cloud_topic" value="$(arg lidar_topic)"/>
   <arg name="approx_sync" value="true"/>

   <arg name="visual_odometry" value="false"/>
   <arg name="icp_odometry" value="false"/>

   <arg name="odom_frame_id" value="odom"/>
   <arg name="queue_size" value="30"/>

</include>
</launch>
GilMe commented 8 months ago

Here are all the parameters as that are printed when I run rtabmap:

[ INFO] [1705417143.665671606]: Starting node...
[ INFO] [1705417143.751089291]: Initializing nodelet with 6 worker threads.
[ INFO] [1705417144.128476894]: /rtabmap/rtabmap(maps): map_filter_radius          = 0.000000
[ INFO] [1705417144.128561633]: /rtabmap/rtabmap(maps): map_filter_angle           = 30.000000
[ INFO] [1705417144.129261657]: /rtabmap/rtabmap(maps): map_cleanup                = true
[ INFO] [1705417144.129677415]: /rtabmap/rtabmap(maps): map_always_update          = false
[ INFO] [1705417144.130077684]: /rtabmap/rtabmap(maps): map_empty_ray_tracing      = true
[ INFO] [1705417144.130645192]: /rtabmap/rtabmap(maps): cloud_output_voxelized     = true
[ INFO] [1705417144.131072502]: /rtabmap/rtabmap(maps): cloud_subtract_filtering   = false
[ INFO] [1705417144.131509605]: /rtabmap/rtabmap(maps): cloud_subtract_filtering_min_neighbors = 2
[ INFO] [1705417144.132617515]: /rtabmap/rtabmap(maps): octomap_tree_depth         = 16
[ INFO] [1705417144.191740675]: rtabmap: frame_id      = base_link
[ INFO] [1705417144.191853191]: rtabmap: odom_frame_id = odom
[ INFO] [1705417144.191901736]: rtabmap: map_frame_id  = map
[ INFO] [1705417144.191929417]: rtabmap: log_to_rosout_level = 4
[ INFO] [1705417144.191956362]: rtabmap: initial_pose  = 
[ INFO] [1705417144.191978187]: rtabmap: use_action_for_goal  = false
[ INFO] [1705417144.192006988]: rtabmap: tf_delay      = 0.050000
[ INFO] [1705417144.192033709]: rtabmap: tf_tolerance  = 0.100000
[ INFO] [1705417144.192055598]: rtabmap: odom_sensor_sync   = false
[ INFO] [1705417144.192080719]: rtabmap: pub_loc_pose_only_when_localizing = false
[ INFO] [1705417144.194123956]: rtabmap: stereo_to_depth = false
[ INFO] [1705417144.194183222]: rtabmap: gen_scan  = false
[ INFO] [1705417144.194211383]: rtabmap: gen_depth  = false
[ INFO] [1705417144.195415392]: rtabmap: scan_cloud_max_points = 0
[ INFO] [1705417144.195470018]: rtabmap: scan_cloud_is_2d      = false
[ INFO] [1705417144.299685526]: Setting RTAB-Map parameter "Grid/3D"="true"
[ INFO] [1705417144.350235979]: Setting RTAB-Map parameter "Grid/Sensor"="0"
[ INFO] [1705417144.527957376]: Setting RTAB-Map parameter "Mem/IncrementalMemory"="true"
[ INFO] [1705417144.529252908]: Setting RTAB-Map parameter "Mem/InitWMWithAllNodes"="false"
[ INFO] [1705417144.916663187]: Update RTAB-Map parameter "Kp/DetectorStrategy"="6" from arguments
[ INFO] [1705417144.916807352]: Update RTAB-Map parameter "RGBD/CreateOccupancyGrid"="true" from arguments
[ INFO] [1705417145.201984239]: Setting "Grid/RangeMax" parameter to 0 (default 5.000000) as "subscribe_scan", "subscribe_scan_cloud" or "gen_scan" is true and Grid/Sensor is 0.
[ INFO] [1705417145.202287417]: Setting "Icp/PointToPlaneRadius" parameter to 0 (default 0.000000) as "subscribe_scan_cloud" is true.
[ INFO] [1705417145.205984855]: RTAB-Map detection rate = 1.000000 Hz
[ INFO] [1705417145.208401833]: rtabmap: Deleted database "/home/peterpan/.ros/rtabmap.db" (--delete_db_on_start or -d are set).
[ INFO] [1705417145.208506797]: rtabmap: Using database from "/home/peterpan/.ros/rtabmap.db" (0 MB).
[ INFO] [1705417145.951379614]: rtabmap: Database version = "0.21.3".
[ INFO] [1705417145.951793132]: rtabmap: SLAM mode (Mem/IncrementalMemory=true)
[ INFO] [1705417146.061368759]: /rtabmap/rtabmap: subscribe_depth = false
[ INFO] [1705417146.061731715]: /rtabmap/rtabmap: subscribe_rgb = false
[ INFO] [1705417146.061944138]: /rtabmap/rtabmap: subscribe_stereo = true
[ INFO] [1705417146.062154353]: /rtabmap/rtabmap: subscribe_rgbd = false (rgbd_cameras=1)
[ INFO] [1705417146.062369369]: /rtabmap/rtabmap: subscribe_sensor_data = false
[ INFO] [1705417146.062561695]: /rtabmap/rtabmap: subscribe_odom_info = false
[ INFO] [1705417146.062752838]: /rtabmap/rtabmap: subscribe_user_data = false
[ INFO] [1705417146.062942956]: /rtabmap/rtabmap: subscribe_scan = false
[ INFO] [1705417146.063151187]: /rtabmap/rtabmap: subscribe_scan_cloud = true
[ INFO] [1705417146.063346586]: /rtabmap/rtabmap: subscribe_scan_descriptor = false
[ INFO] [1705417146.063545536]: /rtabmap/rtabmap: queue_size    = 30
[ INFO] [1705417146.063741255]: /rtabmap/rtabmap: approx_sync   = true
[ INFO] [1705417146.064033777]: Setup stereo callback
[ INFO] [1705417146.241651394]: 
/rtabmap/rtabmap subscribed to (approx sync):
   /stereo_camera/left/image_rect \
   /stereo_camera/right/image_rect \
   /stereo/fisheye_left/camera_info \
   /stereo/fisheye_right/camera_info
[ INFO] [1705417146.631454171]: rtabmap 0.21.3 started...
matlabbe commented 8 months ago

That's on purpose, particularly for stereo, it is rarely a good idea to approximate sync in rtabmap node stereo topics with lidar data. You should use subscribe_rgbd:=true with subscribe_scan_cloud:=true, then use rtabmap_sync/stereo_sync node to exactly sync your stereo topics into a rgbd_image topic that rtabmap can then consume with approx sync with the lidar point cloud. See figure 6 in this paper.

For RGB-D topics, we should normally do the same thing (with rtabmap_util/rgbd_sync), but we still kept the old approach for backward compatibility.