Info on some parameters

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

Info on some parameters

manuel.lo
Hello.
I'm newbie, so sorry for my questions.
I'm studying all RTAB-Map parameters and I need to know the meaning and the effects of these parameters (probably I will need your help again in near future :) ):

1) RTAB-Map Setting - Threshold - T_ratio: what does it mean "The loop closure hypothesis must be over T_ratio x lastHypothesisValue"? Is lastHypothesisValue a parameter?

2) RTAB-Map Settings - Memory - Laser scan filtering: what's the meaning of the 4 parameters:
- Downsampling step. If > 1, downsample the laser scans when creating a location. This feature can be used to save laser scans already downsampled.
- Voxel size. If > 0 m, voxel filtering is done on laser scans when creating a signature. If the laser scan had normals, they will be removed. To recompute the normals, make sure to use Normal K or Normal Radius parameters below
- Normal K. If > 0 and laser scans don't have normals, normals will be computed with K search neighbors when creating a signature
- Normal Radius. If > 0 and laser scans don't have normals, normals will be computed with radius search when creating a signature
What's a signature? What these 4 parameters do to laser scans? How do they impact on RTAB-Map performance?

3) RTAB-Map Settings - Memory - Rehearsal/Weight Update: what's the meaning of T_similarity?
What's the meaning of "On transfer, signatures are sorted by weight->ID (i.e. the oldest of the lowest weighted signatures are transferred first). If false, the signatures are sorted by weight->Age (i.e. the oldest inserted in WM of the lowest weighted signatures are transferred first). Note that retrieval updates the age, not the ID." What is weight referred to?

4) RTAB-Map Settings - Memory: what's the meaning of "Raw descriptors kept in memory"?

If you need more clarification, I'm here.

Thanks a lot.

           Manuel
Reply | Threaded
Open this post in threaded view
|

Re: Info on some parameters

matlabbe
Administrator
Hi Manuel,

1) T_ratio can be used to reject loop closure hypotheses that are decreasing. For example if set at 0.9, then if the last best hypothesis was 0.6, then the current one should be at least 0.9x0.6=0.54 to be considered as a loop closure hypothesis. By default it is disabled, as in RGB-D SLAM mode, the wrong hypotheses can be easily rejected on the motion estimation step.

2) When creating a new node in the map, the laser scan can be filtered. If downsampling is set to 2, half of the rays will be filtered. If voxel size is set, the density of the scan will be uniformly filtered to have 1 pt/voxel size. The normal K and radius are parameters used to compute normals in the scan, if they are not already computed. Those parameters are also in ICP parameters, but it is better do filtering when creating the node instead of using those in ICP to avoid refiltering each time we want to do ICP with those scans. These parameters are not used if you don't have lidar.

3) T_similarity is explained in section III-B of this paper: Appearance-Based Loop Closure Detection for Online Large-Scale and Long-Term Operation
For the "weight->ID" thing, the difference is the ID vs Age. Age is updated when a node is brought back in Working Memory, as ID not. In the papers, the "weight->Age" approach is used.

4) During quantization to visual word vocabulary, features matching a word in the vocabulary will be linked to descriptor of this word. With this option on, we still keep the descriptor of that feature for motion estimation. With raw descriptors saved, when we need to estimate motion estimation between two images of a loop closure, we recompute the matches between them using original descriptors of all features (ignoring quantization to vocabulary), generating more accurate correspondences.

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

Re: Info on some parameters

manuel.lo
Hi Mathieu.

Thanks a lot for your answers.

I'm proceeding in studying RTAB-Map parameters and, now, can you, please, explain the meaning of the following parameters:

In RTAB-Map Settings - RGB-D SLAM - Proximity Detection:
1) When comparing to a local path, merge the laser scans using the odometry poses instead of the ones in the optimized local graph - Parameter RGBD/ProximityPathRawPosesUsed
2) Save scan matching IDs in link's user data - Paramerer RGBD/ScanMatchingIdsSavedInLinks

In RTAB-Map Settings - RGB-D SLAM - Local Occupancy Grid:
3) Footprint filtering length (0=disabled) - Parameter Grid/FootprintLength
4) Footprint filtering width (0=disabled). Footprint length should be set - Parameter Grid/FootprintWidth
5) Footprint filtering height (0=disabled). Footprint length and width should be set - Parameter Grid/FootprintHeight
in Normals Segmentation Approach:
6) Flat obstacles detected - Parameter Grid/FlatObstacleDetected - In addition to the explanation of the parameter, are the obstacles flat because they are detected in 3D?

In RTAB-Map Settings - Motion Estimation - Visual Registration:
7) Forward estimation only (A->B). If false, a transformation is also computed in backward direction (B->A), then the two resulting transforms are merged (middle interpolation between the transforms) - Parameter Vis/ForwardEstOnly
8) Refine transformation with bundle adjustment. See Optimizer panel - Parameter Vis/BundleAdjustment

In RTAB-Map Settings - Motion Estimation:
9) Match frame's corners to source's projected points (when guess transform is provided) instead of projected points to frame's corners - Parameter Vis/CorGuessMatchToProjection

If you need more clarifications, I'm here.

Thanks to those who can help me.

           Manuel
Reply | Threaded
Open this post in threaded view
|

Re: Info on some parameters

matlabbe
Administrator
Hi Manuel,

For Proximity Detection theory, see section 3.3 of the paper "Long-term online multi-session graph-based SPLAM with memory management".
1) When assembling the laser scans of a path, we have the choice of using the already optimized poses from the current graph of the map (so including loop closure detections), or using raw/optimized odometry poses only (default).
2) For debugging purpose, scan ids used for proximity detections are saved in the link computed. In database viewer, we can then re-assemble the merged scans of the proximity links for visualization (in Constraints view).

3,4,5) We can define a footprint box around the robot to filter all points in it. Sometimes the camera can see the robot itself, so this can be used to filter the obstacles on the robot.
6) When set to false, all flat obstacles are considered as ground. If true, only the biggest plane ans those at the same height are segmented as ground. For example, the top of a table would be segmented as obstacle if the camera can also see the ground. When Grid/FromDepth=true or if the laser scan is 3D, yes the obstacles are detected in 3D.

7) Experimental if false, we can compute motion transformation matching features from frame A to frame B, and then compute also motion from frame B to frame A and merge the two transforms. Not used.
8) This is what it is said, motion estimation is refined using bundle adjustment (currently only g2o is supported).

9) This will change slightly how features are matched. For Frame-To-Frame estimation, this parameter will not have a big effect. For Frame-to-Map estimation (like used by OdometryF2M), we will have better correspondences when this parameter is false. When many points in the map are projected around the same feature, we will only have one match for that feature. When parameter is true and if feature is alone in the matching radius where multiple map points are projected in it, that feature would be matched to many map points.

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

Re: Info on some parameters

manuel.lo
Hi Mathieu.

Thanks very much for your answers.

Now I have a question for the following parameter in RTAB-Map Settings - Optimizer - Solver - g2o/Solver:

- what's the meaning of parameter g2o/Solver?

I saw that it can assume values:
- 0=CSparse (default);
- 1=PGC;
- 2=Cholmod;
- 3=Eigen.

What are these (CSparse, PGC, Cholmod and Eigen) choices and what are their relative differences and effects?

If you need more clarifications, I'm here.

Thanks a lot.

           Manuel
Reply | Threaded
Open this post in threaded view
|

Re: Info on some parameters

matlabbe
Administrator
For this specific g2o parameter, see g2o documentation.

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

Re: Info on some parameters

manuel.lo
This post was updated on .
Hi Mathieu.

Thanks a lot for your answers.

At moment, I'm using Hokuyo UTM-30LX and Kinectv2.

I have set tf between Hokuyo and Kinectv2 and, in fact, the scans are
consistent.

I'm mapping 3D then 6 DoF with ICP active on registration options, but I
have 2 cases:
1) narrow ICP parameters ie low thresholds and loop closures are rejected
and not good;
2) if we relax parameters, loop closures accepted, but to make the scans
adhere, the map isn't good (it's cambered).

What would you recommend for a correct use of Hokuyo? Is it a parameter
matter or something other?

Thanks.

             Manuel
Reply | Threaded
Open this post in threaded view
|

Re: Info on some parameters

matlabbe
Administrator
This post was updated on .
What is current launch file? Do you have a database to share?