cartographer-project / cartographer_ros

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

The submap tips over #1221

Open MrGitGo opened 5 years ago

MrGitGo commented 5 years ago

I am working with a tof camera and my problem is this:

Screenshot-correct

Then this happens:

Screenshot-wrong

I have looked at the imu (rostopic echo /imu) and I couldn't see any changes in there. So I think there is no problem with the imu or the odometry.

This is my lua:

include "map_builder.lua"
include "trajectory_builder.lua"

options = {
  map_builder = MAP_BUILDER,
  trajectory_builder = TRAJECTORY_BUILDER,
  map_frame = "map",
  tracking_frame = "imu",

  published_frame = "odom",
  odom_frame = "odom",
  provide_odom_frame = false,
  publish_frame_projected_to_2d = false,
  use_odometry = true,
  use_nav_sat = false,
  use_landmarks = false,
  num_laser_scans = 0,
  num_multi_echo_laser_scans = 0,
  num_subdivisions_per_laser_scan = 1,
  num_point_clouds = 1,
  lookup_transform_timeout_sec = 0.2,--0.1
  submap_publish_period_sec = 0.5,--0.1
  pose_publish_period_sec = 5e-3,
  trajectory_publish_period_sec = 30e-5,
  rangefinder_sampling_ratio = .5,
  odometry_sampling_ratio = 1.,
  fixed_frame_pose_sampling_ratio = 1.,
  imu_sampling_ratio = 1.,
  landmarks_sampling_ratio = 1.,

}

-- if point cloud frequency is low e.g. 10 hz then decrease submaps.num_range_data to 5, optimize_every_n_nodes to 30

MAP_BUILDER.use_trajectory_builder_3d = true
MAP_BUILDER.num_background_threads = 6

TRAJECTORY_BUILDER_3D.use_online_correlative_scan_matching = true

TRAJECTORY_BUILDER_3D.submaps.num_range_data = 100 --120

TRAJECTORY_BUILDER_3D.high_resolution_adaptive_voxel_filter.min_num_points = 1050 --150
TRAJECTORY_BUILDER_3D.high_resolution_adaptive_voxel_filter.max_length = 10. --2.
TRAJECTORY_BUILDER_3D.high_resolution_adaptive_voxel_filter.max_range = 15. --15.

Do you also have hints for tuning?

This is the bag file: https://www.dropbox.com/s/cuc9fmy3zcrjz6a/2019-03-12-Neu.bag?dl=0

gaschler commented 5 years ago

I still suspect IMU, please post the data contents of a few IMU messages.

Also, please post the text output of rosbag_validate as the issue template describes.

Cartographer initializes submap orientation with IMU gravity direction.

TRAJECTORY_BUILDER_3D.use_online_correlative_scan_matching = true

Why do you use the correlative scan matcher?

use_odometry = true,

For tuning, always start with as few input as possible, so no odometry. Only add after it works with the minimum sensor set.

MrGitGo commented 5 years ago

Thank you for your answer! I put the correlative scan matcher out and it works fine without. Thanks!

MrGitGo commented 5 years ago

Hey @gaschler I thought the problem was solved but it's not. The tip over is not that big anymore. Thats why I thought it is solved but I have here the rosbag validate: https://gist.github.com/Semih67/671cf968358a3178c9abb34e8e26f9f3

and this is my imu data:

header:
  seq: 1359
  stamp:
    secs: 1552894209
    nsecs: 922173471
  frame_id: "imu"
orientation:
  x: 0.0
  y: 0.0
  z: 0.0
  w: 0.0
orientation_covariance: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]
angular_velocity:
  x: -0.00111111111111
  y: -0.00444444444444
  z: -0.00111111111111
angular_velocity_covariance: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]

I hope you can help me with this EDIT: @gaschler or @MichaelGrupp I have noticed that it could be a problem of the global slam. If I set optimize every n nodes to zero, the imu stays at the correct rotation. But if I increase it, the higher the value the longer it takes to get the wrong rotation

MrGitGo commented 5 years ago

And here is more:

---
header:
  seq: 1075
  stamp:
    secs: 1552894748
    nsecs: 156453738
  frame_id: "imu"
orientation:
  x: 0.0
  y: 0.0
  z: 0.0
  w: 0.0
orientation_covariance: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]
angular_velocity:
  x: 0.0
  y: 0.00111111111111
  z: 0.0
angular_velocity_covariance: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]
linear_acceleration:
  x: -0.13
  y: 0.24
  z: 9.49
linear_acceleration_covariance: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]
---
header:
  seq: 1076
  stamp:
    secs: 1552894748
    nsecs: 166435749
  frame_id: "imu"
orientation:
  x: 0.0
  y: 0.0
  z: 0.0
  w: 0.0
orientation_covariance: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]
angular_velocity:
  x: -0.00111111111111
  y: 0.0
  z: 0.0
angular_velocity_covariance: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]
linear_acceleration:
  x: -0.16
  y: 0.27
  z: 9.52
linear_acceleration_covariance: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]
---
header:
  seq: 1077
  stamp:
    secs: 1552894748
    nsecs: 176433824
  frame_id: "imu"
orientation:
  x: 0.0
  y: 0.0
  z: 0.0
  w: 0.0
orientation_covariance: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]
angular_velocity:
  x: -0.00111111111111
  y: 0.00111111111111
  z: 0.0
angular_velocity_covariance: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]
linear_acceleration:
  x: -0.14
  y: 0.23
  z: 9.55
linear_acceleration_covariance: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]
---
header:
  seq: 1078
  stamp:
    secs: 1552894748
    nsecs: 186434875
  frame_id: "imu"
orientation:
  x: 0.0
  y: 0.0
  z: 0.0
  w: 0.0
orientation_covariance: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]
angular_velocity:
  x: -0.00222222222222
  y: 0.00333333333333
  z: -0.00111111111111
angular_velocity_covariance: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]
linear_acceleration:
  x: -0.16
  y: 0.22
  z: 9.55
linear_acceleration_covariance: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]
jccurtis commented 5 years ago

The jump in rotation during global slam (pose graph optimization) is the exact issue I observe (#1201) with a dual lidar system. The result of local slam is relatively stable but there is something about the global optimization which I don't understand and have likely configured incorrectly. Do you notice this if you start from a stationary pose or if you are moving at the beginning of the data set?