lua文件是cartographer中用于参数配置的文件,熟悉lua文件可以让我们对cartographer有一个基础的认知,也可以更好的根据自己的设备进行产品的调试与使用,这里简单介绍一下自己的lua文件应该包含哪些内容。
看一个简单的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.
include "map_builder.lua"
include "trajectory_builder.lua"
options = {
map_builder = MAP_BUILDER, -- map_builder.lua的配置信息
trajectory_builder = TRAJECTORY_BUILDER, -- trajectory_builder.lua的配置信息
map_frame = "map", -- 地图坐标系的名字
tracking_frame = "base_link", -- 将所有传感器数据转换到这个坐标系下默认imu_link,在有IMU的情况下将其他数据转到IMU下,因为IMU频率高,转到其他坐标系下需要转换次数更多
published_frame = "odom", -- tf: map -> odom "footprint"
odom_frame = "odom", -- 里程计的坐标系名字
provide_odom_frame = false, -- 是否提供odom的tf, 如果为true,则tf树为map->odom->footprint
publish_frame_projected_to_2d = false, -- 是否将坐标系投影到平面上
--use_pose_extrapolator = false -- 发布tf时是否使用pose_extrapolator的结果。
use_odometry = true, -- 是否使用里程计,如果使用要求一定要有odom的tf
use_nav_sat = false, -- 是否使用gps
use_landmarks = true, -- 是否使用landmark
num_laser_scans = 1, -- 是否使用单线激光数据
num_multi_echo_laser_scans = 0, -- 是否使用multi_echo_laser_scans数据
-- 这两个还有下面的是否使用点云数据不能同时为0
num_subdivisions_per_laser_scan = 1, -- 1帧数据被分成几次处理,一般为1
num_point_clouds = 0, -- 是否使用点云数据
lookup_transform_timeout_sec = 0.2, -- 查找tf时的超时时间
submap_publish_period_sec = 0.3, -- 发布数据的时间间隔
pose_publish_period_sec = 5e-3, -- 发布pose的时间间隔,比如:5e-3频率是200Hz
trajectory_publish_period_sec = 30e-3, -- 发布轨迹标记的间隔,30e-3是科学记数法,表示的是30乘以10的-3次方。也就是0.030秒,就是30毫秒。
rangefinder_sampling_ratio = 1., -- 传感器数据的采样频率,多少次数据采样一次,默认都是1。
odometry_sampling_ratio = 1.,
fixed_frame_pose_sampling_ratio = 1.,
imu_sampling_ratio = 1.,
landmarks_sampling_ratio = 1.,
}
MAP_BUILDER.use_trajectory_builder_2d = true
TRAJECTORY_BUILDER_2D.submaps.num_range_data = 35 -- 其含义应该应该是多少帧插入一次子图,算法中还有一个乘二操作。
--num_range_data设置的值与CPU有这样一种关系,值小(10),CPU使用率比较稳定,整体偏高,值大时,CPU短暂爆发使用(插入子图的时候),平时使用率低,呈现极大的波动状态。
TRAJECTORY_BUILDER_2D.min_range = 0.3 --激光的最近有效距离
TRAJECTORY_BUILDER_2D.max_range = 8. --激光最远的有效距离
TRAJECTORY_BUILDER_2D.missing_data_ray_length = 1. --无效激光数据设置距离为该数值,滤波的时候使用
TRAJECTORY_BUILDER_2D.use_imu_data = false --是否使用imu数据
TRAJECTORY_BUILDER_2D.use_online_correlative_scan_matching = true -- 选择是否先求解online scan matching,然后用correlative scan matcher为Ceres求解器产生一个好的初始解,为true时效果更好
TRAJECTORY_BUILDER_2D.real_time_correlative_scan_matcher.linear_search_window = 0.1 -- 线距离搜索框,在这个框的大小内,搜索最佳scan匹配.
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
--POSE_GRAPH.optimization_problem.huber_scale = 1e2 --鲁棒核函数,去噪
--POSE_GRAPH.optimize_every_n_nodes = 35 --后端优化节点
--POSE_GRAPH.constraint_builder.min_score = 0.65 --当匹配分数低于此值时,忽略该分数。感觉可能是用来检测是否匹配到回环的
return options
对于上述一个lua文件,主要分为以下几个部分:
这里引用了两个头文件:
include "map_builder.lua"
include "trajectory_builder.lua"
它们是放在cartographer_detailed_comments_ws/src/cartographer/configuration_files路径下,这里虽然只include了两个,但是其中也引用了该目录下其他几个lua文件。这几个lua文件基本包含了cartographer的大部分参数。先看一下trajectory_builder.lua:
include "trajectory_builder_2d.lua"
include "trajectory_builder_3d.lua"
TRAJECTORY_BUILDER = {
trajectory_builder_2d = TRAJECTORY_BUILDER_2D,
trajectory_builder_3d = TRAJECTORY_BUILDER_3D,
-- pure_localization_trimmer = {
-- max_submaps_to_keep = 3,
-- },
collate_fixed_frame = true, -- 是否将数据放入阻塞队列中
collate_landmarks = false, -- 是否将数据放入阻塞队列中
}
这个文件比较短,它包含了一个2d轨迹的lua以及一个3d轨迹的lua。
然后再看一下2d的参数文件:
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, -- 几帧有效的点云数据进行一次扫描匹配
voxel_filter_size = 0.025, -- 体素滤波的立方体的边长
-- 使用固定的voxel滤波之后, 再使用自适应体素滤波器
-- 体素滤波器 用于生成稀疏点云 以进行 扫描匹配
adaptive_voxel_filter = {
max_length = 0.5, -- 尝试确定最佳的立方体边长, 边长最大为0.5
min_num_points = 200, -- 如果存在 较多点 并且大于'min_num_points', 则减小体素长度以尝试获得该最小点数
max_range = 50., -- 距远离原点超过max_range 的点被移除
},
-- 闭环检测的自适应体素滤波器, 用于生成稀疏点云 以进行 闭环检测
loop_closure_adaptive_voxel_filter = {
max_length = 0.9,
min_num_points = 100,
max_range = 50.,
},
-- 是否使用 real_time_correlative_scan_matcher 为ceres提供先验信息
-- 计算复杂度高 , 但是很鲁棒 , 在odom或者imu不准时依然能达到很好的效果
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, -- 用于计算各部分score的权重
rotation_delta_cost_weight = 1e-1,
},
-- ceres匹配的一些配置参数
ceres_scan_matcher = {
occupied_space_weight = 1.,
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", -- 地图的种类, 还可以是tsdf格式
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地图的一些配置
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,
},
},
},
}
这个文件还是比较长的,简单看一下。
前面第一个参数:
use_imu_data = true, -- 是否使用imu数据
是否使用IMU,如果设置为true则需要有IMU,如果没有IMU,可以在前面的lua文件第三部分内容其他参数中添加一行:
TRAJECTORY_BUILDER_2D.use_imu_data = false --是否使用imu数据
相当于对该参数进行了一次重映射。
min_range = 0., -- 雷达数据的最远最近滤波, 保存中间值
max_range = 30.,
表示使用的雷达的最远最近距离。
min_z = -0.8, -- 雷达数据的最高与最低的过滤, 保存中间值
max_z = 2.,
雷达点云的最高与最低高度的滤波参数,超过这个范围的点会被过滤掉。
missing_data_ray_length = 5., -- 超过最大距离范围的数据点用这个距离代替
雷达数据中有一些超过测量范围的点,显示为NAN或者inf之类的,或者是超过上述设置的最远距离的值,这些东西就会用missing_data_ray_length的值代替。
num_accumulated_range_data = 1, -- 几帧有效的点云数据进行一次扫描匹配
几帧有效数据做一次扫描匹配,一般设置为1.
voxel_filter_size = 0.025, -- 体素滤波的立方体的边长
cartographer会对点云进行体素滤波,这里设置了体素滤波的边长。
-- 使用固定的voxel滤波之后, 再使用自适应体素滤波器
-- 体素滤波器 用于生成稀疏点云 以进行 扫描匹配
adaptive_voxel_filter = {
max_length = 0.5, -- 尝试确定最佳的立方体边长, 边长最大为0.5
min_num_points = 200, -- 如果存在 较多点 并且大于'min_num_points', 则减小体素长度以尝试获得该最小点数
max_range = 50., -- 距远离原点超过max_range 的点被移除
},
自适应体素滤波器的设置,cartographer会对点云进行多次的处理,设置这个后cartographer会将滤波后的点云数量限制在min_num_points范围内。
-- 闭环检测的自适应体素滤波器, 用于生成稀疏点云 以进行 闭环检测
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, -- 用于计算各部分score的权重
rotation_delta_cost_weight = 1e-1,
},
这个参数的含义是是否在扫描匹配前面先进行一次位姿计算,如果设置为true会很大的提高计算量,如果使用单线雷达数据建图时建图效果不好,总是叠图的话可以打开这个参数,可以优化建图效果。但是会付出一定的计算量。
-- ceres匹配的一些配置参数
ceres_scan_matcher = {
occupied_space_weight = 1.,
translation_weight = 10.,
rotation_weight = 40.,
ceres_solver_options = {
use_nonmonotonic_steps = false,
max_num_iterations = 20,
num_threads = 1,
},
},
前端扫描匹配的一些参数设置,第一个代表点云与地图匹配的权重,第二个代表匹配的位姿与先验位姿的平移权重,第三个代表匹配的位姿与先验位姿的旋转权重。ceres_solver_options内部是ceres内部的一些参数。
-- 为了防止子图里插入太多数据, 在插入子图之前之前对数据进行过滤
motion_filter = {
max_time_seconds = 5.,
max_distance_meters = 0.2,
max_angle_radians = math.rad(1.),
},
像gmapping粒子滤波这种一般需要机器人运动超过一定距离才会进行一次计算与地图的插入,但是cartographer不一样,它会对每一帧数据进行计算。为了减少子图插入太多点云数据,可以通过这里的motion_filter进行过滤。
-- 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;
},
},
},
use_imu_based参数决定了是否使用imu_based内部参数。
-- 子图相关的一些配置
submaps = {
num_range_data = 90, -- 一个子图里插入雷达数据的个数的一半
grid_options_2d = {
grid_type = "PROBABILITY_GRID", -- 地图的种类, 还可以是tsdf格式
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地图的一些配置
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,
},
},
},
}
这块是子图相关的参数设置,num_range_data代表一个子图会插入多少个点云数据的一半,为什么是一半,因为代码里这个参数会乘以2。grid_type为地图的格式,默认是概率栅格地图。resolution为地图的分辨率,如果要修改地图的分辨率就是修改的这里。
2d的参数大概就是这些,3d的类似,少数区别:
首先关于体素滤波这块,3d有两个体素滤波:
-- 在3d slam 时会有2个自适应体素滤波, 一个生成高分辨率点云, 一个生成低分辨率点云
high_resolution_adaptive_voxel_filter = {
max_length = 2.,
min_num_points = 150,
max_range = 15.,
},
low_resolution_adaptive_voxel_filter = {
max_length = 4.,
min_num_points = 200,
max_range = MAX_3D_RANGE,
},
其次,3d的submap也有两种:
submaps = {
-- 2种分辨率的地图
high_resolution = 0.10, -- 用于近距离测量的高分辨率hybrid网格 for local SLAM and loop closure, 用来与小尺寸voxel进行精匹配
high_resolution_max_range = 20., -- 在插入 high_resolution map 之前过滤点云的最大范围
low_resolution = 0.45,
num_range_data = 160, -- 用于远距离测量的低分辨率hybrid网格 for local SLAM only, 用来与大尺寸voxel进行粗匹配
range_data_inserter = {
hit_probability = 0.55,
miss_probability = 0.49,
num_free_space_voxels = 2,
intensity_threshold = INTENSITY_THRESHOLD,
},
},
再看一下map_builder.lua:
include "pose_graph.lua"
MAP_BUILDER = {
use_trajectory_builder_2d = false,
use_trajectory_builder_3d = false,
num_background_threads = 4,
pose_graph = POSE_GRAPH,
collate_by_trajectory = false,
}
这个文件也很短,注意
use_trajectory_builder_2d = false,
use_trajectory_builder_3d = false,
这两个参数有且仅有一个为true。默认两个都是false,所以在第三节配置参数中要将其中一个映射为true。num_background_threads为线程数量。pose_graph代表加载pose_graph.lua相关参数配置。
pose_graph用于设置后端优化参数:
POSE_GRAPH = {
-- 每隔多少个节点执行一次后端优化
optimize_every_n_nodes = 90,
-- 约束构建的相关参数
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, -- 打印约束计算的log
-- 基于分支定界算法的2d粗匹配器
fast_correlative_scan_matcher = {
linear_search_window = 7.,
angular_search_window = math.rad(30.),
branch_and_bound_depth = 7,
},
-- 基于ceres的2d精匹配器
ceres_scan_matcher = {
occupied_space_weight = 20.,
translation_weight = 10.,
rotation_weight = 1.,
ceres_solver_options = {
use_nonmonotonic_steps = true,
max_num_iterations = 10,
num_threads = 1,
},
},
-- 基于分支定界算法的3d粗匹配器
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的3d精匹配器
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 = 1.1e2, -- 3d里imu的线加速度的权重
rotation_weight = 1.6e4, -- 3d里imu的旋转的权重
-- 前端结果残差的权重
local_slam_pose_translation_weight = 1e5,
local_slam_pose_rotation_weight = 1e5,
-- 里程计残差的权重
odometry_translation_weight = 1e5,
odometry_rotation_weight = 1e5,
-- gps残差的权重
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., -- 纯定位时多少秒执行一次全子图的约束计算
-- overlapping_submaps_trimmer_2d = {
-- fresh_submaps_count = 1,
-- min_covered_area = 2,
-- min_added_submaps_count = 5,
-- },
}
首先:
-- 每隔多少个节点执行一次后端优化
optimize_every_n_nodes = 90,
代表了多少个节点进行一次优化,一般设置为num_range_data的两倍左右。
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,
回环检测时平移和旋转的权重。
-- 基于分支定界算法的2d粗匹配器
fast_correlative_scan_matcher = {
linear_search_window = 7.,
angular_search_window = math.rad(30.),
branch_and_bound_depth = 7,
},
分支定界算法的粗匹配器的参数。
-- 基于ceres的3d精匹配器
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,
},
},
ceres精匹配器的参数。
以及再往下是3d的两个匹配器参数:
-- 基于分支定界算法的3d粗匹配器
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的3d精匹配器
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,
},
},
然后是一些残差相关的值
-- 优化残差方程的相关参数
optimization_problem = {
huber_scale = 1e1, -- 值越大,(潜在)异常值的影响就越大
acceleration_weight = 1.1e2, -- 3d里imu的线加速度的权重
rotation_weight = 1.6e4, -- 3d里imu的旋转的权重
-- 前端结果残差的权重
local_slam_pose_translation_weight = 1e5,
local_slam_pose_rotation_weight = 1e5,
-- 里程计残差的权重
odometry_translation_weight = 1e5,
odometry_rotation_weight = 1e5,
-- gps残差的权重
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, -- 在建图结束之后执行一次全局优化, 不要求实时性, 迭代次数多
cartographer在结束的时候会进行一次全局优化,这里是全局优化的迭代次数。
global_sampling_ratio = 0.003, -- 纯定位时候查找回环的频率
纯定位模式下的查找回环的频率。
global_constraint_search_after_n_seconds = 10., -- 纯定位时多少秒执行一次全子图的约束计算
多少秒执行一次子图的约束
options中的参数是指上面lua文件中没有的参数,需要根据自己的设置。展开看一下这部分:
首先是前两行:
map_builder = MAP_BUILDER, -- map_builder.lua的配置信息
trajectory_builder = TRAJECTORY_BUILDER, -- trajectory_builder.lua的配置信息
定义包含前两个头文件的配置信息,照着写不用管。
map_frame = "map", -- 地图坐标系的名字
用于设置地图坐标系的名字,一般都用map。
tracking_frame = "base_link", -- 将所有传感器数据转换到这个坐标系下默认imu_link,在有IMU的情况下将其他数据转到IMU下,因为IMU频率高,转到其他坐标系下需要转换次数更多
cartographer在做数据处理的时候,会将所有的传感器数据都转换到该坐标系下进行处理。每个传感器的频率不一样,IMU一般频率最高,如果有IMU,则将IMU转换到其他坐标系下需要更多的转换计算量。没有IMU设置为base_link也可以。
published_frame = "odom", -- tf: map -> odom "footprint"
用于发布到map的TF变换的坐标系,有odom的话最好写odom,没有的话看自己的TF变换,取自己的TF树最上层的一个坐标系即可。
odom_frame = "odom", -- 里程计的坐标系名字
里程计坐标系的名称,一般用的是odom。
provide_odom_frame = false, -- 是否提供odom的tf, 如果为true,则tf树为map->odom->footprint
是否提供一个虚拟的odom,在没有odom的情况下,如果这里设置为true,则cartographer会在运算过程中发布一个map->odom->“published_frame“的TF变换。如果设置为false,则算法会直接发布一个map->“published_frame“的TF变换。
publish_frame_projected_to_2d = false, -- 是否将坐标系投影到平面上
是否将坐标系投影到平面上,没什么太大意义,设置为false即可。
--use_pose_extrapolator = false -- 发布tf时是否使用pose_extrapolator的结果。
这个参数的含义是发布TF时使用位姿推测器推测出来的位姿还是使用算法计算出来的位姿,那一般肯定是算法计算出来的更为准确。推测出来的会有误差。
use_odometry = true, -- 是否使用里程计,如果使用要求一定要有odom的tf
use_nav_sat = false, -- 是否使用gps
use_landmarks = true, -- 是否使用landmark
是否存在这三种传感器数据,三者都是通过topic形式进行订阅,如果设置为true则会订阅对应的topic。注意这三者的topic是唯一的,它们分别只能订阅一个对应的topic数据。但是这三者可以同时订阅是没关系的。但是雷达是可以订阅多个的。
num_laser_scans = 1, -- 是否使用单线激光数据
num_multi_echo_laser_scans = 0, -- 是否使用multi_echo_laser_scans数据
-- 这两个还有下面的是否使用点云数据不能同时为0
num_point_clouds = 0,
表示使用单线雷达还是多线雷达,或者也可以是点云数据。cartographer支持多雷达建图,但是据说效果不是很好,所以一般使用一个单线雷达或者一个多线雷达就可以了。
num_subdivisions_per_laser_scan = 1, -- 1帧数据被分成几次处理,一般为1
一帧数据分为几次处理,一般设置为1即可。
lookup_transform_timeout_sec = 0.2, -- 查找tf时的超时时间
查找tf时的超时时间。
submap_publish_period_sec = 0.3, -- 发布数据的时间间隔
发布submap的频率,0.3s更新一次submap的发布。
pose_publish_period_sec = 5e-3, -- 发布pose的时间间隔,比如:5e-3频率是200Hz
姿态的发布频率,一般还是比较高的。
trajectory_publish_period_sec = 30e-3, -- 发布轨迹标记的间隔,30e-3是科学记数法,表示的是30乘以10的-3次方。也就是0.030秒,就是30毫秒。
运动轨迹的发布频率,同样很高。
rangefinder_sampling_ratio = 1., -- 传感器数据的采样频率,多少次数据采样一次,默认都是1。
odometry_sampling_ratio = 1.,
fixed_frame_pose_sampling_ratio = 1.,
imu_sampling_ratio = 1.,
landmarks_sampling_ratio = 1.,
几种传感器数据的处理频率,cartographer在处理传感器数据时并不是每一帧数据都会处理,而是设置了一个采样器,当采样器设置为1时才是每一帧数据都会进行处理,如果设置为小于1(例如0.5)则会每两帧数据才处理一次。这样子首先可以降低数据量,其次如果传感器数据不准的情况下可以降低它的使用频率。
options后面的一些参数是指在头文件中已经存在的参数,这些参数已经有默认值,如果不想使用默认值可以写在这里重定义它的值。