cartographer-project / cartographer_ros

Provides ROS integration for Cartographer.
Apache License 2.0
1.66k stars 1.21k forks source link

combining cartographer with other localization estimates #1003

Closed dan9thsense closed 4 years ago

dan9thsense commented 6 years ago

I am using cartographer and it is working pretty well, but I want to improve localization by adding some other sources, such as visual odometry, amcl, etc. I am trying to use robot_localization to combine cartographer's pose with the other sources.

To do that, I need a good estimate of the covariance in the pose from cartographer. From reading the docs, I think that the covariance is set as a fixed value and I understand the rationale for that-- see here. From that discussion, I think the covariances correspond to matcher.translation_weight and matcher.rotation_weight, however, I think perhaps that the correspondence is inverted (higher covariances mean more uncertainty, but higher weights mean more value is placed on that variable). How do I translate the weights into covariances?

I have been using the default values in cartographer and it works fine with these. However, I have no idea which ones should be used to send the covariances to robot_localization.

I found these default values in trajectory_builder_2d.lua. TRAJECTORY_BUILDER_2D.ceres_scan_matcher.translation_weight = 10. TRAJECTORY_BUILDER_2D.ceres_scan_matcher.rotation_weight = 40.

I found these in pose_graph.lua. Note that the weights it sets for ceres_scan are different than the weights for ceres_scan in trajectory_builder_2d:

POSE_GRAPH.matcher_translation_weight = 500 POSE_GRAPH.matcher_rotation_weight = 1600

POSE_GRAPH.ceres_scan_matcher.translation_weight = 10. POSE_GRAPH.ceres_scan_matcher.rotation_weight = 1.

POSE_GRAPH.optimization_problem.matcher_translation_weight = 1e5 POSE_GRAPH.optimization_problem.matcher_rotation_weight = 0.01

Here are some other default values. I wonder if I should change these to match the actual odometry and IMU covariances in the robot? The actual values are much smaller than these defaults. For example, the odometry pose covariance in translation is about 10. (vs 1e5 as default) and the imu rotation covariance is about 0.1 (vs. 3e5 as default). POSE_GRAPH.optimization_problem.acceleration_weight = 1e3 POSE_GRAPH.optimization_problem.rotation_weight = 3e5 POSE_GRAPH.optimization_problem.local_slam_pose_translation_weight = 1e5 POSE_GRAPH.optimization_problem.local_slam_pose_rotation_weight = 1e5 POSE_GRAPH.optimization_problem.odometry_translation_weight = 1e5 POSE_GRAPH.optimization_problem.odometry_rotation_weight = 1e5 POSE_GRAPH.optimization_problem.fixed_frame_pose_translation_weight = 1e1 POSE_GRAPH.optimization_problem.fixed_frame_pose_rotation_weight = 1e2

selamie commented 5 years ago

Hi,

I'm working on a ground vehicle project and we want to use a similar approach, combining robot_localization with cartographer. Were you ever successful @dan9thsense ?

Thanks!

dan9thsense commented 5 years ago

Yes, it does work, but I never got a good answer regarding the covariance.

RonaldEnsing commented 4 years ago

I am also combining robot localization with cartographer.

@dan9thsense @selamie Does the robot localization odometry that you pass to cartographer include a global estimation (NavSatFix), meaning that you pass a global localization estimate, or is it based on an odometry estimation (e.g. wheel encoders)?

Do the results improve?

dan9thsense commented 4 years ago

I send cartographer just the wheel odometry and imu data. Then I use robot localization to combine the estimates from cartographer with other sources such as visual io and GPS.

RonaldEnsing commented 4 years ago

I send cartographer just the wheel odometry and imu data. Then I use robot localization to combine the estimates from cartographer with other sources such as visual io and GPS.

Have you also tried it the other way around? Using robot localization to fuse wheel odometry and imu, and then pass that to cartographers odometry input?

MichaelGrupp commented 4 years ago

Cartographer does not provide covariances for the reasons stated in the PR that you linked, and the weights are an optimization parameter for each cost term that enters optimization instead of an actual uncertainty measurement.

Closing due to inactivity.