Some questions in visual odometer

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

Some questions in visual odometer

willzoe
When I read the paper RTAB-Map as an Open-Source Lidar and Visual SLAM Library for Large-Scale and Long-Term Online Operation, there are some things I don’t understand in the visual odometer section.

In the Feature Matching module, the article says,

For F2M, matching is done by nearest neighbor search (Muja & Lowe, 2009) with nearest neighbor distance ratio (NNDR) test (Lowe, 2004), using binary robust independent elementary features (BRIEF) descriptors (Calonder, Lepetit, Strecha, & Fua, 2010) of the extracted features against those in the Feature Map.

1. Does the nearest neighbor search used here refer to FLANN? Is the role of parameter Vis/CorNNType to choose which NNS algorithm to use?

2. The descriptor used here is BRIEF, which corresponds to Vis/FeatureType = "6". But the stereo_odometry node defaults to Vis / FeatureType = "8", which is GFTT/ORB. Does this mean that the BRIEF improved by ORB feature is used as a descriptor?

3. How is the Feature Map generated? Does the Feature Map contain many key frames? What is the difference between the role of the two parameters Odom/KeyFrameThr and Odom/VisKeyFrameThr?

In the Motion Prediction module,

1. The explanation of the parameter Vis/CorGuessMatchToProjection is

[Vis / CorType = 0] Match frame's corners to source's projected points (when guess transform is provided) instead of projected points to frame's corners.
But I don't understand the meaning of this paragraph. Would you like to explain its function in detail?

2. Is the parameter guess_frame_id in node stereo_odometry used for this module?

Reply | Threaded
Open this post in threaded view
|

Re: Some questions in visual odometer

matlabbe
Administrator
Hi,

1. Yes and Yes. You can adjust Kp/NndrRatio for BOW quantization and Vis/CorNNDR for feature matching between frames for motion estimation.

2. The OpenCV version you have may not support BRIEF, it is why GFTT/ORB is used instead. The default alue will change depending on which OpencV version used and available modules. See those lines.

3. Yes, the Feature Map is created from many key frames. Odom/KeyFrameThr is a ratio of inliers with the FeatureMap while Odom/VisKeyFrameThr is a number of inliers. If we get low inliers, on of this two thresholds will trigger a new key frame, otherwise we don't add new features to Feature Map.

4. Vis/CorGuessMatchToProjection is more experimental, I didn't see lot of difference whether it is true or false. When we have a guess, features from the FeatureMap are projected to current frame based on the motion guess. This limit the search for feature matching, to be more robust to repetitive visual features (many features with very similar descriptor). When false, we compare from projected features to extracted features in the current frame. When true, we match extracted features of current frame to projected features.

5. Yes, guess_frame_id is used to get an external motion estimation guess, e.g., wheel odometry instead of assuming a constant velocity model (like in figure 3). In the paper, we didn't mention it for visual odometry as I am not sure it was implemented at that time or it is because in the experiments we didn't use external guess when visual odometry was done.

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

Re: Some questions in visual odometer

willzoe
matlabbe wrote
2. The OpenCV version you have may not support BRIEF, it is why GFTT/ORB is used instead. The default alue will change depending on which OpencV version used and available modules. See those lines.
1. What is the difference between Vis/FeatureType = "2"(ORB) and Vis/FeatureType = "8"(GFTT/ORB)?
matlabbe wrote
4. Vis/CorGuessMatchToProjection is more experimental, I didn't see lot of difference whether it is true or false. When we have a guess, features from the FeatureMap are projected to current frame based on the motion guess. This limit the search for feature matching, to be more robust to repetitive visual features (many features with very similar descriptor). When false, we compare from projected features to extracted features in the current frame. When true, we match extracted features of current frame to projected features.
2. Sorry, although I noticed your emphasis, I still don't understand the difference between when it is true and false. These two situations seem to only match extracted features of current frame and projected features. Perhaps it is because I did not understand the relationship between motion prediction and feature matching. Would you like to explain it in detail again?
matlabbe wrote
5. Yes, guess_frame_id is used to get an external motion estimation guess, e.g., wheel odometry instead of assuming a constant velocity model (like in figure 3). In the paper, we didn't mention it for visual odometry as I am not sure it was implemented at that time or it is because in the experiments we didn't use external guess when visual odometry was done.
3. Is motion prediction implemented in the current visual odometer? If I use wheel odometry as a guess, how should I set it up?
Reply | Threaded
Open this post in threaded view
|

Re: Some questions in visual odometer

matlabbe
Administrator
1. ORB means that ORB from OpenCV is used for keypoint detection and descriptor. GFTT/ORB means that GFTT is used for keypoint detection, then ORB descriptors are extracted from those keypoints.

2. We have Feature Map projected in current frame, and features extracted from current frame. When we do general matching between two frames, we can match featuresA to FeaturesB or FeaturesB to FeaturesA. In the case of this parameter, it tells if we want to match ProjectedFeatures to ExtractedFeatures or ExtractedFeatures to ProjectedFeatures. For more details, ProjectedFeatures are the prediction of the features of the map in the current frame based on past odometry motion (or guess).

3. When guess_frame_id is not used, a constant velocity model is used. In other words, it will predict where the features should be in next frame based on current velocity. To use wheel odometry instead of constant motion model, set guess_frame_id to odometry frame of your wheel odometry. Set also odom_frame_id to a name different than the one used by wheel odometry. Example if wheel odometry publishes:
/odom -> /base_footprint
if we set guess_frame_id=odom, odom_frame_id=visual_odom and frame_id=base_footprint, the TF tree will look like this (like explained in the paper in icp_odomety section):
/visual_odom -> /odom -> /base_footprint