Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017 #include "cartographer/mapping/internal/3d/scan_matching/rotational_scan_matcher.h"
00018
00019 #include <map>
00020 #include <vector>
00021
00022 #include "cartographer/common/math.h"
00023 #include "cartographer/common/port.h"
00024
00025 namespace cartographer {
00026 namespace mapping {
00027 namespace scan_matching {
00028
00029 namespace {
00030
00031 constexpr float kMinDistance = 0.2f;
00032 constexpr float kMaxDistance = 0.9f;
00033 constexpr float kSliceHeight = 0.2f;
00034
00035 void AddValueToHistogram(float angle, const float value,
00036 Eigen::VectorXf* histogram) {
00037
00038
00039 while (angle > static_cast<float>(M_PI)) {
00040 angle -= static_cast<float>(M_PI);
00041 }
00042 while (angle < 0.f) {
00043 angle += static_cast<float>(M_PI);
00044 }
00045 const float zero_to_one = angle / static_cast<float>(M_PI);
00046 const int bucket = common::Clamp<int>(
00047 common::RoundToInt(histogram->size() * zero_to_one - 0.5f), 0,
00048 histogram->size() - 1);
00049 (*histogram)(bucket) += value;
00050 }
00051
00052 Eigen::Vector3f ComputeCentroid(const sensor::PointCloud& slice) {
00053 CHECK(!slice.empty());
00054 Eigen::Vector3f sum = Eigen::Vector3f::Zero();
00055 for (const sensor::RangefinderPoint& point : slice) {
00056 sum += point.position;
00057 }
00058 return sum / static_cast<float>(slice.size());
00059 }
00060
00061 void AddPointCloudSliceToHistogram(const sensor::PointCloud& slice,
00062 Eigen::VectorXf* const histogram) {
00063 if (slice.empty()) {
00064 return;
00065 }
00066
00067
00068
00069
00070 const Eigen::Vector3f centroid = ComputeCentroid(slice);
00071 Eigen::Vector3f last_point_position = slice.front().position;
00072 for (const sensor::RangefinderPoint& point : slice) {
00073 const Eigen::Vector2f delta =
00074 (point.position - last_point_position).head<2>();
00075 const Eigen::Vector2f direction = (point.position - centroid).head<2>();
00076 const float distance = delta.norm();
00077 if (distance < kMinDistance || direction.norm() < kMinDistance) {
00078 continue;
00079 }
00080 if (distance > kMaxDistance) {
00081 last_point_position = point.position;
00082 continue;
00083 }
00084 const float angle = common::atan2(delta);
00085 const float value = std::max(
00086 0.f, 1.f - std::abs(delta.normalized().dot(direction.normalized())));
00087 AddValueToHistogram(angle, value, histogram);
00088 }
00089 }
00090
00091
00092
00093
00094 sensor::PointCloud SortSlice(const sensor::PointCloud& slice) {
00095 struct SortableAnglePointPair {
00096 bool operator<(const SortableAnglePointPair& rhs) const {
00097 return angle < rhs.angle;
00098 }
00099
00100 float angle;
00101 sensor::RangefinderPoint point;
00102 };
00103 const Eigen::Vector3f centroid = ComputeCentroid(slice);
00104 std::vector<SortableAnglePointPair> by_angle;
00105 by_angle.reserve(slice.size());
00106 for (const sensor::RangefinderPoint& point : slice) {
00107 const Eigen::Vector2f delta = (point.position - centroid).head<2>();
00108 if (delta.norm() < kMinDistance) {
00109 continue;
00110 }
00111 by_angle.push_back(SortableAnglePointPair{common::atan2(delta), point});
00112 }
00113 std::sort(by_angle.begin(), by_angle.end());
00114 sensor::PointCloud result;
00115 for (const auto& pair : by_angle) {
00116 result.push_back(pair.point);
00117 }
00118 return result;
00119 }
00120
00121 float MatchHistograms(const Eigen::VectorXf& submap_histogram,
00122 const Eigen::VectorXf& scan_histogram) {
00123
00124
00125 const float scan_histogram_norm = scan_histogram.norm();
00126 const float submap_histogram_norm = submap_histogram.norm();
00127 const float normalization = scan_histogram_norm * submap_histogram_norm;
00128 if (normalization < 1e-3f) {
00129 return 1.f;
00130 }
00131 return submap_histogram.dot(scan_histogram) / normalization;
00132 }
00133
00134 }
00135
00136 RotationalScanMatcher::RotationalScanMatcher(const Eigen::VectorXf* histogram)
00137 : histogram_(histogram) {}
00138
00139
00140
00141 Eigen::VectorXf RotationalScanMatcher::RotateHistogram(
00142 const Eigen::VectorXf& histogram, const float angle) {
00143 const float rotate_by_buckets = -angle * histogram.size() / M_PI;
00144 int full_buckets = common::RoundToInt(rotate_by_buckets - 0.5f);
00145 const float fraction = rotate_by_buckets - full_buckets;
00146 while (full_buckets < 0) {
00147 full_buckets += histogram.size();
00148 }
00149 Eigen::VectorXf rotated_histogram_0 = Eigen::VectorXf::Zero(histogram.size());
00150 Eigen::VectorXf rotated_histogram_1 = Eigen::VectorXf::Zero(histogram.size());
00151 for (int i = 0; i != histogram.size(); ++i) {
00152 rotated_histogram_0[i] = histogram[(i + full_buckets) % histogram.size()];
00153 rotated_histogram_1[i] =
00154 histogram[(i + 1 + full_buckets) % histogram.size()];
00155 }
00156 return fraction * rotated_histogram_1 +
00157 (1.f - fraction) * rotated_histogram_0;
00158 }
00159
00160 Eigen::VectorXf RotationalScanMatcher::ComputeHistogram(
00161 const sensor::PointCloud& point_cloud, const int histogram_size) {
00162 Eigen::VectorXf histogram = Eigen::VectorXf::Zero(histogram_size);
00163 std::map<int, sensor::PointCloud> slices;
00164 for (const sensor::RangefinderPoint& point : point_cloud) {
00165 slices[common::RoundToInt(point.position.z() / kSliceHeight)].push_back(
00166 point);
00167 }
00168 for (const auto& slice : slices) {
00169 AddPointCloudSliceToHistogram(SortSlice(slice.second), &histogram);
00170 }
00171 return histogram;
00172 }
00173
00174 std::vector<float> RotationalScanMatcher::Match(
00175 const Eigen::VectorXf& histogram, const float initial_angle,
00176 const std::vector<float>& angles) const {
00177 std::vector<float> result;
00178 result.reserve(angles.size());
00179 for (const float angle : angles) {
00180 const Eigen::VectorXf scan_histogram =
00181 RotateHistogram(histogram, initial_angle + angle);
00182 result.push_back(MatchHistograms(*histogram_, scan_histogram));
00183 }
00184 return result;
00185 }
00186
00187 }
00188 }
00189 }