Detailed explanation of lua parameters for cartographer learning

The lua file is the file used for parameter configuration in cartographer. Familiarity with the lua file can give us a basic understanding of cartographer, and we can better debug and use the product according to our own equipment. Here is a brief introduction of what should be included in our lua file.
Look at a simple lua file:

-- 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

For the above lua file, it is mainly divided into the following parts:

1. Header file

Two header files are referenced here:

include "map_builder.lua"
include "trajectory_builder.lua"

They are placed under the path of cartographer_detailed_comments_ws/src/cartographer/configuration_files. Although only two are included here, several other lua files in this directory are also referenced. These lua files basically contain most of the parameters of cartographer. Take a look at trajectory_builder.lua first:

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,  -- 是否将数据放入阻塞队列中
}

This file is relatively short, it contains a 2d track lua and a 3d track lua.
Then look at the 2d parameter file:

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,
      },
    },
  },
}

This file is still relatively long, just take a look.

The first parameter in front:

use_imu_data = true,            -- 是否使用imu数据

Whether to use IMU, if it is set to true, IMU is required, if there is no IMU, you can add a line in the other parameters of the third part of the previous lua file:

TRAJECTORY_BUILDER_2D.use_imu_data = false              --是否使用imu数据

It is equivalent to remapping the parameter once.

  min_range = 0.,                 -- 雷达数据的最远最近滤波, 保存中间值
  max_range = 30.,

Indicates the maximum and minimum distances of the radar used.

  min_z = -0.8,                   -- 雷达数据的最高与最低的过滤, 保存中间值
  max_z = 2.,

The filtering parameters of the highest and lowest heights of the radar point cloud. Points beyond this range will be filtered out.

missing_data_ray_length = 5.,   -- 超过最大距离范围的数据点用这个距离代替

There are some points in the radar data that exceed the measurement range, which are displayed as NAN or inf, or exceed the farthest value set above, and these things will be replaced by the value of missing_data_ray_length.

num_accumulated_range_data = 1, -- 几帧有效的点云数据进行一次扫描匹配

Several frames of valid data do a scan match, generally set to 1.

voxel_filter_size = 0.025,      -- 体素滤波的立方体的边长

The cartographer will perform voxel filtering on the point cloud, and the side length of the voxel filtering is set here.

-- 使用固定的voxel滤波之后, 再使用自适应体素滤波器
  -- 体素滤波器 用于生成稀疏点云 以进行 扫描匹配
  adaptive_voxel_filter = {
    
    
    max_length = 0.5,             -- 尝试确定最佳的立方体边长, 边长最大为0.5
    min_num_points = 200,         -- 如果存在 较多点 并且大于'min_num_points', 则减小体素长度以尝试获得该最小点数
    max_range = 50.,              -- 距远离原点超过max_range 的点被移除
  },

For the setting of the adaptive voxel filter, cartographer will process the point cloud multiple times. After setting this, cartographer will limit the number of filtered point clouds to the range of min_num_points.

  -- 闭环检测的自适应体素滤波器, 用于生成稀疏点云 以进行 闭环检测
  loop_closure_adaptive_voxel_filter = {
    
    
    max_length = 0.9,
    min_num_points = 100,
    max_range = 50.,
  },

Voxel filter parameters when doing closed-loop detection.

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,
  },

The meaning of this parameter is whether to perform a pose calculation before the scan matching. If it is set to true, the amount of calculation will be greatly increased. If the map construction effect is not good when using single-line radar data, and the map is always stacked, you can turn on this parameter to optimize the map construction effect. But it will pay a certain amount of calculation.

-- 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,
    },
  },

Some parameter settings of the front-end scan matching, the first represents the weight of point cloud and map matching, the second represents the translation weight of the matched pose and the prior pose, and the third represents the rotation weight of the matched pose and the prior pose. Inside ceres_solver_options are some parameters inside ceres.

  -- 为了防止子图里插入太多数据, 在插入子图之前之前对数据进行过滤
  motion_filter = {
    
    
    max_time_seconds = 5.,
    max_distance_meters = 0.2,
    max_angle_radians = math.rad(1.),
  },

Like the gmapping particle filter, it generally requires the robot to move beyond a certain distance before performing a calculation and inserting the map, but cartographer is different, it will calculate each frame of data. In order to reduce the insertion of too much point cloud data in the submap, it can be filtered by the motion_filter here.

-- TODO(schwoere,wohe): Remove this constant. This is only kept for ROS.
  imu_gravity_time_constant = 10.,

This can be ignored, it seems to be useless.

-- 位姿预测器
  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;
      },
    },
  },

The use_imu_based parameter determines whether to use the imu_based internal parameter.

-- 子图相关的一些配置
  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,
      },
    },
  },
}

This is the submap-related parameter setting. num_range_data represents half of how many point cloud data a submap will insert. Why is it half, because this parameter in the code will be multiplied by 2. grid_type is the format of the map, and the default is a probability grid map. resolution is the resolution of the map, if you want to modify the resolution of the map, you can modify it here.

The parameters of 2d are probably these, 3d is similar, with a few differences:
first of all, about voxel filtering, 3d has two voxel filters:

  --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,
  },

Secondly, there are two types of 3d submaps:

  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,
    },
  },

Look at map_builder.lua again:

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,
}

This file is also very short, note

  use_trajectory_builder_2d = false,
  use_trajectory_builder_3d = false,

These two parameters have and only one is true. Both are false by default, so one of them must be mapped to true in the configuration parameters in the third section. num_background_threads is the number of threads. pose_graph represents loading pose_graph.lua related parameter configuration.

pose_graph is used to set the backend optimization parameters:

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,
  --  },
}

first:

-- 每隔多少个节点执行一次后端优化
  optimize_every_n_nodes = 90,

It represents how many nodes are optimized once, and is generally set to about twice the value of num_range_data.

Constraint_builder contains some parameters related to backend optimization

sampling_ratio = 0.3,                 -- 对局部子图进行回环检测时的计算频率, 数值越大, 计算次数越多

The calculation frequency when performing loop closure detection on local subgraphs.

max_constraint_distance = 15.,        -- 对局部子图进行回环检测时能成为约束的最大距离

The maximum distance of constraints during loop closure.

min_score = 0.55,                     -- 对局部子图进行回环检测时的最低分数阈值

Only loopback detections above this value are successful loopbacks.

global_localization_min_score = 0.6,  -- 对整体子图进行回环检测时的最低分数阈值

The minimum score threshold for the loop detection of the overall subgraph, the upper parameter is a local loop, and the lower one is a large loop.

    loop_closure_translation_weight = 1.1e4,
    loop_closure_rotation_weight = 1e5,

Weights for translation and rotation during loop closure.

    -- 基于分支定界算法的2d粗匹配器
    fast_correlative_scan_matcher = {
    
    
      linear_search_window = 7.,
      angular_search_window = math.rad(30.),
      branch_and_bound_depth = 7,
    },

Parameters for the coarse matcher of the branch and bound algorithm.

-- 基于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,
      },
    },

Arguments for the ceres fine matcher.

And further down are the two matcher parameters of 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,
      },
    },

and then some residual related values

-- 优化残差方程的相关参数
  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 will perform a global optimization at the end, here is the number of iterations of global optimization.

global_sampling_ratio = 0.003,    -- 纯定位时候查找回环的频率

Frequency of finding loopbacks in pure positioning mode.

global_constraint_search_after_n_seconds = 10., -- 纯定位时多少秒执行一次全子图的约束计算

How many seconds to execute the constraints of the subgraph

2.options parameter

The parameters in options refer to the parameters that are not in the lua file above, and need to be set according to your own. Expand and take a look at this part:
First, the first two lines:

  map_builder = MAP_BUILDER,                            -- map_builder.lua的配置信息
  trajectory_builder = TRAJECTORY_BUILDER,              -- trajectory_builder.lua的配置信息

The definition contains the configuration information of the first two header files, and it is ignored as written.

map_frame = "map",                                    -- 地图坐标系的名字

The name used to set the map coordinate system, generally use map.

tracking_frame = "base_link",                         -- 将所有传感器数据转换到这个坐标系下默认imu_link,在有IMU的情况下将其他数据转到IMU下,因为IMU频率高,转到其他坐标系下需要转换次数更多

When cartographer is doing data processing, it will convert all sensor data to this coordinate system for processing. The frequency of each sensor is different, and the IMU generally has the highest frequency. If there is an IMU, converting the IMU to other coordinate systems requires more conversion calculations. It is also possible to set base_link without IMU.

published_frame = "odom",                        -- tf: map -> odom  "footprint"

The coordinate system used for the TF transformation published to the map. If there is odom, it is best to write odom. If not, look at your own TF transformation and take the coordinate system at the top of your own TF tree.

odom_frame = "odom",                                  -- 里程计的坐标系名字

The name of the odometer coordinate system is usually odom.

provide_odom_frame = false,                            -- 是否提供odom的tf, 如果为true,则tf树为map->odom->footprint

Whether to provide a virtual odom. If there is no odom, if this is set to true, the cartographer will publish a TF transformation of map->odom->"published_frame" during the operation. If set to false, the algorithm will directly publish a TF transformation of map->"published_frame".

publish_frame_projected_to_2d = false,                -- 是否将坐标系投影到平面上

It doesn't make much sense whether to project the coordinate system onto the plane, just set it to false.

--use_pose_extrapolator = false                       -- 发布tf时是否使用pose_extrapolator的结果。

The meaning of this parameter is whether the pose inferred by the pose estimator or the pose calculated by the algorithm when publishing TF is generally more accurate than the one calculated by the algorithm. It is assumed that there will be errors.

  use_odometry = true,                                  -- 是否使用里程计,如果使用要求一定要有odom的tf
  use_nav_sat = false,                                  -- 是否使用gps
  use_landmarks = true,                                -- 是否使用landmark

Whether there are these three kinds of sensor data, all three are subscribed in the form of topic, if set to true, the corresponding topic will be subscribed. Note that the topics of these three are unique, and they can only subscribe to one corresponding topic data. But it doesn't matter that all three can subscribe at the same time. But the radar can subscribe to multiple.

  num_laser_scans = 1,                                  -- 是否使用单线激光数据
  num_multi_echo_laser_scans = 0,                       -- 是否使用multi_echo_laser_scans数据
                                                        -- 这两个还有下面的是否使用点云数据不能同时为0
  num_point_clouds = 0,  

Indicates whether to use single-line radar or multi-line radar, or point cloud data. Cartographer supports multi-radar mapping, but it is said that the effect is not very good, so generally a single-line radar or a multi-line radar is enough.

  num_subdivisions_per_laser_scan = 1,                  -- 1帧数据被分成几次处理,一般为1

A frame of data is divided into several processing times, generally set to 1.

lookup_transform_timeout_sec = 0.2,                   -- 查找tf时的超时时间

Timeout when looking up tf.

submap_publish_period_sec = 0.3,                      -- 发布数据的时间间隔

The frequency of releasing the submap, update the release of the submap every 0.3s.

pose_publish_period_sec = 5e-3,                       -- 发布pose的时间间隔,比如:5e-3频率是200Hz

Posture frequency is generally relatively high.

trajectory_publish_period_sec = 30e-3,                -- 发布轨迹标记的间隔,30e-3是科学记数法,表示的是30乘以10-3次方。也就是0.030秒,就是30毫秒。

The release frequency of motion tracks is also very high.

  rangefinder_sampling_ratio = 1.,                      -- 传感器数据的采样频率,多少次数据采样一次,默认都是1。
  odometry_sampling_ratio = 1.,
  fixed_frame_pose_sampling_ratio = 1.,
  imu_sampling_ratio = 1.,
  landmarks_sampling_ratio = 1.,

The processing frequency of several sensor data, when cartographer processes sensor data, it does not process every frame of data, but sets a sampler. When the sampler is set to 1, every frame of data will be processed. If it is set to less than 1 (for example, 0.5), it will only process every two frames of data. This can firstly reduce the amount of data, and secondly, if the sensor data is inaccurate, it can reduce the frequency of its use.

3. Other parameters

Some parameters after options refer to the parameters that already exist in the header file. These parameters already have default values. If you don’t want to use the default value, you can write here to redefine its value.

Guess you like

Origin blog.csdn.net/YiYeZhiNian/article/details/131774720