二cartographer-2d前后端参数解释
Posted Hill_LAI
tags:
篇首语:本文由小常识网(cha138.com)小编为大家整理,主要介绍了二cartographer-2d前后端参数解释相关的知识,希望对你有一定的参考价值。
解释:
1-前端参数用来构建一个一个小子图(submap)
2-后端参数用来把一个一个小子图拼接成一个大地图(map),如何调整一个一个子图的相对位置关系,这里使用了位姿图的方式,建立激光与子图之间的约束来构建优化方程,解方程来实现最优化结果。
前端参数文件
trajectory_builder_2d.lua
-- Copyright 2016 The Cartographer Authors
--
-- Licensed under the Apache License, Version 2.0 (the "License");
-- you may not use this file except in compliance with the License.
-- You may obtain a copy of the License at
--
-- http://www.apache.org/licenses/LICENSE-2.0
--
-- Unless required by applicable law or agreed to in writing, software
-- distributed under the License is distributed on an "AS IS" BASIS,
-- WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
-- See the License for the specific language governing permissions and
-- limitations under the License.
TRAJECTORY_BUILDER_2D = {
use_imu_data = true, //是否使用imu数据
min_range = 0., //激光的最近有效距离
max_range = 30., //激光最远的有效距离
min_z = -0.8, //激光高度最低有效高度
max_z = 2., //激光最高有效高度
missing_data_ray_length = 5., //无效激光数据设置距离为该数值
num_accumulated_range_data = 1, //积累几帧激光数据作为一个标准单位scan
voxel_filter_size = 0.025, //网格滤波大小,单位为米
adaptive_voxel_filter = { //自适应滤波
max_length = 0.5, //最大网格大小
min_num_points = 200, //最小点数量
max_range = 50., //最远有效距离
},
loop_closure_adaptive_voxel_filter = {
max_length = 0.9,
min_num_points = 100,
max_range = 50.,
},
use_online_correlative_scan_matching = false,
real_time_correlative_scan_matcher = {
linear_search_window = 0.1,
angular_search_window = math.rad(20.),
translation_delta_cost_weight = 1e-1,
rotation_delta_cost_weight = 1e-1,
},
use_intensity_ceres_scan_matching = false,
//occupied_space_weight是激光珊格匹配的权重,越大则越希望珊格匹配的越多,
//translation_weight和rotation_weight参数是为了防止只有珊格匹配造成误匹配,所以增加了这2个参数
//目的是为了只在初始位置附近进行匹配,距离初始位置过远则会受到惩罚,权重越大惩罚越大,匹配的得分会更低
//换句话说,在距离初始距离更远的距离,获得的匹配被认可,需要更准确的珊格匹配。
ceres_scan_matcher = {
occupied_space_weight = 1.,
intensity_space_weight = 1., --okagv
translation_weight = 10.,
rotation_weight = 40.,
ceres_solver_options = {
use_nonmonotonic_steps = false,
max_num_iterations = 20,
num_threads = 1,
},
},
motion_filter = {
max_time_seconds = 5.,
max_distance_meters = 0.2,
max_angle_radians = math.rad(1.),
},
-- TODO(schwoere,wohe): Remove this constant. This is only kept for ROS.
imu_gravity_time_constant = 10.,
pose_extrapolator = {
use_imu_based = false,
constant_velocity = {
imu_gravity_time_constant = 10.,
pose_queue_duration = 0.001,
},
imu_based = {
pose_queue_duration = 5.,
gravity_constant = 9.806,
pose_translation_weight = 1.,
pose_rotation_weight = 1.,
imu_acceleration_weight = 1.,
imu_rotation_weight = 1.,
odometry_translation_weight = 1.,
odometry_rotation_weight = 1.,
solver_options = {
use_nonmonotonic_steps = false;
max_num_iterations = 10;
num_threads = 1;
},
},
},
submaps = {
num_range_data = 90,
grid_options_2d = {
grid_type = "PROBABILITY_GRID",
resolution = 0.05,
},
range_data_inserter = {
range_data_inserter_type = "PROBABILITY_GRID_INSERTER_2D",
probability_grid_range_data_inserter = {
insert_free_space = true,
hit_probability = 0.55,
miss_probability = 0.49,
},
tsdf_range_data_inserter = {
truncation_distance = 0.3,
maximum_weight = 10.,
update_free_space = false,
normal_estimation_options = {
num_normal_samples = 4,
sample_radius = 0.5,
},
project_sdf_distance_to_scan_normal = true,
update_weight_range_exponent = 0,
update_weight_angle_scan_normal_to_ray_kernel_bandwidth = 0.5,
update_weight_distance_cell_to_hit_kernel_bandwidth = 0.5,
},
},
},
}
后端参数文件
pose_graph.lua
-- Copyright 2016 The Cartographer Authors
--
-- Licensed under the Apache License, Version 2.0 (the "License");
-- you may not use this file except in compliance with the License.
-- You may obtain a copy of the License at
--
-- http://www.apache.org/licenses/LICENSE-2.0
--
-- Unless required by applicable law or agreed to in writing, software
-- distributed under the License is distributed on an "AS IS" BASIS,
-- WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
-- See the License for the specific language governing permissions and
-- limitations under the License.
POSE_GRAPH = {
optimize_every_n_nodes = 90,
optimize_every_meter = 0.5, --okagv
constraint_builder = {
sampling_ratio = 0.3,
max_constraint_distance = 15.,
min_score = 0.55,
global_localization_min_score = 0.6,
loop_closure_translation_weight = 1.1e4,
loop_closure_rotation_weight = 1e5,
log_matches = true,
max_match_variety_distance = 2.,
fast_correlative_scan_matcher = {
linear_search_window = 7.,
angular_search_window = math.rad(30.),
branch_and_bound_depth = 7,
},
ceres_scan_matcher = {
occupied_space_weight = 20.,
intensity_space_weight = 1.,
translation_weight = 10.,
rotation_weight = 1.,
ceres_solver_options = {
use_nonmonotonic_steps = true,
max_num_iterations = 10,
num_threads = 1,
},
},
fast_correlative_scan_matcher_3d = {
branch_and_bound_depth = 8,
full_resolution_depth = 3,
min_rotational_score = 0.77,
min_low_resolution_score = 0.55,
linear_xy_search_window = 5.,
linear_z_search_window = 1.,
angular_search_window = math.rad(15.),
},
ceres_scan_matcher_3d = {
occupied_space_weight_0 = 5.,
occupied_space_weight_1 = 30.,
translation_weight = 10.,
rotation_weight = 1.,
only_optimize_yaw = false,
ceres_solver_options = {
use_nonmonotonic_steps = false,
max_num_iterations = 10,
num_threads = 1,
},
},
},
matcher_translation_weight = 5e2,
matcher_rotation_weight = 1.6e3,
optimization_problem = {
huber_scale = 1e1,
acceleration_weight = 1e3,
rotation_weight = 3e5,
local_slam_pose_translation_weight = 1e5,
local_slam_pose_rotation_weight = 1e5,
odometry_translation_weight = 1e5,
odometry_rotation_weight = 1e5,
fixed_frame_pose_translation_weight = 1e1,
fixed_frame_pose_rotation_weight = 1e2,
fixed_frame_pose_use_tolerant_loss = false,
fixed_frame_pose_tolerant_loss_param_a = 1,
fixed_frame_pose_tolerant_loss_param_b = 1,
log_solver_summary = false,
use_online_imu_extrinsics_in_3d = true,
fix_z_in_3d = false,
ceres_solver_options = {
use_nonmonotonic_steps = false,
max_num_iterations = 50,
num_threads = 7,
},
},
max_num_final_iterations = 200,
global_sampling_ratio = 0.003,
log_residual_histograms = true,
global_constraint_search_after_n_seconds = 10.,
local_constraint_search_after_n_seconds = 2.,
overlapping_submaps_trimmer_2d = {
fresh_submaps_count = 1,
min_covered_area = 2,
min_added_submaps_count = 5,
loop_check_seconds = 5,
},
}
以上是关于二cartographer-2d前后端参数解释的主要内容,如果未能解决你的问题,请参考以下文章