cartographer-project / cartographer_ros

Provides ROS integration for Cartographer.
Apache License 2.0
1.64k stars 1.2k forks source link

VLP16 + IMU tuning issue, and question for Z value drift. #1639

Closed hengjiUSTC closed 3 years ago

hengjiUSTC commented 3 years ago

Hi Cartographer team, I have been testing cartographer with gazebo simulation and the result trajectory have quiet large Z drift. I'v tried a lot of lua changes but all not working. Really hope to get some help here.

  1. My rosbag validation:

    I0604 15:13:43.151882 12826 rosbag_validate_main.cc:399] Time delta histogram for consecutive messages on topic "/imu" (frame_id: "imu_link"):
    Count: 240271  Min: 0.002  Max: 0.006  Mean: 0.00202946
    [0.002000, 0.002400)    ####################    Count: 237476 (98.8367%)  Total: 237476 (98.8367%)
    [0.002400, 0.002800)                            Count: 0 (0%)     Total: 237476 (98.8367%)
    [0.002800, 0.003200)                            Count: 3 (0.00124859%)    Total: 237479 (98.838%)
    [0.003200, 0.003600)                            Count: 0 (0%)     Total: 237479 (98.838%)
    [0.003600, 0.004000)                            Count: 0 (0%)     Total: 237479 (98.838%)
    [0.004000, 0.004400)                            Count: 2784 (1.15869%)    Total: 240263 (99.9967%)
    [0.004400, 0.004800)                            Count: 0 (0%)     Total: 240263 (99.9967%)
    [0.004800, 0.005200)                            Count: 0 (0%)     Total: 240263 (99.9967%)
    [0.005200, 0.005600)                            Count: 0 (0%)     Total: 240263 (99.9967%)
    [0.005600, 0.006000]                            Count: 8 (0.00332957%)    Total: 240271 (100%)
    I0604 15:13:43.153411 12826 rosbag_validate_main.cc:399] Time delta histogram for consecutive messages on topic "/odom" (frame_id: "odom"):
    Count: 48614  Min: 0.007  Max: 0.013  Mean: 0.0100024
    [0.007000, 0.007600)                            Count: 2 (0.00411404%)    Total: 2 (0.00411404%)
    [0.007600, 0.008200)                            Count: 2 (0.00411404%)    Total: 4 (0.00822808%)
    [0.008200, 0.008800)                            Count: 0 (0%)     Total: 4 (0.00822808%)
    [0.008800, 0.009400)                      ##    Count: 4083 (8.39882%)    Total: 4087 (8.40704%)
    [0.009400, 0.010000)                            Count: 0 (0%)     Total: 4087 (8.40704%)
    [0.010000, 0.010600)       #################    Count: 40438 (83.1818%)   Total: 44525 (91.5888%)
    [0.010600, 0.011200)                      ##    Count: 4085 (8.40293%)    Total: 48610 (99.9918%)
    [0.011200, 0.011800)                            Count: 0 (0%)     Total: 48610 (99.9918%)
    [0.011800, 0.012400)                            Count: 3 (0.00617106%)    Total: 48613 (99.9979%)
    [0.012400, 0.013000]                            Count: 1 (0.00205702%)    Total: 48614 (100%)
    E0604 15:13:43.153892 12826 rosbag_validate_main.cc:383] Point data (frame_id: "velodyne") has a large gap, largest is 0.108 s, recommended is [0.0005, 0.05] s with no jitter.
    I0604 15:13:43.154147 12826 rosbag_validate_main.cc:399] Time delta histogram for consecutive messages on topic "/points2" (frame_id: "velodyne"):
    Count: 14152  Min: 0.01  Max: 0.108  Mean: 0.0343472
    [0.010000, 0.019800)                      ##    Count: 1182 (8.35218%)    Total: 1182 (8.35218%)
    [0.019800, 0.029600)                  ######    Count: 3956 (27.9536%)    Total: 5138 (36.3058%)
    [0.029600, 0.039400)                   #####    Count: 3429 (24.2298%)    Total: 8567 (60.5356%)
    [0.039400, 0.049200)                 #######    Count: 4833 (34.1507%)    Total: 13400 (94.6863%)
    [0.049200, 0.059000)                       #    Count: 581 (4.10543%)     Total: 13981 (98.7917%)
    [0.059000, 0.068800)                            Count: 104 (0.734878%)    Total: 14085 (99.5266%)
    [0.068800, 0.078600)                            Count: 39 (0.275579%)     Total: 14124 (99.8021%)
    [0.078600, 0.088400)                            Count: 23 (0.162521%)     Total: 14147 (99.9647%)
    [0.088400, 0.098200)                            Count: 4 (0.0282646%)     Total: 14151 (99.9929%)
    [0.098200, 0.108000]                            Count: 1 (0.00706614%)    Total: 14152 (100%)
  2. lua

  3. launch

  4. bag

My data is recorded on a gazebo. I tried use scan with/without odom by settinguse_odometry = true/false, as usually our vehicle have bad odom outdoor. So I want to study the scan quality with IMU + lidar only. However in both cases (w/o Odom), my result shows big z drift to about 1m. The start and end location on simulator is almost the same spot.

Result without odom: 1lidar_2021-06-04-14-36-53 bag_xray_xz_all

Result with odom: 1lidar_2021-06-04-14-36-53 bag_xray_yz_all 1lidar_2021-06-04-14-36-53 bag_xray_xz_all

Topdown View: 1lidar_2021-06-04-14-36-53 bag_xray_xy_all

I'd be really appreciate if some one could help me tuning my config to eliminate z drift. Also I want to know is that OK the trajectory don't close? Cause I'm thinking maybe it's just because the old trajectory is not updated. How do we know if the map result is correct? Currently I'm hoping the trajectory close as my rosbag's start and end point is in the same place.

hengjiUSTC commented 3 years ago

I'v also tried without filtering VLP16's ground points, the z drift is bigger.

gooney16 commented 3 years ago

Hi, I was running into a similar issue. I'm pasting the lua config file which helped out to fix the issue. The weights can be made better, you'll need to tinker around to get the optimal values.

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

options = { map_builder = MAP_BUILDER, trajectory_builder = TRAJECTORY_BUILDER, map_frame = "map", tracking_frame = "imu_link", published_frame = "base_link", odom_frame = "odom", provide_odom_frame = true, 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, 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., fixed_frame_pose_sampling_ratio = 1., imu_sampling_ratio = 1., landmarks_sampling_ratio = 1., }

MAP_BUILDER.use_trajectory_builder_3d = true MAP_BUILDER.num_background_threads = 7

TRAJECTORY_BUILDER_3D.num_accumulated_range_data = 1 TRAJECTORY_BUILDER_3D.min_range = 2.5 TRAJECTORY_BUILDER_3D.max_range = 50 TRAJECTORY_BUILDER_3D.submaps.num_range_data = 100

TRAJECTORY_BUILDER_3D.ceres_scan_matcher.translation_weight = 10. TRAJECTORY_BUILDER_3D.ceres_scan_matcher.rotation_weight = 1. TRAJECTORY_BUILDER_3D.ceres_scan_matcher.ceres_solver_options.max_num_iterations = 50

POSE_GRAPH.optimization_problem.log_solver_summary = true POSE_GRAPH.optimization_problem.acceleration_weight = 500 --1e3 500 POSE_GRAPH.optimization_problem.rotation_weight = 100 --3e5 1000
POSE_GRAPH.optimization_problem.ceres_solver_options.max_num_iterations = 1000 POSE_GRAPH.optimization_problem.huber_scale = 5e2 POSE_GRAPH.optimize_every_n_nodes = 80 POSE_GRAPH.constraint_builder.sampling_ratio = 0.1 POSE_GRAPH.global_sampling_ratio = 0.003 POSE_GRAPH.constraint_builder.min_score = 0.50 POSE_GRAPH.constraint_builder.global_localization_min_score = 0.55 POSE_GRAPH.constraint_builder.max_constraint_distance = 20. POSE_GRAPH.constraint_builder.fast_correlative_scan_matcher_3d.linear_xy_search_window = 250. POSE_GRAPH.constraint_builder.fast_correlative_scan_matcher_3d.linear_z_search_window = 30. POSE_GRAPH.constraint_builder.fast_correlative_scan_matcher_3d.angular_search_window = math.rad(60.) POSE_GRAPH.constraint_builder.ceres_scan_matcher_3d.ceres_solver_options.max_num_iterations = 50

return options

Hope this works for you!

hengjiUSTC commented 3 years ago

Thanks!