For this example we'll start at ``cartographer`` commit `aba4575`_ and ``cartographer_ros`` commit `99c23b6`_ and look at the bag ``b2-2016-04-27-12-31-41.bag`` from our test data set.
Local SLAM drifts over time, only loop closure can fix this drift.
Submaps must be small enough so that the drift inside them is below the resolution, so that they are locally correct.
On the other hand, they should be large enough to be being distinct for loop closure to work properly.
The size of submaps is configured through ``TRAJECTORY_BUILDER_2D.submaps.num_range_data``.
Looking at the individual submaps for this example they already fit the two constraints rather well, so we assume this parameter is well tuned.
The choice of scan matchers
^^^^^^^^^^^^^^^^^^^^^^^^^^^
The idea behind local SLAM is to use sensor data of other sensors besides the range finder to predict where the next scan should be inserted into the submap.
Then, the ``CeresScanMatcher`` takes this as prior and finds the best spot where the scan match fits the submap.
It does this by interpolating the submap and sub-pixel aligning the scan.
This is fast, but cannot fix errors that are significantly larger than the resolution of the submaps.
If your sensor setup and timing is reasonable, using only the ``CeresScanMatcher`` is usually the best choice to make.
If you do not have other sensors or you do not trust them, Cartographer also provides a ``RealTimeCorrelativeScanMatcher``.
It uses an approach similar to how scans are matched against submaps in loop closure, but instead it matches against the current submap.
The best match is then used as prior for the ``CeresScanMatcher``.
This scan matcher is very expensive and will essentially override any signal from other sensors but the range finder, but it is robust in feature rich environments.
Tuning the correlative scan matcher
^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^
TODO
Tuning the ``CeresScanMatcher``
^^^^^^^^^^^^^^^^^^^^^^^^^^^^^
In our case, the scan matcher can freely move the match forward and backwards without impacting the score.
We'd like to penalize this situation by making the scan matcher pay more for deviating from the prior that it got.
The two parameters controlling this are ``TRAJECTORY_BUILDER_2D.ceres_scan_matcher.translation_weight`` and ``rotation_weight``.
The higher, the more expensive it is to move the result away from the prior, or in other words: scan matching has to generate a higher score in another position to be accepted.
For instructional purposes, let's make deviating from the prior really expensive:
This allows the optimizer to pretty liberally overwrite the scan matcher results.
This results in poses close to the prior, but inconsistent with the depth sensor and clearly broken.
Experimenting with this value yields a better result at ``2e2``.
.. TODO(hrapp): VIDEO with translation_weight = 2e2
Here, the scan matcher used rotation to still slightly mess up the result though.
Setting the ``rotation_weight`` to ``4e2`` leaves us with a reasonable result.
Verification
------------
To make sure that we did not overtune for this particular issue, we need to run the configuration against other collected data.
In this case, the new parameters did reveal slipping, for example at the beginning of ``b2-2016-04-05-14-44-52.bag``, so we had to lower the ``translation_weight`` to ``1e2``.
This setting is worse for the case we wanted to fix, but no longer slips.
Before checking them in, we normalize all weights, since they only have relative meaning.
The result of this tuning was `PR 428`_.
In general, always try to tune for a platform, not a particular bag.