Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Tuning cartographer with odometry #1122

Closed
DoctorSnake opened this issue Apr 26, 2018 · 10 comments
Closed

Tuning cartographer with odometry #1122

DoctorSnake opened this issue Apr 26, 2018 · 10 comments
Assignees

Comments

@DoctorSnake
Copy link

DoctorSnake commented Apr 26, 2018

Hi @SirVer , @wohe

Following our email exchange, I'm opening an issue here to ask for some tuning guidance.
We are running into some problems with integrating our odometry to cartographer.

When we use the laser scan only, by setting the following parameter to "true",
TRAJECTORY_BUILDER_2D.use_online_correlative_scan_matching = true
the mapping works well up until the door is opened at the end. We are hoping the odometry information will improve that part.

When we use laser scan + odometry, the mapping is actually a lot worse. The map drifts a lot, as if the algorithm was not tracking the rotation correctly.

The following google drive link contains all the data :

  • the rosbag with laser scan, odometry and the tf and tf_static
  • the ".lua" configuration files
  • the videos of each scenario

https://drive.google.com/drive/folders/18yZHLtLivF58gpXP5a_AM5zuDGEjMg2W?usp=sharing

Thanks a lot for your help

@SirVer SirVer self-assigned this Apr 26, 2018
@SirVer
Copy link
Contributor

SirVer commented Apr 26, 2018

Your example is missing your URDF. How are odom and the laser frame connected?

@DoctorSnake
Copy link
Author

Okay, so I have included 2 files in the google drive :

  • maryam.urdf.xacro, the contains the global urdf of the robot
  • nav_module.urdf.xacro, that contains the specific part where the laser sensor is located

Basically those two files allowed to generate a /tf_static from "base_footprint" to "base_laser" (the frame of the laser scan).
This /tf_static that is already contained in the rosbag.There is also a published /tf from odom to base_footprint.

Concerning the tuning, i have made some progress by lowering the rotation weight in the ceres scan matcher (from 40 to 0.01) :

TRAJECTORY_BUILDER_2D.use_online_correlative_scan_matching = false TRAJECTORY_BUILDER_2D.ceres_scan_matcher.translation_weight = 10. TRAJECTORY_BUILDER_2D.ceres_scan_matcher.rotation_weight = 0.01

The drift now occurs only when a new submap is created. but inside a submab the mapping is quite good.

@DoctorSnake
Copy link
Author

DoctorSnake commented Jun 1, 2018

Hi, @SirVer
I have some updates.

The main problem was our odometry data, indeed the wheels did not have the same pressure, thus not the same diameters. The result was a drift in odometry twist :
odometry yaw rate = true yaw rate + error_ratio* linear velocity / distance between wheels

The first solution for us was to use calibrated odometry with cartographer. But it's a heavy solution :

  • we would have to do that for all robots
  • and we would have to do that frequently in case of pressure loss in the wheels

The best solution was still to tune cartographer's global SLAM to be robust to that kind of odometry error. We have found a set of parameters in the global SLAM that seem to work

POSE_GRAPH.matcher_translation_weight = 1e5 POSE_GRAPH.matcher_rotation_weight = 0.01

Additionally we saw in some other issues, that enabling the online_correlative_scan_matcher did not really disable the use of odometry, but combine both the correlative and the ceres scan matcher (that use odometry). Thus we added this line for "precaution"
TRAJECTORY_BUILDER_2D.use_online_correlative_scan_matching = true

To summarize, our .lua file looks like this now

include "trajectory_builder.lua"

options = {
  map_builder = MAP_BUILDER,
  trajectory_builder = TRAJECTORY_BUILDER,
  map_frame = "map",
  tracking_frame = "base_laser",
  published_frame = "odom",
  odom_frame = "odom_carto",
  provide_odom_frame = false,
  use_odometry = true,
  num_laser_scans = 1,
  num_multi_echo_laser_scans = 0,
  num_subdivisions_per_laser_scan = 1,
  num_point_clouds = 0,
  lookup_transform_timeout_sec = 0.2,
  submap_publish_period_sec = 0.3,
  pose_publish_period_sec = 5e-3,
  trajectory_publish_period_sec = 30e-3,
  rangefinder_sampling_ratio = 1.,
  odometry_sampling_ratio = 1.,
  imu_sampling_ratio = 1.,
  use_nav_sat=false,
  fixed_frame_pose_sampling_ratio = 1.,
}

MAP_BUILDER.use_trajectory_builder_2d = true

TRAJECTORY_BUILDER_2D.use_imu_data = false
TRAJECTORY_BUILDER_2D.use_online_correlative_scan_matching = true
TRAJECTORY_BUILDER_2D.ceres_scan_matcher.translation_weight = 10.
TRAJECTORY_BUILDER_2D.ceres_scan_matcher.rotation_weight = 0.01

POSE_GRAPH.matcher_translation_weight = 1e5
POSE_GRAPH.matcher_rotation_weight = 0.01
POSE_GRAPH.constraint_builder.min_score = 0.65
POSE_GRAPH.constraint_builder.global_localization_min_score = 0.7

return options```

@JiahengZhao
Copy link

Hi, @DoctorSnake , have you tackled the problem you met?
I'm trying to tuning cartographer with odometry according to the Doc "Odometry in Global Optimization". However, as a beginner I'm confused with the procedure.

I noticed in your rosbag file, the odom is:

pose:
pose:
position:
x: 0.0
y: 0.0
z: 0.0
orientation:
x: 0.0
y: 0.0
z: 0.0
w: 1.0
covariance: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]
twist:
twist:
linear:
x: -0.0
y: 0.0
z: 0.0
angular:
x: 0.0
y: 0.0
z: 0.0
covariance: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]

What do z and w mean in orientation? And twist? During the process the covariance remains 0, is it the weight of odom that works during local SLAM?

I'm really thankful for your rely!

@gaschler
Copy link
Contributor

Closing inactive issues.

@DoctorSnake
Copy link
Author

DoctorSnake commented Aug 28, 2018

I was still waiting for some support...
Anyway I have noticed that cartographer uses the position fields in odometry instead of speed for scan matching.

I have purposely modified the odometry in gazebo simulation to reproduce our real data :

  • first a bias in yaw rate in the twist field. The bias being proportional to linear speed.
    There was almost no effect on cartographer.

  • then i integrated that bias in the position field, so that it was drifting. Then there was a clear effect on cartographer output trajectory.

I what i am saying is correct, i hope some people in the team can take a look at that. Because in my opinion only twist values should be used from odometry in the scan matcher.

Kind Regards

@JiahengZhao
Copy link

JiahengZhao commented Aug 28, 2018 via email

@DoctorSnake
Copy link
Author

Hi, thank you for your response.
That confirms my guess then.
In which file can i find AddOdometry ?

Kind Regards

@DoctorSnake
Copy link
Author

Okay i found a bunch of files with AddOdometryData methods, including pose_extrapolator.cc.
And it is true it only the pose is used, and never the twist.

In my opinion odometry should be used the same way IMU is used, meaning only last known position from cartographer + angular velocity * dt = initial guess for scan matching.

Using pose in odometry means incredibly relying on it, which can only be done in a perfect world (even ground, not slippery, no bias in the odometry calculation model, etc)...

@vagrant-drift
Copy link

@DoctorSnake in fact it does not use the pose but use pose’s difference and can avoid accumulated error

Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment
Labels
None yet
Projects
None yet
Development

No branches or pull requests

5 participants