Ceres Scan Matcher Options

1,478 views
Skip to first unread message

Nicholash Bedi

unread,
Feb 9, 2017, 6:11:36 PM2/9/17
to google-cartographer
Hello,

I was wondering what do the following parameters do, in respect to the Ceres Scan Matcher, and how do I determine what value they should be?
  • occupied_space_cost_functor_weight
  • previous_pose_translation_delta_cost_functor_weight
  • initial_pose_estimate_rotation_delta_cost_functor_weight
  • covariance_scale
  • use_nonmonotonic_steps


Background:
I am trying to use the Ceres Scan matcher independently of the mapping portion of Google cartographer. I am currently running the scan matcher with the values in the trajectory_builder_2d.lua form :


"  ceres_scan_matcher = {
    occupied_space_cost_functor_weight = 20.,
    previous_pose_translation_delta_cost_functor_weight = 1.,
    initial_pose_estimate_rotation_delta_cost_functor_weight = 1e2,
    covariance_scale = 2.34e-4,
    ceres_solver_options = {
      use_nonmonotonic_steps = true,
      max_num_iterations = 50,
      num_threads = 1,
    },
  },"


However, the scan matcher's estimates seem to be quite bad. I ran three tests: one displacing the vehicle 3cm from its original position, the second, displacing the vehicle 16cm from its original position, and lastly, displacing the vehicle 46cm from its original position. I ran each test 10 times with the Real time correlative and Fast correlative scan matcher as well and got the following results:

I was wondering if you could give any insight into what these parameters do, a potential range for these values, why there are different results given the same input and any other relevant information.


Please let me know if I can provide more information,

Nick

Auto Generated Inline Image 1
Auto Generated Inline Image 2

Damon Kohler

unread,
Feb 10, 2017, 5:48:36 AM2/10/17
to Nicholash Bedi, google-cartographer
Hi Nick,

In order to make sense of your graphs, I think we need some more information.

- What resolution is the map your using the scan matchers against? The accuracy of both correlative scan matchers (CSM) is limited by resolution.

- Are you applying rotations as well as translations to the perturbations? Rotations are much harder to correct for the Ceres scan matcher.

Both of the correlative scan matchers should always return the same error so long as the perturbation is within the search window. Using them when the perturbation is larger than the search window doesn't make sense. The only other reason they may return different errors is if the environment is repetitive within the search window. Then there may be multiple alignments that produce the same score.

The Ceres scan matcher is only useful for subpixel alignment. That is to say, the initial estimate for the scan match should be within 1 pixel/voxel of the correct alignment. Testing outside that range will produce likely arbitrary results. 

As for descriptions of the parameters, see my inline answers:

On Fri, Feb 10, 2017 at 12:11 AM Nicholash Bedi <nichola...@avidbots.com> wrote:
Hello,

I was wondering what do the following parameters do, in respect to the Ceres Scan Matcher, and how do I determine what value they should be?
  • occupied_space_cost_functor_weight
This weight is applied to the occupied space cost function. This cost function tries to minimize the number of LIDAR returns which do not overlap occupied space. 
  • previous_pose_translation_delta_cost_functor_weight
This is the weight applied to the cost function that tries to minimize the transnational change in position. You can think of it as a zero-motion model. Given a fixed frequency of scan matches, it's roughly equivalent to capping maximum velocity.
  • initial_pose_estimate_rotation_delta_cost_functor_weight
This is the weight applied to the cost function which minimizes deviation from the provided rotational estimate (e.g. from IMU gyros or correlative scan matching).
  • covariance_scale
This scale is applied to the Ceres estimate of covariance before adding the result to the sparse pose graph. It's essentially a weight of how important local SLAM scan matches are.
  • use_nonmonotonic_steps


Background:
I am trying to use the Ceres Scan matcher independently of the mapping portion of Google cartographer. I am currently running the scan matcher with the values in the trajectory_builder_2d.lua form :


"  ceres_scan_matcher = {
    occupied_space_cost_functor_weight = 20.,
    previous_pose_translation_delta_cost_functor_weight = 1.,
    initial_pose_estimate_rotation_delta_cost_functor_weight = 1e2,
    covariance_scale = 2.34e-4,
    ceres_solver_options = {
      use_nonmonotonic_steps = true,
      max_num_iterations = 50,
      num_threads = 1,
    },
  },"


However, the scan matcher's estimates seem to be quite bad. I ran three tests: one displacing the vehicle 3cm from its original position, the second, displacing the vehicle 16cm from its original position, and lastly, displacing the vehicle 46cm from its original position. I ran each test 10 times with the Real time correlative and Fast correlative scan matcher as well and got the following results:

Auto Generated Inline Image 1

Auto Generated Inline Image 2

I was wondering if you could give any insight into what these parameters do, a potential range for these values, why there are different results given the same input and any other relevant information.


Please let me know if I can provide more information,

Nick

--
You received this message because you are subscribed to the Google Groups "google-cartographer" group.
To unsubscribe from this group and stop receiving emails from it, send an email to google-cartogra...@googlegroups.com.
To post to this group, send email to google-ca...@googlegroups.com.
To view this discussion on the web visit https://groups.google.com/d/msgid/google-cartographer/1ccddd12-ba3c-448e-8024-0e950fae5b2a%40googlegroups.com.
For more options, visit https://groups.google.com/d/optout.
--
Google Germany GmbH | Erika-Mann-Strasse | 80636 Muenchen | Germany

AG Hamburg, HRB 86891 | Sitz der Gesellschaft: Hamburg | Geschäftsführer: Matthew Scott Sucherman, Paul Terence Manicle

Nicholash Bedi

unread,
Feb 10, 2017, 4:41:18 PM2/10/17
to google-cartographer, nichola...@avidbots.com
Thanks Damon

The resolution of the map is 0.05m.
It turns out I was applying a different search windows for the each of the correlative search windows. I am now applying the following search window to both correlative scan matchers:
  linear_search_window_ = 4.0;
  angular_search_window_ = 2.0943951; //  120 degrees
and it is now producing the same result for both correlative scan matchers in almost all scenarios.

I performed another set of tests and it seems as if the cerca scan matcher is still under performing. I provided the scan matchers an estimate pose equal to the ground truth and than off of the ground truth, in just the x direction, by 0.04m, 0.15m and 0.50m. the rotation estimate was equal to the ground truth in all scenarios. I got the following results: 

Is there anything I can do to improve the Ceres scan matcher results?
Also, to clarify, the Ceres scan matcher should work well if given an estimate within 1 pixel of the ground truth? Would this mean that the Ceres should work well with any estimate within +/- 2.5cm if the resolution is 5cm?

Thanks,
Nick
To unsubscribe from this group and stop receiving emails from it, send an email to google-cartographer+unsub...@googlegroups.com.
Auto Generated Inline Image 1

Damon Kohler

unread,
Feb 13, 2017, 4:59:48 AM2/13/17
to Nicholash Bedi, google-cartographer
I'm still confused by your results. If your resolution is constant, and the perturbation is within the search window, the CSM result shouldn't change between tests. It's an exhaustive search. Can you verify that the result from CSM is changing between tests?

As for Ceres, I would expect good results for +/- 2.5 cm perturbations on a 5cm map. You may find it performs well outside that range as well. But, quality will degrade as the perturbation gets larger. It is a local optimization that relies on a good starting point.


To unsubscribe from this group and stop receiving emails from it, send an email to google-cartogra...@googlegroups.com.
To post to this group, send email to google-ca...@googlegroups.com.
--
Google Germany GmbH | Erika-Mann-Strasse | 80636 Muenchen | Germany

AG Hamburg, HRB 86891 | Sitz der Gesellschaft: Hamburg | Geschäftsführer: Matthew Scott Sucherman, Paul Terence Manicle

--
You received this message because you are subscribed to the Google Groups "google-cartographer" group.
To unsubscribe from this group and stop receiving emails from it, send an email to google-cartogra...@googlegroups.com.

To post to this group, send email to google-ca...@googlegroups.com.

For more options, visit https://groups.google.com/d/optout.
Reply all
Reply to author
Forward
0 new messages