Browse Source

Follow googlecartographer/cartographer#682. (#77)

[RFC=0001](https://github.com/googlecartographer/rfcs/blob/master/text/0001-renaming-sparse-pose-graph.md)
Wolfgang Hess 8 years ago
parent
commit
b477a3d1ca

+ 3 - 3
cartographer_turtlebot/configuration_files/turtlebot_depth_camera_2d.lua

@@ -51,8 +51,8 @@ TRAJECTORY_BUILDER_2D.ceres_scan_matcher.rotation_weight = 300
 
 TRAJECTORY_BUILDER_2D.submaps.resolution = 0.035
 TRAJECTORY_BUILDER_2D.submaps.num_range_data = 120
-SPARSE_POSE_GRAPH.optimize_every_n_scans = 120
-SPARSE_POSE_GRAPH.constraint_builder.min_score = 0.82
-SPARSE_POSE_GRAPH.constraint_builder.sampling_ratio = 1.
+POSE_GRAPH.optimize_every_n_scans = 120
+POSE_GRAPH.constraint_builder.min_score = 0.82
+POSE_GRAPH.constraint_builder.sampling_ratio = 1.
 
 return options

+ 9 - 9
cartographer_turtlebot/configuration_files/turtlebot_depth_camera_3d.lua

@@ -60,15 +60,15 @@ TRAJECTORY_BUILDER_3D.ceres_scan_matcher.translation_weight = 4.
 TRAJECTORY_BUILDER_3D.ceres_scan_matcher.rotation_weight = 1e3
 TRAJECTORY_BUILDER_3D.ceres_scan_matcher.only_optimize_yaw = true
 
-SPARSE_POSE_GRAPH.constraint_builder.sampling_ratio = 0.2
-SPARSE_POSE_GRAPH.optimization_problem.ceres_solver_options.max_num_iterations = 10
-SPARSE_POSE_GRAPH.constraint_builder.min_score = 0.48
-SPARSE_POSE_GRAPH.constraint_builder.log_matches = true
-SPARSE_POSE_GRAPH.constraint_builder.fast_correlative_scan_matcher_3d.min_rotational_score = 0.
-SPARSE_POSE_GRAPH.constraint_builder.fast_correlative_scan_matcher_3d.linear_xy_search_window = 2.
+POSE_GRAPH.constraint_builder.sampling_ratio = 0.2
+POSE_GRAPH.optimization_problem.ceres_solver_options.max_num_iterations = 10
+POSE_GRAPH.constraint_builder.min_score = 0.48
+POSE_GRAPH.constraint_builder.log_matches = true
+POSE_GRAPH.constraint_builder.fast_correlative_scan_matcher_3d.min_rotational_score = 0.
+POSE_GRAPH.constraint_builder.fast_correlative_scan_matcher_3d.linear_xy_search_window = 2.
 
-SPARSE_POSE_GRAPH.optimization_problem.huber_scale = 1e1
-SPARSE_POSE_GRAPH.optimization_problem.acceleration_weight = 1e-1
-SPARSE_POSE_GRAPH.optimization_problem.rotation_weight = 1e3
+POSE_GRAPH.optimization_problem.huber_scale = 1e1
+POSE_GRAPH.optimization_problem.acceleration_weight = 1e-1
+POSE_GRAPH.optimization_problem.rotation_weight = 1e3
 
 return options

+ 2 - 2
cartographer_turtlebot/configuration_files/turtlebot_urg_lidar_2d.lua

@@ -46,7 +46,7 @@ TRAJECTORY_BUILDER_2D.use_imu_data = true
 TRAJECTORY_BUILDER_2D.use_online_correlative_scan_matching = true
 TRAJECTORY_BUILDER_2D.motion_filter.max_angle_radians = math.rad(0.1)
 
-SPARSE_POSE_GRAPH.constraint_builder.min_score = 0.65
-SPARSE_POSE_GRAPH.constraint_builder.global_localization_min_score = 0.7
+POSE_GRAPH.constraint_builder.min_score = 0.65
+POSE_GRAPH.constraint_builder.global_localization_min_score = 0.7
 
 return options