Closed hengjiUSTC closed 3 years ago
I'v also tried without filtering VLP16's ground points, the z drift is bigger.
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!
Thanks!
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.
My rosbag validation:
lua
launch
bag
My data is recorded on a gazebo. I tried use scan with/without odom by setting
use_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:
Result with odom:
Topdown View:
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.