introlab / rtabmap_ros

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

Is there any parameters for optimization? #854

Open robotdevel opened 1 year ago

robotdevel commented 1 year ago

Hello sir.

I was testing rtabmap to use rgb-d camera and 2d LiDAR for generating 2d map.

my question is that "The rtabmap has parameters for optimization?"

when I finish to do rtabmap SLAM it has little error when robot took rotation motion(yaw rotation).

So I thought that it can be optimized if rtabmap has a margin about rotation error or optimization iteration parameters.

Would you help me about my problem?

Thank you so much.

matlabbe commented 1 year ago

There are parameters here:

rtabmap --params | grep Optimize

Param: GTSAM/Optimizer = "1"                               [0=Levenberg 1=GaussNewton 2=Dogleg]
Param: Mem/UseOdomGravity = "false"                        [Use odometry instead of IMU orientation to add gravity links to new nodes created. We assume that odometry is already aligned with gravity (e.g., we are using a VIO approach). Gravity constraints are used by graph optimization only if "Optimizer/GravitySigma" is not zero.]
Param: Optimizer/Epsilon = "0.00001"                       [Stop optimizing when the error improvement is less than this value.]
Param: Optimizer/GravitySigma = "0.3"                      [Gravity sigma value (>=0, typically between 0.1 and 0.3). Optimization is done while preserving gravity orientation of the poses. This should be used only with visual/lidar inertial odometry approaches, for which we assume that all odometry poses are aligned with gravity. Set to 0 to disable gravity constraints. Currently supported only with g2o and GTSAM optimization strategies (see Optimizer/Strategy).]
Param: Optimizer/Iterations = "20"                         [Optimization iterations.]
Param: Optimizer/LandmarksIgnored = "false"                [Ignore landmark constraints while optimizing. Currently only g2o and gtsam optimization supports this.]
Param: Optimizer/PriorsIgnored = "true"                    [Ignore prior constraints (global pose or GPS) while optimizing. Currently only g2o and gtsam optimization supports this.]
Param: Optimizer/Robust = "false"                          [Robust graph optimization using Vertigo (only work for g2o and GTSAM optimization strategies). Not compatible with "RGBD/OptimizeMaxError" if enabled.]
Param: Optimizer/Strategy = "2"                            [Graph optimization strategy: 0=TORO, 1=g2o, 2=GTSAM and 3=Ceres.]
Param: Optimizer/VarianceIgnored = "false"                 [Ignore constraints' variance. If checked, identity information matrix is used for each constraint. Otherwise, an information matrix is generated from the variance saved in the links.]
Param: RGBD/MaxOdomCacheSize = "10"                        [Maximum odometry cache size. Used only in localization mode (when Mem/IncrementalMemory=false). This is used to get smoother localizations and to verify localization transforms (when RGBD/OptimizeMaxError!=0) to make sure we don't teleport to a location very similar to one we previously localized on. Set 0 to disable caching.]
Param: RGBD/OptimizeFromGraphEnd = "false"                 [Optimize graph from the newest node. If false, the graph is optimized from the oldest node of the current graph (this adds an overhead computation to detect to oldest node of the current graph, but it can be useful to preserve the map referential from the oldest node). Warning when set to false: when some nodes are transferred, the first referential of the local map may change, resulting in momentary changes in robot/map position (which are annoying in teleoperation).]
Param: RGBD/OptimizeMaxError = "3.0"                       [Reject loop closures if optimization error ratio is greater than this value (0=disabled). Ratio is computed as absolute error over standard deviation of each link. This will help to detect when a wrong loop closure is added to the graph. Not compatible with "Optimizer/Robust" if enabled.]
Param: g2o/Optimizer = "0"                                 [0=Levenberg 1=GaussNewton]

To adjust the optimization, it is often greatly dependent on the covariance you set in odometry topic.

SiinaIng commented 1 year ago

How to use this command rtabmap --params | grep Optimize on windows?

matlabbe commented 1 year ago

Other option is to look in this file: https://github.com/introlab/rtabmap/blob/master/corelib/include/rtabmap/core/Parameters.h

If you installed windows binaries, you can do RTABMap.exe --params