Loop closure registration strategies - Help

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

Loop closure registration strategies - Help

DavideR
Hi Mathieu,
I ask for some explanations about the registration strategies after a visual loop closure
detection.
I am sorry but even after reading your exhaustive papers, still I am not sure about what's
going on depending on the selected registration strategy.

Reg/Strategy = 1 (Geometry ICP)

I am not sure if even with this strategy, the visual registration (3Dto2D PnP RANSAC) must
occur before any scan cloud ICP registration.
If not, could you confirm me that the motion registration is made just upon the estimate of the
transform between the scan cloud stored in the candidate loop closure node and the current
scan cloud.

Loop Closure Detection and Visual Registration

For a better loop closure detection performances I think the best way to extract features from
images to update the vocabulary is to scan the entire view without using a depth mask. This
could lead to detect more far features for example in case of distant buildings in the
background.
Once a loop closure is detected though, if a 3Dto2D visual registration strategy is required, it
is necessary to match the features that actually have associated a depth value.
So for visual registration it is preferable to extract a sufficient number of feature in the
foreground where a valid depth value actually is supposed to exist so somehow extracting
more features using a depth mask.
In case of a loop closure hypothesis, will the features in the recalled candidate image be
again extracted using the parameters set in the visual registration panel (for example using depth mask)?

I'm going to describe an outdoor scenario where I'm facing some problems to finally compute
the transform and accept the loop closure:
A. A right visual loop closure hypothesis is found (I can see that the recalled image depicts
the same revisited place).
B. The only features to match that have a valid depth value are the ones in the first 5-7
meters in front of the robot where there's only asphalt.
C. Consequently it is quite hard to get a sufficient number of RANSAC inliers, especially in
case of flat asphalt without markings.
D. Any loop closure is then rejected even though the visual recall matched.
Is any way to get a workaround for this problem?

Depth by structure from motion

I'm wondering if there's any way to estimate the depth information of far features (over the Max depth of the stereo camera) by exploiting structure from motion algorithms in order to get more landmarks on the map so to have more pnp inliers for the camera registration.


Thank you a lot for your support!

Cheers

Reply | Threaded
Open this post in threaded view
|

Re: Loop closure registration strategies - Help

matlabbe
Administrator
Hi,

Reg/Strategy = 1 (Geometry ICP)

Visual transformation is still done for only loop closure transform estimation. As loop closures are detected visually, there is always a first transformation computed using visual features, then ICP is done to refine that transformation. If "Reg/Strategy" = 2 or 0 is set, we can set "RGBD/LoopClosureReextractFeatures" to true to re-extract visual features using parameters in "Vis/" group.

When refining odometry links ("RGBD/NeighborLinkRefining"=true), as odometry has already a guess transform, ICP is done directly without computing a visual one.

Loop Closure Detection and Visual Registration
We can set "Mem/DepthAsMask" and "Vis/DepthAsMask" to false to extract features everywhere independently of the depth image values. If some features don't have depth, structure from motion is done to estimate their depth based on odometry transformation (assuming that odometry is quite accurate!).

I don't know what kind of camera you are using, but if you can use it in stereo mode instead of RGB-D, rtabmap will extract features everywhere by default, and estimate feature depth even if disparity is very small (infinity). For example, it will be able to initialize feature's depth at some kilometers. Those far features are very useful for more accurate orientation estimation for visual odometry, and also for loop closures.

Depth by structure from motion
See above.

cheers,
Mathieu
Reply | Threaded
Open this post in threaded view
|

Re: Loop closure registration strategies - Help

DavideR
Hi,
Thank You for your support!
Regarding the first question about registration strategies I then still have some doubts after your reply.

I found out that using registration strategy 1 (Geometry ICP) during localization, a greater number of loop closure detections are finally accepted with respect to the case I use registration strategy 0 (Visual).

If a first Visual registration is necessary for both strategies, why more loop closure are accepted using a refinement?

Moreover, what the third strategy (Visual+Geometry) actually means?

Could you point me out briefly the main differences between all the trhee approaches to compute a loop closure transform please?


Thank you really a lot for your support,
cheers

Davide
Reply | Threaded
Open this post in threaded view
|

Re: Loop closure registration strategies - Help

matlabbe
Administrator
DavideR wrote
If a first Visual registration is necessary for both strategies, why more loop closure are accepted using a refinement?
For loop closure detection, it should be the same or even less with ICP refinement (if ICP fails after visually it has been accepted). Do you have both databases to share?

For Visual+Geometry, it is an old approach where for loop closure detection (bag-of-words), we used less features than for visual registration. It was used to re-extract features and recompute visual transformation with more features after a loop closure detection before doing ICP. In current version of rtabmap, we don't need to do that, as we can now have a different number of features for loop closure detection than for registration during signature initialization (no need to re-extract features). Looking at the newest code, it seems that Geometry and Visual+Geometry would give the same result, both using visual as guess for ICP. I don't see big differences between them by default. The only difference I see is if we force RGBD/LoopClosureReextractFeatures=true (to reproduce the old RTAB-Map behavior), features will be reextracted in Visual+Geometry approach, but they won't in Geometry approach. Ideally, the Geometry-only approach would not have rely on vision to get a first transformation guess, however there is no geometry-only approach implemented in RTAB-Map to do so (ICP requires a good first guess to not fall in a local minimum). Implementing a loop closure detector based only on geometry, we could be purely geometric. Until then, we use the vision guess for ICP.

In summary, when setting Visual+Geometry or Geometry, there is no difference for loop closure detection. However, for neighbor link refining (RGBD/NeighborLinkRefining=true), there is a difference: in the second approach a visual transformation is not done before ICP, ICP is done directly with odometry guess. Setting Visual+Geometry registration will force to refine the odometry guess using vision before refining with ICP (in general we don't want that if we expect odometry to be relatively accurate and to be able to refine odometry even in the dark or in textureless areas with the lidar, it is why I recommend using Reg/Strategy=1 with a lidar and not 2). For visual-only registration strategy, only visual transformation is done.

cheers,
Mathieu