cartographer详解(二)—— Real Time Correlative Scan Matcher(3d模式)

cartographer详解(二)—— Real Time Correlative Scan Matcher(3d模式)

摘要:这章主要讲解cartographer中3d模式下使用的 real time 匹配,先讲原理,然后详解代码。关于2d模式下的做法,略有不同,下一章在详细介绍。

1、准备知识介绍

  • 概率栅格图
    占据栅格图(occupancy grid map),就是利用了栅格化的思路,将障碍物在地图中以占据栅格进行表示。概率越高,说明该位置很有可能有障碍物;相反概率越低,也就意味着该位置很可能是空的。下面两图分别表示占据栅格图局部示意、以及整张地图。
    在这里插入图片描述在这里插入图片描述

2、Real Time 匹配算法综述

  • 激光打到障碍物才返回,也就是说当前激光数据可以很好的反应出当前车辆附近障碍物的轮廓。
    在这里插入图片描述
  • 通过激光扫描到的轮廓,和上面栅格图进行对比,通过最佳匹配位置找到机器人的位姿。
  • 如何找到最佳匹配位置了。
    1、在设定的初始位置,在窗口范围内搜索,提取出每个候选位姿。
    2、计算出每个候选位姿下,点云打在栅格图上面的概率,计算其和。
    3、概率和最大的候选位姿,就为所要寻找的最佳位姿。

3、代码详解

通过上面的讲述,对real time 匹配算法,有了个直观的认识,下面结合代码进一步了解其细节。

  • 代码总入口
float RealTimeCorrelativeScanMatcher::Match(
    const transform::Rigid3d& initial_pose_estimate, //机器人初始位置
    const sensor::PointCloud& point_cloud, //雷达点云
    const HybridGrid& hybrid_grid, //概率栅格图
    transform::Rigid3d* pose_estimate //求得的最佳位姿
    ) const {
  CHECK_NOTNULL(pose_estimate);
  float best_score = -1.f;
  for (const transform::Rigid3f& transform : GenerateExhaustiveSearchTransforms(
           hybrid_grid.resolution(), point_cloud)) {
    const transform::Rigid3f candidate =
        initial_pose_estimate.cast<float>() * transform;
    const float score = ScoreCandidate(
        hybrid_grid, sensor::TransformPointCloud(point_cloud, candidate),
        transform);
    if (score > best_score) {
      best_score = score;
      *pose_estimate = candidate.cast<double>();
    }
  }
  return best_score;
}

上面函数的有一下两个主要逻辑:
1、GenerateExhaustiveSearchTransforms:创建搜索空间,也就是说在一定范围内,等间隔划分搜索位置,这所有搜索位置的集合为搜索空间。
2、ScoreCandidate:最佳位置,应该出现在上面搜索空间中的某一个搜索位置。该函数的目的就是,对搜索空间中的所有搜索位置进行打分,找出打分最高的,就认为是最佳位置。

下面详细看这两个函数的代码,了解其细节

  • 创建搜索空间:GenerateExhaustiveSearchTransforms
std::vector<transform::Rigid3f>
RealTimeCorrelativeScanMatcher::GenerateExhaustiveSearchTransforms(
    const float resolution, const sensor::PointCloud& point_cloud) const {
  std::vector<transform::Rigid3f> result;
  //线性搜索步长=线性搜索距离(x,y,z方向)÷ 分辨率(每个格子的长度)
  const int linear_window_size =  
      common::RoundToInt(options_.linear_search_window() / resolution);
  // We set this value to something on the order of resolution to make sure that
  // the std::acos() below is defined.
  float max_scan_range = 3.f * resolution;
  for (const Eigen::Vector3f& point : point_cloud) {
    const float range = point.norm();
    max_scan_range = std::max(range, max_scan_range);
  }
  const float kSafetyMargin = 1.f - 1e-3f;
  const float angular_step_size =  //采用余弦定理计算角度步长,具体理解见下面图片。
      kSafetyMargin * std::acos(1.f - common::Pow2(resolution) /
                                          (2.f * common::Pow2(max_scan_range)));
  const int angular_window_size =
      common::RoundToInt(options_.angular_search_window() / angular_step_size);
  for (int z = -linear_window_size; z <= linear_window_size; ++z) {
    for (int y = -linear_window_size; y <= linear_window_size; ++y) {
      for (int x = -linear_window_size; x <= linear_window_size; ++x) {
        for (int rz = -angular_window_size; rz <= angular_window_size; ++rz) {
          for (int ry = -angular_window_size; ry <= angular_window_size; ++ry) {
            for (int rx = -angular_window_size; rx <= angular_window_size;
                 ++rx) {
              const Eigen::Vector3f angle_axis(rx * angular_step_size,
                                               ry * angular_step_size,
                                               rz * angular_step_size);
              result.emplace_back(
                  Eigen::Vector3f(x * resolution, y * resolution,
                                  z * resolution),
                  transform::AngleAxisVectorToRotationQuaternion(angle_axis));
            }
          }
        }
      }
    }
  }
  return result;
}

角度步长angular_step_size的计算如下:
在这里插入图片描述
在这里插入图片描述

  • 对候选位置进行打分:ScoreCandidate
float RealTimeCorrelativeScanMatcher::ScoreCandidate(
    const HybridGrid& hybrid_grid,
    const sensor::PointCloud& transformed_point_cloud,
    const transform::Rigid3f& transform) const {
  float score = 0.f;
  //获得每个point,在概率栅格图hybrid_grid上面的概率score, 求和,然后求平均。
  for (const Eigen::Vector3f& point : transformed_point_cloud) {
    score += hybrid_grid.GetProbability(hybrid_grid.GetCellIndex(point));
  }
  score /= static_cast<float>(transformed_point_cloud.size());
  const float angle = transform::GetAngle(transform);
  //求得的分值score,要乘以对应的权重。候选位置的平移量translation,旋转量angle越大,
  //说明越偏离初始值,可靠性越差,对应的权重就越小。
  score *=
      std::exp(-common::Pow2(transform.translation().norm() *
                                 options_.translation_delta_cost_weight() +
                             angle * options_.rotation_delta_cost_weight()));
  CHECK_GT(score, 0.f);
  return score;
}
  • 1
    点赞
  • 13
    收藏
    觉得还不错? 一键收藏
  • 1
    评论

“相关推荐”对你有帮助么?

  • 非常没帮助
  • 没帮助
  • 一般
  • 有帮助
  • 非常有帮助
提交
评论 1
添加红包

请填写红包祝福语或标题

红包个数最小为10个

红包金额最低5元

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

抵扣说明:

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

余额充值