27 namespace scan_matching {
31 constexpr
float kMinDistance = 0.2f;
32 constexpr
float kMaxDistance = 0.9f;
33 constexpr
float kSliceHeight = 0.2f;
35 void AddValueToHistogram(
float angle,
const float value,
36 Eigen::VectorXf* histogram) {
39 while (angle > static_cast<float>(M_PI)) {
40 angle -=
static_cast<float>(M_PI);
43 angle +=
static_cast<float>(M_PI);
45 const float zero_to_one = angle /
static_cast<float>(M_PI);
46 const int bucket = common::Clamp<int>(
48 histogram->size() - 1);
49 (*histogram)(bucket) += value;
53 CHECK(!slice.empty());
54 Eigen::Vector3f sum = Eigen::Vector3f::Zero();
55 for (
const Eigen::Vector3f& point : slice) {
58 return sum /
static_cast<float>(slice.size());
62 Eigen::VectorXf*
const histogram) {
70 const Eigen::Vector3f centroid = ComputeCentroid(slice);
71 Eigen::Vector3f last_point = slice.front();
72 for (
const Eigen::Vector3f& point : slice) {
73 const Eigen::Vector2f delta = (point - last_point).head<2>();
74 const Eigen::Vector2f direction = (point - centroid).head<2>();
75 const float distance = delta.norm();
76 if (distance < kMinDistance || direction.norm() < kMinDistance) {
79 if (distance > kMaxDistance) {
84 const float value = std::max(
85 0.f, 1.f - std::abs(delta.normalized().dot(direction.normalized())));
86 AddValueToHistogram(angle, value, histogram);
94 struct SortableAnglePointPair {
95 bool operator<(
const SortableAnglePointPair& rhs)
const {
96 return angle < rhs.angle;
100 Eigen::Vector3f point;
102 const Eigen::Vector3f centroid = ComputeCentroid(slice);
103 std::vector<SortableAnglePointPair> by_angle;
104 by_angle.reserve(slice.size());
105 for (
const Eigen::Vector3f& point : slice) {
106 const Eigen::Vector2f delta = (point - centroid).head<2>();
107 if (delta.norm() < kMinDistance) {
110 by_angle.push_back(SortableAnglePointPair{
common::atan2(delta), point});
112 std::sort(by_angle.begin(), by_angle.end());
114 for (
const auto& pair : by_angle) {
115 result.push_back(pair.point);
122 Eigen::VectorXf RotateHistogram(
const Eigen::VectorXf& histogram,
124 const float rotate_by_buckets = -angle * histogram.size() / M_PI;
126 const float fraction = rotate_by_buckets - full_buckets;
127 while (full_buckets < 0) {
128 full_buckets += histogram.size();
130 Eigen::VectorXf rotated_histogram_0 = Eigen::VectorXf::Zero(histogram.size());
131 Eigen::VectorXf rotated_histogram_1 = Eigen::VectorXf::Zero(histogram.size());
132 for (
int i = 0; i != histogram.size(); ++i) {
133 rotated_histogram_0[i] = histogram[(i + full_buckets) % histogram.size()];
134 rotated_histogram_1[i] =
135 histogram[(i + 1 + full_buckets) % histogram.size()];
137 return fraction * rotated_histogram_1 +
138 (1.f - fraction) * rotated_histogram_0;
141 float MatchHistograms(
const Eigen::VectorXf& submap_histogram,
142 const Eigen::VectorXf& scan_histogram) {
145 const float scan_histogram_norm = scan_histogram.norm();
146 const float submap_histogram_norm = submap_histogram.norm();
147 const float normalization = scan_histogram_norm * submap_histogram_norm;
148 if (normalization < 1e-3f) {
151 return submap_histogram.dot(scan_histogram) / normalization;
158 Eigen::VectorXf histogram = Eigen::VectorXf::Zero(histogram_size);
159 std::map<int, sensor::PointCloud> slices;
160 for (
const Eigen::Vector3f& point : point_cloud) {
163 for (
const auto& slice : slices) {
164 AddPointCloudSliceToHistogram(SortSlice(slice.second), &histogram);
170 const std::vector<std::pair<Eigen::VectorXf, float>>& histograms_at_angles)
172 Eigen::VectorXf::Zero(histograms_at_angles.at(0).first.size())) {
173 for (
const auto& histogram_at_angle : histograms_at_angles) {
175 RotateHistogram(histogram_at_angle.first, histogram_at_angle.second);
180 const Eigen::VectorXf& histogram,
const float initial_angle,
181 const std::vector<float>& angles)
const {
182 std::vector<float> result;
183 result.reserve(angles.size());
184 for (
const float angle : angles) {
185 const Eigen::VectorXf scan_histogram =
186 RotateHistogram(histogram, initial_angle + angle);
187 result.push_back(MatchHistograms(
histogram_, scan_histogram));
int RoundToInt(const float x)
T atan2(const Eigen::Matrix< T, 2, 1 > &vector)
Eigen::VectorXf histogram_
std::vector< float > Match(const Eigen::VectorXf &histogram, float initial_angle, const std::vector< float > &angles) const
std::vector< Eigen::Vector3f > PointCloud
static Eigen::VectorXf ComputeHistogram(const sensor::PointCloud &point_cloud, int histogram_size)
RotationalScanMatcher(const std::vector< std::pair< Eigen::VectorXf, float >> &histograms_at_angles)