cartographer-project / cartographer_ros

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

Tuning problem with cartographer 2D on KITTI (only velodyne) dataset #1353

Closed UserUsingGit closed 5 years ago

UserUsingGit commented 5 years ago

Hello, I am trying to run cartographer_ros (2D map) on the KITTI dataset (201_09_26_drive_0117) using only the velodyne data (without IMU). With the current configuration, cartographer_ros seems not to be able to find a proper map transformation, so I guess my configuration requires some tuning. All links are provided at the end of this post. I used kitti2bag to convert the data to a rosbag and filtered out all unnecessary information (only point cloud and IMU data included, even if I do not want to use IMU). rosbag validate gives the following output: cartographer_rosbag_validate -bag_filename kitti_0117_filtered.bag E0710 12:32:13.697472 16218 rosbag_validate_main.cc:389] IMU data (frame_id: "imu_link") has a large gap, largest is 0.120025 s, recommended is [0.0005, 0.005] s with no jitter. I0710 12:32:13.697748 16218 rosbag_validate_main.cc:398] Time delta histogram for consecutive messages on topic "/kitti/oxts/imu" (frame_id: "imu_link"): Count: 659 Min: 0.079939 Max: 0.120025 Mean: 0.103449 [0.079939, 0.083947) Count: 5 (0.758725%) Total: 5 (0.758725%) [0.083947, 0.087956) Count: 0 (0.000000%) Total: 5 (0.758725%) [0.087956, 0.091965) Count: 9 (1.365706%) Total: 14 (2.124431%) [0.091965, 0.095973) Count: 0 (0.000000%) Total: 14 (2.124431%) [0.095973, 0.099982) #### Count: 130 (19.726858%) Total: 144 (21.851290%) [0.099982, 0.103991) ######## Count: 257 (38.998482%) Total: 401 (60.849773%) [0.103991, 0.107999) # Count: 44 (6.676783%) Total: 445 (67.526558%) [0.107999, 0.112008) ###### Count: 203 (30.804249%) Total: 648 (98.330803%) [0.112008, 0.116016) Count: 4 (0.606980%) Total: 652 (98.937782%) [0.116016, 0.120025] Count: 7 (1.062215%) Total: 659 (100.000000%) E0710 12:32:13.697800 16218 rosbag_validate_main.cc:382] Point data (frame_id: "velo_link") has a large gap, largest is 0.104271 s, recommended is [0.0005, 0.05] s with no jitter. I0710 12:32:13.697816 16218 rosbag_validate_main.cc:398] Time delta histogram for consecutive messages on topic "/kitti/velo/pointcloud" (frame_id: "velo_link"): Count: 659 Min: 0.102537 Max: 0.104271 Mean: 0.103440 [0.102537, 0.102711) Count: 2 (0.303490%) Total: 2 (0.303490%) [0.102711, 0.102884) Count: 0 (0.000000%) Total: 2 (0.303490%) [0.102884, 0.103057) Count: 1 (0.151745%) Total: 3 (0.455235%) [0.103057, 0.103231) # Count: 22 (3.338392%) Total: 25 (3.793627%) [0.103231, 0.103404) #### Count: 129 (19.575113%) Total: 154 (23.368740%) [0.103404, 0.103577) ############## Count: 467 (70.864944%) Total: 621 (94.233688%) [0.103577, 0.103751) # Count: 33 (5.007587%) Total: 654 (99.241272%) [0.103751, 0.103924) Count: 2 (0.303490%) Total: 656 (99.544762%) [0.103924, 0.104098) Count: 1 (0.151745%) Total: 657 (99.696510%) [0.104098, 0.104271] Count: 2 (0.303490%) Total: 659 (100.000000%)

Even if rosbag validate claims that the framerate is too low, it seems to work in 3D (using pointcloud + IMU). In the 2D case, the map is not properly created. Here is a screenshot: Screenshot from 2019-07-10 12-18-00

Like suggested in #1135 , I played around with TRAJECTORY_BUILDER_2D.min_z and TRAJECTORY_BUILDER_2D.max_z but did not get any good results.

link to rosbag: https://drive.google.com/open?id=1mN-bdOp4fgakswVqUurV-MUAdRE1x3B6 lua configuration (kit_2d.lua): https://github.com/UserUsingGit/cartographer_ros/blob/master/cartographer_ros/configuration_files/kit_2d.lua rviz configuration (demo_kit_2d.rviz): https://github.com/UserUsingGit/cartographer_ros/blob/master/cartographer_ros/configuration_files/demo_kit_2d.rviz launch file (kit_2d.launch): https://github.com/UserUsingGit/cartographer_ros/blob/master/cartographer_ros/launch/kit_2d.launch demo launch file (demo_kit_2d.launch) https://github.com/UserUsingGit/cartographer_ros/blob/master/cartographer_ros/launch/demo_kit_2d.launch urdf file (kit_2d.urdf): https://github.com/UserUsingGit/cartographer_ros/blob/master/cartographer_ros/urdf/kit_2d.urdf

Thanks in advance!

UserUsingGit commented 5 years ago

I resolved the issue by adding the following settings: TRAJECTORY_BUILDER_2D.ceres_scan_matcher.translation_weight = 1e-2 TRAJECTORY_BUILDER_2D.ceres_scan_matcher.rotation_weight = 1e-2 TRAJECTORY_BUILDER_2D.ceres_scan_matcher.occupied_space_weight = 1e1 I do not understand why I had to set the trust on scan matching if TRAJECTORY_BUILDER_2D.use_imu_data = false since I have no other source of sensors, the only source left should be the point cloud topic. If anybody has an explanation to this please let me know. But somehow it was necessary. Additionally I modified max_z and min_z: TRAJECTORY_BUILDER_2D.min_z = -1. TRAJECTORY_BUILDER_2D.max_z = 1.
Now it works wonderfully. Following is the complete configuration of kit_2d.lua (loop closure enabled):

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 = true, use_odometry = false, 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 = 0.1, imu_sampling_ratio = 0.1, landmarks_sampling_ratio = 1., } -- GENERAL MAP_BUILDER.use_trajectory_builder_2d = true -- LOCAL SLAM TRAJECTORY_BUILDER_2D.voxel_filter_size = 0.05 --0.15 TRAJECTORY_BUILDER_2D.ceres_scan_matcher.translation_weight = 1e-2 TRAJECTORY_BUILDER_2D.ceres_scan_matcher.rotation_weight = 1e-2 TRAJECTORY_BUILDER_2D.ceres_scan_matcher.occupied_space_weight = 1e1 TRAJECTORY_BUILDER_2D.use_imu_data = false -- Nr ROS msgs that make one complete scan, Kitti (Velodyne): 1 pointcloud/msg TRAJECTORY_BUILDER_2D.num_accumulated_range_data = 1 -- Define amount of scans per submap TRAJECTORY_BUILDER_2D.submaps.num_range_data = 30 -- Online SLAM TRAJECTORY_BUILDER_2D.use_online_correlative_scan_matching = false -- Tweaking Performance of 2D setup -- TRAJECTORY_BUILDER_3D.ceres_scan_matcher.ceres_solver_options.num_threads = 6 TRAJECTORY_BUILDER_2D.submaps.grid_options_2d.resolution = 0.1 -- 0.05 TRAJECTORY_BUILDER_2D.min_z = -1. -- -1.5 TRAJECTORY_BUILDER_2D.max_z = 1. -- 1.5 -- GLOBAL SLAM -- MAP_BUILDER.num_background_threads = 7 POSE_GRAPH.optimization_problem.huber_scale = 5e2 POSE_GRAPH.optimize_every_n_nodes = 60 -- Global SLAM enabled POSE_GRAPH.constraint_builder.sampling_ratio = 0.03 POSE_GRAPH.optimization_problem.ceres_solver_options.max_num_iterations = 10 POSE_GRAPH.constraint_builder.min_score = 0.62 POSE_GRAPH.constraint_builder.global_localization_min_score = 0.66 return options