Small number of ORB features between similar frames

classic Classic list List threaded Threaded
2 messages Options
Reply | Threaded
Open this post in threaded view
|

Small number of ORB features between similar frames

Divelix

Hi Mathieu,

I've been experimenting with mobile robot of the following sensor setup: wheel odometry + RGB (640x480 from L515) + Depth (640x480 from L515) +pointcloud (by L515 from its RGB and D). I tried to create map of a room via RTAB-Map with the following parameters (I tried to use only ICP refining of my wheel odometry and loop closure, no visual odometry):

<node pkg="nodelet" type="nodelet" name="rgbd_sync" args="standalone rtabmap_ros/rgbd_sync" output="screen">
        <remap from="rgb/image"        to="$(arg rgb_namespace)/image_raw"/>
        <remap from="depth/image"      to="$(arg depth_namespace)/image_raw"/>
        <remap from="rgb/camera_info"  to="$(arg rgb_namespace)/camera_info"/>
        <remap from="rgbd_image"       to="/rtabmap/rgbd_image"/>
        <param name="approx_sync"      value="true"/> 
        <param name="queue_size"       value="50"/> 
    </node>

    <!-- RTAB-Map -->
    <group ns="rtabmap">
        <node name="rtabmap" pkg="rtabmap_ros" type="rtabmap" output="screen" args="">
            <param name="database_path"        type="string" value="$(arg rtabmap_db_path)"/>
            <param name="frame_id"             type="string" value="base_footprint"/>

            <param name="subscribe_rgbd"       type="bool"   value="true"/>
            <param name="subscribe_rgb"        type="bool"   value="false"/>
            <param name="subscribe_depth"      type="bool"   value="false"/>
            <param name="subscribe_scan_cloud" type="bool"   value="$(arg use_scan_cloud)"/>

            <param name="approx_sync"          type="bool"   value="true"/>

            <!-- use actionlib to send goals to move_base --> 
            <param name="use_action_for_goal"  type="bool" value="true"/>
            <remap from="move_base"            to="/move_base"/>
            
            <!-- inputs -->
            <remap from="scan_cloud"           to="/frontal_camera/depth/color/points" if="$(arg use_scan_cloud)"/>
            <remap from="odom"                 to="/odom"/>
            <remap from="rgb/image"            to="$(arg rgb_namespace)/image_raw"/>
            <remap from="rgb/camera_info"      to="$(arg rgb_namespace)/camera_info"/>
            <remap from="depth/image"          to="$(arg depth_namespace)/image_raw"/>

            <!-- output -->
            <remap from="grid_map" to="/map"/>
            
            <!-- RTAB-Map's parameters -->
            <param name="Reg/Force3DoF"             type="bool"  value="true"/>
            <param name="Grid/Sensor"               type="int"   value="1"/>
            <param name="RGBD/ProximityPathMaxNeighbors" type="string" value="10"/>

            <param name="Reg/Strategy"              type="int"   value="1"/>
            <param name="RGBD/OptimizeMaxError"     type="double" value="3"/>
            <param name="RGBD/NeighborLinkRefining" type="bool"  value="true"/>
            <param name="RGBD/ProximityBySpace"     type="bool"  value="true"/>
            <param name="Rtabmap/LoopThr"           type="string" value="2.0"/>
            <param name="ICP/Strategy"              type="int" value="1"/>
        </node>
    </group>

As I understand, RTAB-Map use visual features (GFTT/ORB by default) to detect loop closure candidates, so finding correspondences between frames is crutial. But in my experiment I found out that there is very few correspondences between almost identical images from different parts of timeline. As you can see in the picture below, there are only 10 correspondences in obvious loop closure candidate, while even RTAB-Map parameter "Vis/MinInliers" has default value of 20. Did I misunderstood or messed up something in my parameters? Thanks in advance

Screenshot from rtabmap-databaseViewer
Reply | Threaded
Open this post in threaded view
|

Re: Small number of ORB features between similar frames

matlabbe
Administrator
Hi,

Depending how commons the same descriptors are seen again, only most descriminative ones will be matched in the vocabulary. However, rtabmap loop closure is done in two steps: 1) BoW using the vocabulary to find the most likely image, so here ~10 features will score, 2) we take the highest loop closure hypothesis and recompute the correspondences between the images (so only using descriptors form the 2 images to get more matches). If you open Constraints View with Reg/Strategy=2 or Reg/Strategy=0 (see Core Parameters panel), then click on Add Constraint, you will see the new correspondences in the images, they should be higher.

cheers,
Mathieu