Follow googlecartographer/cartographer#682. (#598)
[RFC=0001](https://github.com/googlecartographer/rfcs/blob/master/text/0001-renaming-sparse-pose-graph.md)master
parent
e6060567b0
commit
d2bb8b3d01
|
@ -15,6 +15,6 @@
|
||||||
include "backpack_2d.lua"
|
include "backpack_2d.lua"
|
||||||
|
|
||||||
TRAJECTORY_BUILDER.pure_localization = true
|
TRAJECTORY_BUILDER.pure_localization = true
|
||||||
SPARSE_POSE_GRAPH.optimize_every_n_scans = 20
|
POSE_GRAPH.optimize_every_n_scans = 20
|
||||||
|
|
||||||
return options
|
return options
|
||||||
|
|
|
@ -41,11 +41,11 @@ TRAJECTORY_BUILDER_3D.scans_per_accumulation = 160
|
||||||
|
|
||||||
MAP_BUILDER.use_trajectory_builder_3d = true
|
MAP_BUILDER.use_trajectory_builder_3d = true
|
||||||
MAP_BUILDER.num_background_threads = 7
|
MAP_BUILDER.num_background_threads = 7
|
||||||
SPARSE_POSE_GRAPH.optimization_problem.huber_scale = 5e2
|
POSE_GRAPH.optimization_problem.huber_scale = 5e2
|
||||||
SPARSE_POSE_GRAPH.optimize_every_n_scans = 320
|
POSE_GRAPH.optimize_every_n_scans = 320
|
||||||
SPARSE_POSE_GRAPH.constraint_builder.sampling_ratio = 0.03
|
POSE_GRAPH.constraint_builder.sampling_ratio = 0.03
|
||||||
SPARSE_POSE_GRAPH.optimization_problem.ceres_solver_options.max_num_iterations = 10
|
POSE_GRAPH.optimization_problem.ceres_solver_options.max_num_iterations = 10
|
||||||
SPARSE_POSE_GRAPH.constraint_builder.min_score = 0.62
|
POSE_GRAPH.constraint_builder.min_score = 0.62
|
||||||
SPARSE_POSE_GRAPH.constraint_builder.global_localization_min_score = 0.66
|
POSE_GRAPH.constraint_builder.global_localization_min_score = 0.66
|
||||||
|
|
||||||
return options
|
return options
|
||||||
|
|
|
@ -15,6 +15,6 @@
|
||||||
include "backpack_3d.lua"
|
include "backpack_3d.lua"
|
||||||
|
|
||||||
TRAJECTORY_BUILDER.pure_localization = true
|
TRAJECTORY_BUILDER.pure_localization = true
|
||||||
SPARSE_POSE_GRAPH.optimize_every_n_scans = 100
|
POSE_GRAPH.optimize_every_n_scans = 100
|
||||||
|
|
||||||
return options
|
return options
|
||||||
|
|
|
@ -44,6 +44,6 @@ TRAJECTORY_BUILDER_2D.use_imu_data = false
|
||||||
TRAJECTORY_BUILDER_2D.real_time_correlative_scan_matcher.linear_search_window = 0.15
|
TRAJECTORY_BUILDER_2D.real_time_correlative_scan_matcher.linear_search_window = 0.15
|
||||||
TRAJECTORY_BUILDER_2D.real_time_correlative_scan_matcher.angular_search_window = math.rad(35.)
|
TRAJECTORY_BUILDER_2D.real_time_correlative_scan_matcher.angular_search_window = math.rad(35.)
|
||||||
|
|
||||||
SPARSE_POSE_GRAPH.optimization_problem.huber_scale = 1e2
|
POSE_GRAPH.optimization_problem.huber_scale = 1e2
|
||||||
|
|
||||||
return options
|
return options
|
||||||
|
|
|
@ -49,8 +49,8 @@ TRAJECTORY_BUILDER_2D.real_time_correlative_scan_matcher.linear_search_window =
|
||||||
TRAJECTORY_BUILDER_2D.real_time_correlative_scan_matcher.translation_delta_cost_weight = 10.
|
TRAJECTORY_BUILDER_2D.real_time_correlative_scan_matcher.translation_delta_cost_weight = 10.
|
||||||
TRAJECTORY_BUILDER_2D.real_time_correlative_scan_matcher.rotation_delta_cost_weight = 1e-1
|
TRAJECTORY_BUILDER_2D.real_time_correlative_scan_matcher.rotation_delta_cost_weight = 1e-1
|
||||||
|
|
||||||
SPARSE_POSE_GRAPH.optimization_problem.huber_scale = 1e2
|
POSE_GRAPH.optimization_problem.huber_scale = 1e2
|
||||||
SPARSE_POSE_GRAPH.optimize_every_n_scans = 35
|
POSE_GRAPH.optimize_every_n_scans = 35
|
||||||
SPARSE_POSE_GRAPH.constraint_builder.min_score = 0.65
|
POSE_GRAPH.constraint_builder.min_score = 0.65
|
||||||
|
|
||||||
return options
|
return options
|
||||||
|
|
|
@ -44,11 +44,11 @@ TRAJECTORY_BUILDER_3D.submaps.num_range_data = 40.
|
||||||
|
|
||||||
MAP_BUILDER.use_trajectory_builder_3d = true
|
MAP_BUILDER.use_trajectory_builder_3d = true
|
||||||
MAP_BUILDER.num_background_threads = 7
|
MAP_BUILDER.num_background_threads = 7
|
||||||
SPARSE_POSE_GRAPH.optimization_problem.huber_scale = 5e2
|
POSE_GRAPH.optimization_problem.huber_scale = 5e2
|
||||||
SPARSE_POSE_GRAPH.optimize_every_n_scans = 40
|
POSE_GRAPH.optimize_every_n_scans = 40
|
||||||
SPARSE_POSE_GRAPH.constraint_builder.sampling_ratio = 0.03
|
POSE_GRAPH.constraint_builder.sampling_ratio = 0.03
|
||||||
SPARSE_POSE_GRAPH.optimization_problem.ceres_solver_options.max_num_iterations = 10
|
POSE_GRAPH.optimization_problem.ceres_solver_options.max_num_iterations = 10
|
||||||
SPARSE_POSE_GRAPH.constraint_builder.min_score = 0.62
|
POSE_GRAPH.constraint_builder.min_score = 0.62
|
||||||
SPARSE_POSE_GRAPH.constraint_builder.log_matches = true
|
POSE_GRAPH.constraint_builder.log_matches = true
|
||||||
|
|
||||||
return options
|
return options
|
||||||
|
|
Loading…
Reference in New Issue