cartographer的参数

 当我们配置完环境之后咋样运行呢?

launch文件的关键。

<!-- 启动cartographer -->
  <node name="cartographer_node" pkg="cartographer_ros"
      type="cartographer_node" args="
          -configuration_directory $(find cartographer_ros)/configuration_files
          -configuration_basename (name).lua"
      output="screen">
    <remap from="scan" to="front_scan" />
    <remap from="odom" to="odom_scout" />
    <remap from="imu" to="imu" />
  </node>

  <!-- 生成ros格式的地图 -->
  <node name="cartographer_occupancy_grid_node" pkg="cartographer_ros"
      type="cartographer_occupancy_grid_node" args="-resolution 0.05" />

 

在launch文件中<name>.lua是我们需要在上面所展现的路径中添加一个lua文件。

然后将节点内部的 "scan" 话题重映射到名为 "front_scan" 的话题上

odom与imu同理。

最后生成地图,启动 Cartographer 的 Occupancy Grid 节点,并设置生成的 Occupancy Grid 地图的分辨率为 0.05 米。

在lua文件中是对参数进行设置的文件。

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 = "imu_link",              -- 将所有传感器数据转换到这个坐标系下
  published_frame = "footprint",            -- tf: map -> footprint
  odom_frame = "odom",                      -- 里程计的坐标系名字
  provide_odom_frame = false,               -- 是否提供odom的tf, 如果为true,则tf树为map->odom->footprint
                                            -- 如果为false tf树为map->footprint
  publish_frame_projected_to_2d = false,    -- 是否将坐标系投影到平面上
  --use_pose_extrapolator = false,            -- 发布tf时是使用pose_extrapolator的位姿还是前端计算出来的位姿

  use_odometry = false,                     -- 是否使用里程计,如果使用要求一定要有odom的tf
  use_nav_sat = false,                      -- 是否使用gps
  use_landmarks = false,                    -- 是否使用landmark
  num_laser_scans = 0,                      -- 是否使用单线激光数据
  num_multi_echo_laser_scans = 0,           -- 是否使用multi_echo_laser_scans数据
  num_subdivisions_per_laser_scan = 1,      -- 1帧数据被分成几次处理,一般为1
  num_point_clouds = 1,                     -- 是否使用点云数据
  
  lookup_transform_timeout_sec = 0.2,       -- 查找tf时的超时时间
  submap_publish_period_sec = 0.3,          -- 发布数据的时间间隔
  pose_publish_period_sec = 5e-3,
  trajectory_publish_period_sec = 30e-3,

  rangefinder_sampling_ratio = 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.use_imu_data = true
TRAJECTORY_BUILDER_2D.min_range = 0.3
TRAJECTORY_BUILDER_2D.max_range = 100.
TRAJECTORY_BUILDER_2D.min_z = 0.2
--TRAJECTORY_BUILDER_2D.max_z = 1.4
--TRAJECTORY_BUILDER_2D.voxel_filter_size = 0.02

--TRAJECTORY_BUILDER_2D.adaptive_voxel_filter.max_length = 0.5
--TRAJECTORY_BUILDER_2D.adaptive_voxel_filter.min_num_points = 200.
--TRAJECTORY_BUILDER_2D.adaptive_voxel_filter.max_range = 50.

--TRAJECTORY_BUILDER_2D.loop_closure_adaptive_voxel_filter.max_length = 0.9
--TRAJECTORY_BUILDER_2D.loop_closure_adaptive_voxel_filter.min_num_points = 100
--TRAJECTORY_BUILDER_2D.loop_closure_adaptive_voxel_filter.max_range = 50.

TRAJECTORY_BUILDER_2D.use_online_correlative_scan_matching = false
TRAJECTORY_BUILDER_2D.ceres_scan_matcher.occupied_space_weight = 1.
TRAJECTORY_BUILDER_2D.ceres_scan_matcher.translation_weight = 1.
TRAJECTORY_BUILDER_2D.ceres_scan_matcher.rotation_weight = 1.
--TRAJECTORY_BUILDER_2D.ceres_scan_matcher.ceres_solver_options.max_num_iterations = 12

--TRAJECTORY_BUILDER_2D.motion_filter.max_distance_meters = 0.1
--TRAJECTORY_BUILDER_2D.motion_filter.max_angle_radians = 0.004
--TRAJECTORY_BUILDER_2D.imu_gravity_time_constant = 1.

TRAJECTORY_BUILDER_2D.submaps.num_range_data = 80.
TRAJECTORY_BUILDER_2D.submaps.grid_options_2d.resolution = 0.1

POSE_GRAPH.optimize_every_n_nodes = 160.
POSE_GRAPH.constraint_builder.sampling_ratio = 0.3
POSE_GRAPH.constraint_builder.max_constraint_distance = 15.
POSE_GRAPH.constraint_builder.min_score = 0.48
POSE_GRAPH.constraint_builder.global_localization_min_score = 0.60

return options
tracking_frame imu link 就设置成 imu link, 没有就设置成 base_link
published_frame cartographer 发布的 tf 的最下边一个坐标系 , 就是 bag 文件中 tf
树的最上边的一个坐标系
provide_odom_frame 是否提供里程计 , 如果 bag 中有里程计的坐标系 , 这个就是
false, 如果没有 , 就根据需要决定是否提供里程计的坐标系
use_pose_extrapolator = false 这个一定要设置成 false
use_odometry 是否使用里程计的传感器数据 , 如果为 true, tf 树中一定要存在
odom 这个坐标系
use_nav_sat/use_landmarks 是否订阅里程计话题的数据 , 以及 landmark 话题的
数据
num_laser_scans/num_point_clouds 单线点云与多线点云的话题的数量 , 可以同
时为 1, 不可以同时为 0
num_subdivisions_per_laser_scan 一帧点云数据会被分成几次处理 , 设置成 1
行了
MAP_BUILDER.use_trajectory_builder_2d = true 建二维图时一定要有这句话 ,
三维图就把 2d 改成 3d
TRAJECTORY_BUILDER_2D.use_imu_data 是否使用 imu, 如果用 imu,
tracking_frame 一定要设置成 imu link
TRAJECTORY_BUILDER_2D.min_z 点云的最小 z 的范围 , 单线点云不能设置大
0 的值 ( 不设置 ), 多线点云的这个值要大于 0
这几个参数是重点。

还有对话题的问题。
我们将话题重映射后在node_constants.h文件中,例如:
constexpr char kLaserScanTopic[] = "scan";

constexpr(编译时常量)的字符数组,它的名字是 kLaserScanTopic,并初始化为字符串 "scan"。
常调的参数
TRAJECTORY_BUILDER_2D.min_range = 0.3
TRAJECTORY_BUILDER_2D.max_range = 100.
TRAJECTORY_BUILDER_2D.min_z = 0.2 -- / -0.8
TRAJECTORY_BUILDER_2D.voxel_filter_size = 0.02
TRAJECTORY_BUILDER_2D.ceres_scan_matcher.occupied_space_weight = 10.
TRAJECTORY_BUILDER_2D.ceres_scan_matcher.translation_weight = 1.
TRAJECTORY_BUILDER_2D.ceres_scan_matcher.rotation_weight = 1.
TRAJECTORY_BUILDER_2D.submaps.num_range_data = 80.
TRAJECTORY_BUILDER_2D.submaps.grid_options_2d.resolution = 0.1 -- / 0.02
POSE_GRAPH.optimize_every_n_nodes = 160. -- 2 倍的 num_range_data 以上
POSE_GRAPH.constraint_builder.sampling_ratio = 0.3
POSE_GRAPH.constraint_builder.max_constraint_distance = 15.
POSE_GRAPH.constraint_builder.min_score = 0.48
POSE_GRAPH.constraint_builder.global_localization_min_score = 0.60
降低延迟与减小计算量

前端部分
• 减小 max_range, 减小了需要处理的点数, 在雷达数据远距离的点不准时一定要减
小这个值
• 增大 voxel_filter_size, 相当于减小了需要处理的点数
• 增大 submaps.resolution, 相当于减小了匹配时的搜索量
• 对于自适应体素滤波 减小 min_num_points 与 max_range, 增大 max_length, 相当于减小了需要处里的点数

后端部分
• 增大 optimize_every_n_nodes, 降低优化频率, 减小了计算量
• 增大 MAP_BUILDER.num_background_threads, 增加计算速度
• 减小 global_sampling_ratio, 减小计算全局约束的频率
• 减小 constraint_builder.sampling_ratio, 减少了约束的数量
• 增大 constraint_builder.min_score, 减少了约束的数量
• 减小分枝定界搜索窗的大小, 包括
linear_xy_search_window,inear_z_search_window, angular_search_window
• 增大 global_constraint_search_after_n_seconds, 减小计算全局约束的频率
• 减小 max_num_iterations, 减小迭代次数


降低内存
增大子图的分辨率 submaps.resolution
降低纯定位时错误重定位的概率
修改 pose_graph.lua 中的如下参数
• 提高 optimize_every_n_nodes , 减小了优化的次数
• 减小 sampling_ratio, 减小了计算约束的次数
• 减小 max_constraint_distance, 减小了计算约束的距离
• 提高 min_score, 减小了计算约束的数量, 提高约束正确的概率
• 提高 global_localization_min_score, 减小了计算约束的数量, 提高约束正确的概率
• 提高 global_constraint_search_after_n_seconds , 减小了回环的次数(隔多长时间
计算一次)
  • 9
    点赞
  • 12
    收藏
    觉得还不错? 一键收藏
  • 1
    评论
评论 1
添加红包

请填写红包祝福语或标题

红包个数最小为10个

红包金额最低5元

当前余额3.43前往充值 >
需支付:10.00
成就一亿技术人!
领取后你会自动成为博主和红包主的粉丝 规则
hope_wisdom
发出的红包
实付
使用余额支付
点击重新获取
扫码支付
钱包余额 0

抵扣说明:

1.余额是钱包充值的虚拟货币,按照1:1的比例进行支付金额的抵扣。
2.余额无法直接购买下载,可以购买VIP、付费专栏及课程。

余额充值