From 055728af934fdcf1e4b209aac77621a815d937cb Mon Sep 17 00:00:00 2001 From: Wolfgang Hess Date: Fri, 17 Nov 2017 10:52:22 +0100 Subject: [PATCH] Rename options for consistency. (#686) "scan" is better named "node" if it refers to a node in global SLAM. "penalty factor" is renamed "weight" for consistency with other similar options. "scans_per_accumulation" is renamed "num_accumulated_range_data" to match the code and since the accumulated data is not called "scan". --- cartographer/mapping/id.h | 2 +- cartographer/mapping/pose_graph.cc | 4 +- .../optimization_problem_options.cc | 10 ++--- .../proto/optimization_problem_options.proto | 8 ++-- .../mapping/proto/pose_graph_options.proto | 4 +- .../mapping_2d/local_trajectory_builder.cc | 2 +- .../local_trajectory_builder_options.cc | 4 +- cartographer/mapping_2d/pose_graph.cc | 4 +- .../pose_graph/optimization_problem.cc | 5 +-- cartographer/mapping_2d/pose_graph_test.cc | 6 +-- .../local_trajectory_builder_options.proto | 6 +-- .../mapping_2d/proto/submaps_options.proto | 6 +-- .../mapping_3d/local_trajectory_builder.cc | 2 +- .../local_trajectory_builder_options.cc | 4 +- .../local_trajectory_builder_test.cc | 2 +- cartographer/mapping_3d/pose_graph.cc | 4 +- .../pose_graph/optimization_problem.cc | 4 +- .../pose_graph/optimization_problem_test.cc | 4 +- .../local_trajectory_builder_options.proto | 6 +-- .../proto/motion_filter_options.proto | 6 +-- .../mapping_3d/proto/submaps_options.proto | 6 +-- cartographer/sensor/map_by_time.h | 2 +- configuration_files/pose_graph.lua | 6 +-- configuration_files/trajectory_builder_2d.lua | 2 +- configuration_files/trajectory_builder_3d.lua | 2 +- docs/source/configuration.rst | 42 +++++++++---------- 26 files changed, 75 insertions(+), 78 deletions(-) diff --git a/cartographer/mapping/id.h b/cartographer/mapping/id.h index df07a06..b18e3f6 100644 --- a/cartographer/mapping/id.h +++ b/cartographer/mapping/id.h @@ -324,7 +324,7 @@ class MapById { bool empty() const { return begin() == end(); } - // Returns an iterator to the the first element in the container belonging to + // Returns an iterator to the first element in the container belonging to // trajectory 'trajectory_id' whose time is not considered to go before // 'time', or EndOfTrajectory(trajectory_id) if all keys are considered to go // before 'time'. diff --git a/cartographer/mapping/pose_graph.cc b/cartographer/mapping/pose_graph.cc index 30dfb8b..272a4e5 100644 --- a/cartographer/mapping/pose_graph.cc +++ b/cartographer/mapping/pose_graph.cc @@ -71,8 +71,8 @@ std::vector FromProto( proto::PoseGraphOptions CreatePoseGraphOptions( common::LuaParameterDictionary* const parameter_dictionary) { proto::PoseGraphOptions options; - options.set_optimize_every_n_scans( - parameter_dictionary->GetInt("optimize_every_n_scans")); + options.set_optimize_every_n_nodes( + parameter_dictionary->GetInt("optimize_every_n_nodes")); *options.mutable_constraint_builder_options() = pose_graph::CreateConstraintBuilderOptions( parameter_dictionary->GetDictionary("constraint_builder").get()); diff --git a/cartographer/mapping/pose_graph/optimization_problem_options.cc b/cartographer/mapping/pose_graph/optimization_problem_options.cc index f535050..82d6f8e 100644 --- a/cartographer/mapping/pose_graph/optimization_problem_options.cc +++ b/cartographer/mapping/pose_graph/optimization_problem_options.cc @@ -30,12 +30,10 @@ proto::OptimizationProblemOptions CreateOptimizationProblemOptions( parameter_dictionary->GetDouble("acceleration_weight")); options.set_rotation_weight( parameter_dictionary->GetDouble("rotation_weight")); - options.set_consecutive_scan_translation_penalty_factor( - parameter_dictionary->GetDouble( - "consecutive_scan_translation_penalty_factor")); - options.set_consecutive_scan_rotation_penalty_factor( - parameter_dictionary->GetDouble( - "consecutive_scan_rotation_penalty_factor")); + options.set_consecutive_node_translation_weight( + parameter_dictionary->GetDouble("consecutive_node_translation_weight")); + options.set_consecutive_node_rotation_weight( + parameter_dictionary->GetDouble("consecutive_node_rotation_weight")); options.set_fixed_frame_pose_translation_weight( parameter_dictionary->GetDouble("fixed_frame_pose_translation_weight")); options.set_fixed_frame_pose_rotation_weight( diff --git a/cartographer/mapping/pose_graph/proto/optimization_problem_options.proto b/cartographer/mapping/pose_graph/proto/optimization_problem_options.proto index 4a8e68c..dce9050 100644 --- a/cartographer/mapping/pose_graph/proto/optimization_problem_options.proto +++ b/cartographer/mapping/pose_graph/proto/optimization_problem_options.proto @@ -29,11 +29,11 @@ message OptimizationProblemOptions { // Scaling parameter for the IMU rotation term. double rotation_weight = 9; - // Penalty factors for translation changes to the relative pose between consecutive scans. - double consecutive_scan_translation_penalty_factor = 2; + // Scaling parameter for translation between consecutive nodes. + double consecutive_node_translation_weight = 2; - // Penalty factors for rotation changes to the relative pose between consecutive scans. - double consecutive_scan_rotation_penalty_factor = 3; + // Scaling parameter for rotation between consecutive nodes. + double consecutive_node_rotation_weight = 3; // Scaling parameter for the FixedFramePose translation. double fixed_frame_pose_translation_weight = 11; diff --git a/cartographer/mapping/proto/pose_graph_options.proto b/cartographer/mapping/proto/pose_graph_options.proto index b1d8c10..31cdfc8 100644 --- a/cartographer/mapping/proto/pose_graph_options.proto +++ b/cartographer/mapping/proto/pose_graph_options.proto @@ -22,7 +22,7 @@ import "cartographer/mapping/pose_graph/proto/optimization_problem_options.proto message PoseGraphOptions { // Online loop closure: If positive, will run the loop closure while the map // is built. - int32 optimize_every_n_scans = 1; + int32 optimize_every_n_nodes = 1; // Options for the constraint builder. mapping.pose_graph.proto.ConstraintBuilderOptions @@ -44,7 +44,7 @@ message PoseGraphOptions { // optimization. int32 max_num_final_iterations = 6; - // Rate at which we sample a single trajectory's scans for global + // Rate at which we sample a single trajectory's nodes for global // localization. double global_sampling_ratio = 5; diff --git a/cartographer/mapping_2d/local_trajectory_builder.cc b/cartographer/mapping_2d/local_trajectory_builder.cc index a54a44a..c42e923 100644 --- a/cartographer/mapping_2d/local_trajectory_builder.cc +++ b/cartographer/mapping_2d/local_trajectory_builder.cc @@ -125,7 +125,7 @@ LocalTrajectoryBuilder::AddRangeData(const common::Time time, } ++num_accumulated_; - if (num_accumulated_ >= options_.scans_per_accumulation()) { + if (num_accumulated_ >= options_.num_accumulated_range_data()) { num_accumulated_ = 0; const transform::Rigid3d gravity_alignment = transform::Rigid3d::Rotation( extrapolator_->EstimateGravityOrientation(time)); diff --git a/cartographer/mapping_2d/local_trajectory_builder_options.cc b/cartographer/mapping_2d/local_trajectory_builder_options.cc index fe05082..d7f999d 100644 --- a/cartographer/mapping_2d/local_trajectory_builder_options.cc +++ b/cartographer/mapping_2d/local_trajectory_builder_options.cc @@ -34,8 +34,8 @@ proto::LocalTrajectoryBuilderOptions CreateLocalTrajectoryBuilderOptions( options.set_max_z(parameter_dictionary->GetDouble("max_z")); options.set_missing_data_ray_length( parameter_dictionary->GetDouble("missing_data_ray_length")); - options.set_scans_per_accumulation( - parameter_dictionary->GetInt("scans_per_accumulation")); + options.set_num_accumulated_range_data( + parameter_dictionary->GetInt("num_accumulated_range_data")); options.set_voxel_filter_size( parameter_dictionary->GetDouble("voxel_filter_size")); options.set_use_online_correlative_scan_matching( diff --git a/cartographer/mapping_2d/pose_graph.cc b/cartographer/mapping_2d/pose_graph.cc index b1ceb29..0750d48 100644 --- a/cartographer/mapping_2d/pose_graph.cc +++ b/cartographer/mapping_2d/pose_graph.cc @@ -269,8 +269,8 @@ void PoseGraph::ComputeConstraintsForNode( } constraint_builder_.NotifyEndOfNode(); ++num_nodes_since_last_loop_closure_; - if (options_.optimize_every_n_scans() > 0 && - num_nodes_since_last_loop_closure_ > options_.optimize_every_n_scans()) { + if (options_.optimize_every_n_nodes() > 0 && + num_nodes_since_last_loop_closure_ > options_.optimize_every_n_nodes()) { CHECK(!run_loop_closure_); run_loop_closure_ = true; // If there is a 'work_queue_' already, some other thread will take care. diff --git a/cartographer/mapping_2d/pose_graph/optimization_problem.cc b/cartographer/mapping_2d/pose_graph/optimization_problem.cc index c9ec296..1be94e6 100644 --- a/cartographer/mapping_2d/pose_graph/optimization_problem.cc +++ b/cartographer/mapping_2d/pose_graph/optimization_problem.cc @@ -189,9 +189,8 @@ void OptimizationProblem::Solve(const std::vector& constraints, problem.AddResidualBlock( new ceres::AutoDiffCostFunction( new SpaCostFunction(Constraint::Pose{ - relative_pose, - options_.consecutive_scan_translation_penalty_factor(), - options_.consecutive_scan_rotation_penalty_factor()})), + relative_pose, options_.consecutive_node_translation_weight(), + options_.consecutive_node_rotation_weight()})), nullptr /* loss function */, C_nodes.at(first_node_id).data(), C_nodes.at(second_node_id).data()); } diff --git a/cartographer/mapping_2d/pose_graph_test.cc b/cartographer/mapping_2d/pose_graph_test.cc index 3c675f1..4ecff80 100644 --- a/cartographer/mapping_2d/pose_graph_test.cc +++ b/cartographer/mapping_2d/pose_graph_test.cc @@ -65,7 +65,7 @@ class PoseGraphTest : public ::testing::Test { { auto parameter_dictionary = common::MakeDictionary(R"text( return { - optimize_every_n_scans = 1000, + optimize_every_n_nodes = 1000, constraint_builder = { sampling_ratio = 1., max_constraint_distance = 6., @@ -116,8 +116,8 @@ class PoseGraphTest : public ::testing::Test { acceleration_weight = 1., rotation_weight = 1e2, huber_scale = 1., - consecutive_scan_translation_penalty_factor = 0., - consecutive_scan_rotation_penalty_factor = 0., + consecutive_node_translation_weight = 0., + consecutive_node_rotation_weight = 0., fixed_frame_pose_translation_weight = 1e1, fixed_frame_pose_rotation_weight = 1e2, log_solver_summary = true, diff --git a/cartographer/mapping_2d/proto/local_trajectory_builder_options.proto b/cartographer/mapping_2d/proto/local_trajectory_builder_options.proto index e5c35df..dbaf0e5 100644 --- a/cartographer/mapping_2d/proto/local_trajectory_builder_options.proto +++ b/cartographer/mapping_2d/proto/local_trajectory_builder_options.proto @@ -32,9 +32,9 @@ message LocalTrajectoryBuilderOptions { // Points beyond 'max_range' will be inserted with this length as empty space. float missing_data_ray_length = 16; - // Number of scans to accumulate into one unwarped, combined scan to use for - // scan matching. - int32 scans_per_accumulation = 19; + // Number of range data to accumulate into one unwarped, combined range data + // to use for scan matching. + int32 num_accumulated_range_data = 19; // Voxel filter that gets applied to the range data immediately after // cropping. diff --git a/cartographer/mapping_2d/proto/submaps_options.proto b/cartographer/mapping_2d/proto/submaps_options.proto index e18e426..787e50e 100644 --- a/cartographer/mapping_2d/proto/submaps_options.proto +++ b/cartographer/mapping_2d/proto/submaps_options.proto @@ -22,9 +22,9 @@ message SubmapsOptions { // Resolution of the map in meters. double resolution = 1; - // Number of scans before adding a new submap. Each submap will get twice the - // number of scans inserted: First for initialization without being matched - // against, then while being matched. + // Number of range data before adding a new submap. Each submap will get twice + // the number of range data inserted: First for initialization without being + // matched against, then while being matched. int32 num_range_data = 3; RangeDataInserterOptions range_data_inserter_options = 5; diff --git a/cartographer/mapping_3d/local_trajectory_builder.cc b/cartographer/mapping_3d/local_trajectory_builder.cc index aae808d..461911e 100644 --- a/cartographer/mapping_3d/local_trajectory_builder.cc +++ b/cartographer/mapping_3d/local_trajectory_builder.cc @@ -98,7 +98,7 @@ LocalTrajectoryBuilder::AddRangeData(const common::Time time, } ++num_accumulated_; - if (num_accumulated_ >= options_.scans_per_accumulation()) { + if (num_accumulated_ >= options_.num_accumulated_range_data()) { num_accumulated_ = 0; const sensor::RangeData filtered_range_data = { accumulated_range_data_.origin, diff --git a/cartographer/mapping_3d/local_trajectory_builder_options.cc b/cartographer/mapping_3d/local_trajectory_builder_options.cc index b4cdeac..2f0e483 100644 --- a/cartographer/mapping_3d/local_trajectory_builder_options.cc +++ b/cartographer/mapping_3d/local_trajectory_builder_options.cc @@ -31,8 +31,8 @@ proto::LocalTrajectoryBuilderOptions CreateLocalTrajectoryBuilderOptions( proto::LocalTrajectoryBuilderOptions options; options.set_min_range(parameter_dictionary->GetDouble("min_range")); options.set_max_range(parameter_dictionary->GetDouble("max_range")); - options.set_scans_per_accumulation( - parameter_dictionary->GetInt("scans_per_accumulation")); + options.set_num_accumulated_range_data( + parameter_dictionary->GetInt("num_accumulated_range_data")); options.set_voxel_filter_size( parameter_dictionary->GetDouble("voxel_filter_size")); *options.mutable_high_resolution_adaptive_voxel_filter_options() = diff --git a/cartographer/mapping_3d/local_trajectory_builder_test.cc b/cartographer/mapping_3d/local_trajectory_builder_test.cc index 04d7aab..ee2c81a 100644 --- a/cartographer/mapping_3d/local_trajectory_builder_test.cc +++ b/cartographer/mapping_3d/local_trajectory_builder_test.cc @@ -49,7 +49,7 @@ class LocalTrajectoryBuilderTest : public ::testing::Test { return { min_range = 0.5, max_range = 50., - scans_per_accumulation = 1, + num_accumulated_range_data = 1, voxel_filter_size = 0.05, high_resolution_adaptive_voxel_filter = { diff --git a/cartographer/mapping_3d/pose_graph.cc b/cartographer/mapping_3d/pose_graph.cc index bb8b380..1a68814 100644 --- a/cartographer/mapping_3d/pose_graph.cc +++ b/cartographer/mapping_3d/pose_graph.cc @@ -286,8 +286,8 @@ void PoseGraph::ComputeConstraintsForNode( } constraint_builder_.NotifyEndOfNode(); ++num_nodes_since_last_loop_closure_; - if (options_.optimize_every_n_scans() > 0 && - num_nodes_since_last_loop_closure_ > options_.optimize_every_n_scans()) { + if (options_.optimize_every_n_nodes() > 0 && + num_nodes_since_last_loop_closure_ > options_.optimize_every_n_nodes()) { CHECK(!run_loop_closure_); run_loop_closure_ = true; // If there is a 'work_queue_' already, some other thread will take care. diff --git a/cartographer/mapping_3d/pose_graph/optimization_problem.cc b/cartographer/mapping_3d/pose_graph/optimization_problem.cc index 7fcf9c6..dd0d714 100644 --- a/cartographer/mapping_3d/pose_graph/optimization_problem.cc +++ b/cartographer/mapping_3d/pose_graph/optimization_problem.cc @@ -354,8 +354,8 @@ void OptimizationProblem::Solve(const std::vector& constraints, new ceres::AutoDiffCostFunction( new SpaCostFunction(Constraint::Pose{ relative_pose, - options_.consecutive_scan_translation_penalty_factor(), - options_.consecutive_scan_rotation_penalty_factor()})), + options_.consecutive_node_translation_weight(), + options_.consecutive_node_rotation_weight()})), nullptr /* loss function */, C_nodes.at(first_node_id).rotation(), C_nodes.at(first_node_id).translation(), C_nodes.at(second_node_id).rotation(), diff --git a/cartographer/mapping_3d/pose_graph/optimization_problem_test.cc b/cartographer/mapping_3d/pose_graph/optimization_problem_test.cc index 3ea3260..eb14648 100644 --- a/cartographer/mapping_3d/pose_graph/optimization_problem_test.cc +++ b/cartographer/mapping_3d/pose_graph/optimization_problem_test.cc @@ -43,8 +43,8 @@ class OptimizationProblemTest : public ::testing::Test { acceleration_weight = 1e-4, rotation_weight = 1e-2, huber_scale = 1., - consecutive_scan_translation_penalty_factor = 1e-2, - consecutive_scan_rotation_penalty_factor = 1e-2, + consecutive_node_translation_weight = 1e-2, + consecutive_node_rotation_weight = 1e-2, fixed_frame_pose_translation_weight = 1e1, fixed_frame_pose_rotation_weight = 1e2, log_solver_summary = true, diff --git a/cartographer/mapping_3d/proto/local_trajectory_builder_options.proto b/cartographer/mapping_3d/proto/local_trajectory_builder_options.proto index 74077b0..9595e4c 100644 --- a/cartographer/mapping_3d/proto/local_trajectory_builder_options.proto +++ b/cartographer/mapping_3d/proto/local_trajectory_builder_options.proto @@ -28,9 +28,9 @@ message LocalTrajectoryBuilderOptions { float min_range = 1; float max_range = 2; - // Number of scans to accumulate into one unwarped, combined scan to use for - // scan matching. - int32 scans_per_accumulation = 3; + // Number of range data to accumulate into one unwarped, combined range data + // to use for scan matching. + int32 num_accumulated_range_data = 3; // Voxel filter that gets applied to the range data immediately after // cropping. diff --git a/cartographer/mapping_3d/proto/motion_filter_options.proto b/cartographer/mapping_3d/proto/motion_filter_options.proto index ff83cf7..bc25b19 100644 --- a/cartographer/mapping_3d/proto/motion_filter_options.proto +++ b/cartographer/mapping_3d/proto/motion_filter_options.proto @@ -17,12 +17,12 @@ syntax = "proto3"; package cartographer.mapping_3d.proto; message MotionFilterOptions { - // Threshold above which a new scan is inserted based on time. + // Threshold above which range data is inserted based on time. double max_time_seconds = 1; - // Threshold above which a new scan is inserted based on linear motion. + // Threshold above which range data is inserted based on linear motion. double max_distance_meters = 2; - // Threshold above which a new scan is inserted based on rotational motion. + // Threshold above which range data is inserted based on rotational motion. double max_angle_radians = 3; } diff --git a/cartographer/mapping_3d/proto/submaps_options.proto b/cartographer/mapping_3d/proto/submaps_options.proto index 293c7c8..fd1cd92 100644 --- a/cartographer/mapping_3d/proto/submaps_options.proto +++ b/cartographer/mapping_3d/proto/submaps_options.proto @@ -31,9 +31,9 @@ message SubmapsOptions { // local SLAM only. double low_resolution = 5; - // Number of scans before adding a new submap. Each submap will get twice the - // number of scans inserted: First for initialization without being matched - // against, then while being matched. + // Number of range data before adding a new submap. Each submap will get twice + // the number of range data inserted: First for initialization without being + // matched against, then while being matched. int32 num_range_data = 2; RangeDataInserterOptions range_data_inserter_options = 3; diff --git a/cartographer/sensor/map_by_time.h b/cartographer/sensor/map_by_time.h index 97e1329..ab7e9a2 100644 --- a/cartographer/sensor/map_by_time.h +++ b/cartographer/sensor/map_by_time.h @@ -194,7 +194,7 @@ class MapByTime { EndOfTrajectory(trajectory_id)); } - // Returns an iterator to the the first element in the container belonging to + // Returns an iterator to the first element in the container belonging to // trajectory 'trajectory_id' whose time is not considered to go before // 'time', or EndOfTrajectory(trajectory_id) if all keys are considered to go // before 'time'. 'trajectory_id' must refer to an existing trajectory. diff --git a/configuration_files/pose_graph.lua b/configuration_files/pose_graph.lua index 527a674..d69d3c8 100644 --- a/configuration_files/pose_graph.lua +++ b/configuration_files/pose_graph.lua @@ -13,7 +13,7 @@ -- limitations under the License. POSE_GRAPH = { - optimize_every_n_scans = 90, + optimize_every_n_nodes = 90, constraint_builder = { sampling_ratio = 0.3, max_constraint_distance = 15., @@ -65,8 +65,8 @@ POSE_GRAPH = { huber_scale = 1e1, acceleration_weight = 1e3, rotation_weight = 3e5, - consecutive_scan_translation_penalty_factor = 1e5, - consecutive_scan_rotation_penalty_factor = 1e5, + consecutive_node_translation_weight = 1e5, + consecutive_node_rotation_weight = 1e5, fixed_frame_pose_translation_weight = 1e1, fixed_frame_pose_rotation_weight = 1e2, log_solver_summary = false, diff --git a/configuration_files/trajectory_builder_2d.lua b/configuration_files/trajectory_builder_2d.lua index d62d0b6..7779719 100644 --- a/configuration_files/trajectory_builder_2d.lua +++ b/configuration_files/trajectory_builder_2d.lua @@ -19,7 +19,7 @@ TRAJECTORY_BUILDER_2D = { min_z = -0.8, max_z = 2., missing_data_ray_length = 5., - scans_per_accumulation = 1, + num_accumulated_range_data = 1, voxel_filter_size = 0.025, adaptive_voxel_filter = { diff --git a/configuration_files/trajectory_builder_3d.lua b/configuration_files/trajectory_builder_3d.lua index fdb8d16..49567f4 100644 --- a/configuration_files/trajectory_builder_3d.lua +++ b/configuration_files/trajectory_builder_3d.lua @@ -17,7 +17,7 @@ MAX_3D_RANGE = 60. TRAJECTORY_BUILDER_3D = { min_range = 1., max_range = MAX_3D_RANGE, - scans_per_accumulation = 1, + num_accumulated_range_data = 1, voxel_filter_size = 0.15, high_resolution_adaptive_voxel_filter = { diff --git a/docs/source/configuration.rst b/docs/source/configuration.rst index 2d2ea8e..725f7cd 100644 --- a/docs/source/configuration.rst +++ b/docs/source/configuration.rst @@ -86,11 +86,11 @@ double acceleration_weight double rotation_weight Scaling parameter for the IMU rotation term. -double consecutive_scan_translation_penalty_factor - Penalty factors for translation changes to the relative pose between consecutive scans. +double consecutive_node_translation_weight + Scaling parameter for translation between consecutive nodes. -double consecutive_scan_rotation_penalty_factor - Penalty factors for rotation changes to the relative pose between consecutive scans. +double consecutive_node_rotation_weight + Scaling parameter for rotation between consecutive nodes. double fixed_frame_pose_translation_weight Scaling parameter for the FixedFramePose translation. @@ -124,7 +124,7 @@ cartographer.mapping.proto.PoseGraphOptions pose_graph_options cartographer.mapping.proto.PoseGraphOptions =========================================== -int32 optimize_every_n_scans +int32 optimize_every_n_nodes Online loop closure: If positive, will run the loop closure while the map is built. @@ -147,7 +147,7 @@ int32 max_num_final_iterations optimization. double global_sampling_ratio - Rate at which we sample a single trajectory's scans for global + Rate at which we sample a single trajectory's nodes for global localization. bool log_residual_histograms @@ -190,9 +190,9 @@ float max_z float missing_data_ray_length Points beyond 'max_range' will be inserted with this length as empty space. -int32 scans_per_accumulation - Number of scans to accumulate into one unwarped, combined scan to use for - scan matching. +int32 num_accumulated_range_data + Number of range data to accumulate into one unwarped, combined range data + to use for scan matching. float voxel_filter_size Voxel filter that gets applied to the range data immediately after @@ -256,9 +256,9 @@ double resolution Resolution of the map in meters. int32 num_range_data - Number of scans before adding a new submap. Each submap will get twice the - number of scans inserted: First for initialization without being matched - against, then while being matched. + Number of range data before adding a new submap. Each submap will get twice + the number of range data inserted: First for initialization without being + matched against, then while being matched. cartographer.mapping_2d.proto.RangeDataInserterOptions range_data_inserter_options Not yet documented. @@ -323,9 +323,9 @@ float min_range float max_range Not yet documented. -int32 scans_per_accumulation - Number of scans to accumulate into one unwarped, combined scan to use for - scan matching. +int32 num_accumulated_range_data + Number of range data to accumulate into one unwarped, combined range data + to use for scan matching. float voxel_filter_size Voxel filter that gets applied to the range data immediately after @@ -369,13 +369,13 @@ cartographer.mapping_3d.proto.MotionFilterOptions ================================================= double max_time_seconds - Threshold above which a new scan is inserted based on time. + Threshold above which range data is inserted based on time. double max_distance_meters - Threshold above which a new scan is inserted based on linear motion. + Threshold above which range data is inserted based on linear motion. double max_angle_radians - Threshold above which a new scan is inserted based on rotational motion. + Threshold above which range data is inserted based on rotational motion. cartographer.mapping_3d.proto.RangeDataInserterOptions @@ -410,9 +410,9 @@ double low_resolution local SLAM only. int32 num_range_data - Number of scans before adding a new submap. Each submap will get twice the - number of scans inserted: First for initialization without being matched - against, then while being matched. + Number of range data before adding a new submap. Each submap will get twice + the number of range data inserted: First for initialization without being + matched against, then while being matched. cartographer.mapping_3d.proto.RangeDataInserterOptions range_data_inserter_options Not yet documented.