当前位置:   article > 正文

cartographer(8)点云匹配_无特征点云匹配

无特征点云匹配

 1.处理点云数据LocalTrajectoryBuilder2D::AddRangeData

函数实现的功能:
1:依据分发出来的点云中每个点的时间(time),使用位姿推断器推断time时刻tracking坐标系的位姿。
2:依据1中推断出来的位姿将点云中的点转换到local坐标系下。
3:将传入的点云的origins坐标转到 local slam 坐标系下,

做运动畸变的去除相对于tracking_frame的hit坐标 转成 local坐标系下的坐标 

两点相减得到距离 在激光有效范围内  的点保存起来。(此时此刻点云中的点到其对应的原点距离,距离超过最大值(传感器最大值),要做特别的处理)。
4:将3得到点云做自适应体素滤波,并做匹配。
5:根据匹配结果将点云写入submap
6:把匹配得到的位姿加入位姿推断器 

  1. /**
  2. * @brief 处理点云数据, 进行扫描匹配, 将点云写成地图
  3. *
  4. * @param[in] sensor_id 点云数据对应的话题名称
  5. * @param[in] unsynchronized_data 传入的点云数据
  6. * @return std::unique_ptr<LocalTrajectoryBuilder2D::MatchingResult> 匹配后的结果
  7. */
  8. std::unique_ptr<LocalTrajectoryBuilder2D::MatchingResult>
  9. LocalTrajectoryBuilder2D::AddRangeData(
  10. const std::string& sensor_id,
  11. const sensor::TimedPointCloudData& unsynchronized_data) {
  12. // Step: 1 进行多个雷达点云数据的时间同步, 点云的坐标是相对于tracking_frame的
  13. auto synchronized_data =
  14. range_data_collator_.AddRangeData(sensor_id, unsynchronized_data);
  15. if (synchronized_data.ranges.empty()) {
  16. LOG(INFO) << "Range data collator filling buffer.";
  17. return nullptr;
  18. }
  19. const common::Time& time = synchronized_data.time;
  20. // Initialize extrapolator now if we do not ever use an IMU.
  21. // 如果不用imu, 就在雷达这初始化位姿推测器
  22. if (!options_.use_imu_data()) {
  23. InitializeExtrapolator(time);
  24. }
  25. if (extrapolator_ == nullptr) {
  26. // Until we've initialized the extrapolator with our first IMU message, we
  27. // cannot compute the orientation of the rangefinder.
  28. LOG(INFO) << "Extrapolator not yet initialized.";
  29. return nullptr;
  30. }
  31. CHECK(!synchronized_data.ranges.empty());
  32. // TODO(gaschler): Check if this can strictly be 0.
  33. CHECK_LE(synchronized_data.ranges.back().point_time.time, 0.f);
  34. // 计算第一个点的时间
  35. const common::Time time_first_point =
  36. time +
  37. common::FromSeconds(synchronized_data.ranges.front().point_time.time);
  38. // 只有在extrapolator_初始化时, GetLastPoseTime()是common::Time::min()
  39. if (time_first_point < extrapolator_->GetLastPoseTime()) {
  40. LOG(INFO) << "Extrapolator is still initializing.";
  41. return nullptr;
  42. }
  43. std::vector<transform::Rigid3f> range_data_poses;
  44. range_data_poses.reserve(synchronized_data.ranges.size());
  45. bool warned = false;
  46. // 预测得到每一个时间点的位姿
  47. for (const auto& range : synchronized_data.ranges) {
  48. common::Time time_point = time + common::FromSeconds(range.point_time.time);
  49. // 如果该时间比上次预测位姿的时间还要早,说明这个点的时间戳往回走了, 就报错
  50. if (time_point < extrapolator_->GetLastExtrapolatedTime()) {
  51. // 一个循环只报一次错
  52. if (!warned) {
  53. LOG(ERROR)
  54. << "Timestamp of individual range data point jumps backwards from "
  55. << extrapolator_->GetLastExtrapolatedTime() << " to " << time_point;
  56. warned = true;
  57. }
  58. time_point = extrapolator_->GetLastExtrapolatedTime();
  59. }
  60. // Step: 2 预测出 每个点的时间戳时刻, tracking frame 在 local slam 坐标系下的位姿
  61. range_data_poses.push_back(
  62. extrapolator_->ExtrapolatePose(time_point).cast<float>());
  63. }
  64. if (num_accumulated_ == 0) {
  65. // 'accumulated_range_data_.origin' is uninitialized until the last
  66. // accumulation.
  67. accumulated_range_data_ = sensor::RangeData{{}, {}, {}};
  68. }
  69. // Drop any returns below the minimum range and convert returns beyond the
  70. // maximum range into misses.
  71. // 对每个数据点进行处理
  72. for (size_t i = 0; i < synchronized_data.ranges.size(); ++i) {
  73. // 获取在tracking frame 下点的坐标
  74. const sensor::TimedRangefinderPoint& hit =
  75. synchronized_data.ranges[i].point_time;
  76. // 将点云的origins坐标转到 local slam 坐标系下
  77. const Eigen::Vector3f origin_in_local =
  78. range_data_poses[i] *
  79. synchronized_data.origins.at(synchronized_data.ranges[i].origin_index);
  80. // Step: 3 运动畸变的去除, 将相对于tracking_frame的hit坐标 转成 local坐标系下的坐标
  81. sensor::RangefinderPoint hit_in_local =
  82. range_data_poses[i] * sensor::ToRangefinderPoint(hit);
  83. // 计算这个点的距离, 这里用的是去畸变之后的点的距离
  84. const Eigen::Vector3f delta = hit_in_local.position - origin_in_local;
  85. const float range = delta.norm();
  86. // param: min_range max_range
  87. if (range >= options_.min_range()) {
  88. if (range <= options_.max_range()) {
  89. // 在这里可以看到, returns里保存的是local slam下的去畸变之后的点的坐标
  90. accumulated_range_data_.returns.push_back(hit_in_local);
  91. } else {
  92. // Step: 4 超过max_range时的处理: 用一个距离进行替代, 并放入misses里
  93. hit_in_local.position =
  94. origin_in_local +
  95. // param: missing_data_ray_length, 是个比例, 不是距离
  96. options_.missing_data_ray_length() / range * delta;
  97. accumulated_range_data_.misses.push_back(hit_in_local);
  98. }
  99. }
  100. } // end for
  101. // 有一帧有效的数据了
  102. ++num_accumulated_;
  103. // param: num_accumulated_range_data 几帧有效的点云数据进行一次扫描匹配
  104. if (num_accumulated_ >= options_.num_accumulated_range_data()) {
  105. // 计算2次有效点云数据的的时间差
  106. const common::Time current_sensor_time = synchronized_data.time;
  107. absl::optional<common::Duration> sensor_duration;
  108. if (last_sensor_time_.has_value()) {
  109. sensor_duration = current_sensor_time - last_sensor_time_.value();
  110. }
  111. last_sensor_time_ = current_sensor_time;
  112. // 重置变量
  113. num_accumulated_ = 0;
  114. // 获取机器人当前姿态
  115. const transform::Rigid3d gravity_alignment = transform::Rigid3d::Rotation(
  116. extrapolator_->EstimateGravityOrientation(time));
  117. // TODO(gaschler): This assumes that 'range_data_poses.back()' is at time
  118. // 'time'.
  119. // 以最后一个点的时间戳估计出的坐标为这帧数据的原点
  120. accumulated_range_data_.origin = range_data_poses.back().translation();
  121. return AddAccumulatedRangeData(
  122. time,
  123. // 将点云变换到local原点处, 且姿态为0
  124. TransformToGravityAlignedFrameAndFilter(
  125. gravity_alignment.cast<float>() * range_data_poses.back().inverse(),
  126. accumulated_range_data_),
  127. gravity_alignment, sensor_duration);
  128. }
  129. return nullptr;
  130. }

 预测出 每个点的时间戳时刻, tracking frame 在 local slam 坐标系下的位姿

extrapolator_->ExtrapolatePose(time_point).cast<float>());

  1. // 预测得到time时刻 tracking frame 在 local 坐标系下的位姿
  2. transform::Rigid3d PoseExtrapolator::ExtrapolatePose(const common::Time time) {
  3. const TimedPose& newest_timed_pose = timed_pose_queue_.back();
  4. CHECK_GE(time, newest_timed_pose.time);
  5. // 如果本次预测时间与上次计算时间相同 就不再重复计算
  6. if (cached_extrapolated_pose_.time != time) {
  7. // 预测tracking frame在local坐标系下time时刻的位置
  8. const Eigen::Vector3d translation =
  9. ExtrapolateTranslation(time) + newest_timed_pose.pose.translation();
  10. // 预测tracking frame在local坐标系下time时刻的姿态
  11. const Eigen::Quaterniond rotation =
  12. newest_timed_pose.pose.rotation() *
  13. ExtrapolateRotation(time, extrapolation_imu_tracker_.get());
  14. cached_extrapolated_pose_ =
  15. TimedPose{time, transform::Rigid3d{translation, rotation}};
  16. }
  17. return cached_extrapolated_pose_.pose;
  18. }

 先进行点云的旋转与z方向的滤波, 然后再进行体素滤波减少数据量

  1. /**
  2. * @brief 先进行点云的旋转与z方向的滤波, 然后再进行体素滤波减少数据量
  3. *
  4. * @param[in] transform_to_gravity_aligned_frame 将点云变换到原点处, 且姿态为0的坐标变换
  5. * @param[in] range_data 传入的点云
  6. * @return sensor::RangeData 处理后的点云 拷贝
  7. */
  8. sensor::RangeData
  9. LocalTrajectoryBuilder2D::TransformToGravityAlignedFrameAndFilter(
  10. const transform::Rigid3f& transform_to_gravity_aligned_frame,
  11. const sensor::RangeData& range_data) const {
  12. // Step: 5 将原点位于机器人当前位姿处的点云 转成 原点位于local坐标系原点处的点云, 再进行z轴上的过滤
  13. const sensor::RangeData cropped =
  14. sensor::CropRangeData(sensor::TransformRangeData(
  15. range_data, transform_to_gravity_aligned_frame),
  16. options_.min_z(), options_.max_z()); // param: min_z max_z
  17. // Step: 6 对点云进行体素滤波
  18. return sensor::RangeData{
  19. cropped.origin,
  20. sensor::VoxelFilter(cropped.returns, options_.voxel_filter_size()), // param: voxel_filter_size
  21. sensor::VoxelFilter(cropped.misses, options_.voxel_filter_size())};
  22. }

进行扫描匹配, 将点云写入地图 

  1. /**
  2. * @brief 进行扫描匹配, 将点云写入地图
  3. *
  4. * @param[in] time 点云的时间戳
  5. * @param[in] gravity_aligned_range_data 原点位于local坐标系原点处的点云
  6. * @param[in] gravity_alignment 机器人当前姿态
  7. * @param[in] sensor_duration 2帧点云数据的时间差
  8. * @return std::unique_ptr<LocalTrajectoryBuilder2D::MatchingResult>
  9. */
  10. std::unique_ptr<LocalTrajectoryBuilder2D::MatchingResult>
  11. LocalTrajectoryBuilder2D::AddAccumulatedRangeData(
  12. const common::Time time,
  13. const sensor::RangeData& gravity_aligned_range_data,
  14. const transform::Rigid3d& gravity_alignment,
  15. const absl::optional<common::Duration>& sensor_duration) {
  16. // 如果处理完点云之后数据为空, 就报错. 使用单线雷达时不要设置min_z
  17. if (gravity_aligned_range_data.returns.empty()) {
  18. LOG(WARNING) << "Dropped empty horizontal range data.";
  19. return nullptr;
  20. }
  21. // Computes a gravity aligned pose prediction.
  22. // 进行位姿的预测, 先验位姿
  23. const transform::Rigid3d non_gravity_aligned_pose_prediction =
  24. extrapolator_->ExtrapolatePose(time);
  25. // 将三维位姿先旋转到姿态为0, 再取xy坐标将三维位姿转成二维位姿
  26. const transform::Rigid2d pose_prediction = transform::Project2D(
  27. non_gravity_aligned_pose_prediction * gravity_alignment.inverse());
  28. // Step: 7 对 returns点云 进行自适应体素滤波,返回的点云的数据类型是PointCloud
  29. const sensor::PointCloud& filtered_gravity_aligned_point_cloud =
  30. sensor::AdaptiveVoxelFilter(gravity_aligned_range_data.returns,
  31. options_.adaptive_voxel_filter_options());
  32. if (filtered_gravity_aligned_point_cloud.empty()) {
  33. return nullptr;
  34. }
  35. // local map frame <- gravity-aligned frame
  36. // 扫描匹配, 进行点云与submap的匹配
  37. std::unique_ptr<transform::Rigid2d> pose_estimate_2d =
  38. ScanMatch(time, pose_prediction, filtered_gravity_aligned_point_cloud);
  39. if (pose_estimate_2d == nullptr) {
  40. LOG(WARNING) << "Scan matching failed.";
  41. return nullptr;
  42. }
  43. // 将二维坐标旋转回之前的姿态
  44. const transform::Rigid3d pose_estimate =
  45. transform::Embed3D(*pose_estimate_2d) * gravity_alignment;
  46. // 校准位姿估计器
  47. extrapolator_->AddPose(time, pose_estimate);
  48. // Step: 8 将 原点位于local坐标系原点处的点云 变换成 原点位于匹配后的位姿处的点云
  49. sensor::RangeData range_data_in_local =
  50. TransformRangeData(gravity_aligned_range_data,
  51. transform::Embed3D(pose_estimate_2d->cast<float>()));
  52. // 将校正后的雷达数据写入submap
  53. std::unique_ptr<InsertionResult> insertion_result = InsertIntoSubmap(
  54. time, range_data_in_local, filtered_gravity_aligned_point_cloud,
  55. pose_estimate, gravity_alignment.rotation());
  56. // 计算耗时
  57. const auto wall_time = std::chrono::steady_clock::now();
  58. if (last_wall_time_.has_value()) {
  59. const auto wall_time_duration = wall_time - last_wall_time_.value();
  60. kLocalSlamLatencyMetric->Set(common::ToSeconds(wall_time_duration));
  61. if (sensor_duration.has_value()) {
  62. kLocalSlamRealTimeRatio->Set(common::ToSeconds(sensor_duration.value()) /
  63. common::ToSeconds(wall_time_duration));
  64. }
  65. }
  66. // 计算cpu耗时
  67. const double thread_cpu_time_seconds = common::GetThreadCpuTimeSeconds();
  68. if (last_thread_cpu_time_seconds_.has_value()) {
  69. const double thread_cpu_duration_seconds =
  70. thread_cpu_time_seconds - last_thread_cpu_time_seconds_.value();
  71. if (sensor_duration.has_value()) {
  72. kLocalSlamCpuRealTimeRatio->Set(
  73. common::ToSeconds(sensor_duration.value()) /
  74. thread_cpu_duration_seconds);
  75. }
  76. }
  77. last_wall_time_ = wall_time;
  78. last_thread_cpu_time_seconds_ = thread_cpu_time_seconds;
  79. // 返回结果
  80. return absl::make_unique<MatchingResult>(
  81. MatchingResult{time, pose_estimate, std::move(range_data_in_local),
  82. std::move(insertion_result)});
  83. }

声明:本文内容由网友自发贡献,不代表【wpsshop博客】立场,版权归原作者所有,本站不承担相应法律责任。如您发现有侵权的内容,请联系我们。转载请注明出处:https://www.wpsshop.cn/w/羊村懒王/article/detail/122676?site
推荐阅读
相关标签
  

闽ICP备14008679号