rotational_scan_matcher.cc
Go to the documentation of this file.
1 /*
2  * Copyright 2016 The Cartographer Authors
3  *
4  * Licensed under the Apache License, Version 2.0 (the "License");
5  * you may not use this file except in compliance with the License.
6  * You may obtain a copy of the License at
7  *
8  * http://www.apache.org/licenses/LICENSE-2.0
9  *
10  * Unless required by applicable law or agreed to in writing, software
11  * distributed under the License is distributed on an "AS IS" BASIS,
12  * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
13  * See the License for the specific language governing permissions and
14  * limitations under the License.
15  */
16 
18 
19 #include <map>
20 #include <vector>
21 
24 
25 namespace cartographer {
26 namespace mapping {
27 namespace scan_matching {
28 
29 namespace {
30 
31 constexpr float kMinDistance = 0.2f;
32 constexpr float kMaxDistance = 0.9f;
33 constexpr float kSliceHeight = 0.2f;
34 
35 void AddValueToHistogram(float angle, const float value,
36  Eigen::VectorXf* histogram) {
37  // Map the angle to [0, pi), i.e. a vector and its inverse are considered to
38  // represent the same angle.
39  while (angle > static_cast<float>(M_PI)) {
40  angle -= static_cast<float>(M_PI);
41  }
42  while (angle < 0.f) {
43  angle += static_cast<float>(M_PI);
44  }
45  const float zero_to_one = angle / static_cast<float>(M_PI);
46  const int bucket = common::Clamp<int>(
47  common::RoundToInt(histogram->size() * zero_to_one - 0.5f), 0,
48  histogram->size() - 1);
49  (*histogram)(bucket) += value;
50 }
51 
52 Eigen::Vector3f ComputeCentroid(const sensor::PointCloud& slice) {
53  CHECK(!slice.empty());
54  Eigen::Vector3f sum = Eigen::Vector3f::Zero();
55  for (const Eigen::Vector3f& point : slice) {
56  sum += point;
57  }
58  return sum / static_cast<float>(slice.size());
59 }
60 
61 void AddPointCloudSliceToHistogram(const sensor::PointCloud& slice,
62  Eigen::VectorXf* const histogram) {
63  if (slice.empty()) {
64  return;
65  }
66  // We compute the angle of the ray from a point to the centroid of the whole
67  // point cloud. If it is orthogonal to the angle we compute between points, we
68  // will add the angle between points to the histogram with the maximum weight.
69  // This is to reject, e.g., the angles observed on the ceiling and floor.
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) {
77  continue;
78  }
79  if (distance > kMaxDistance) {
80  last_point = point;
81  continue;
82  }
83  const float angle = common::atan2(delta);
84  const float value = std::max(
85  0.f, 1.f - std::abs(delta.normalized().dot(direction.normalized())));
86  AddValueToHistogram(angle, value, histogram);
87  }
88 }
89 
90 // A function to sort the points in each slice by angle around the centroid.
91 // This is because the returns from different rangefinders are interleaved in
92 // the data.
93 sensor::PointCloud SortSlice(const sensor::PointCloud& slice) {
94  struct SortableAnglePointPair {
95  bool operator<(const SortableAnglePointPair& rhs) const {
96  return angle < rhs.angle;
97  }
98 
99  float angle;
100  Eigen::Vector3f point;
101  };
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) {
108  continue;
109  }
110  by_angle.push_back(SortableAnglePointPair{common::atan2(delta), point});
111  }
112  std::sort(by_angle.begin(), by_angle.end());
113  sensor::PointCloud result;
114  for (const auto& pair : by_angle) {
115  result.push_back(pair.point);
116  }
117  return result;
118 }
119 
120 // Rotates the given 'histogram' by the given 'angle'. This might lead to
121 // rotations of a fractional bucket which is handled by linearly interpolating.
122 Eigen::VectorXf RotateHistogram(const Eigen::VectorXf& histogram,
123  const float angle) {
124  const float rotate_by_buckets = -angle * histogram.size() / M_PI;
125  int full_buckets = common::RoundToInt(rotate_by_buckets - 0.5f);
126  const float fraction = rotate_by_buckets - full_buckets;
127  while (full_buckets < 0) {
128  full_buckets += histogram.size();
129  }
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()];
136  }
137  return fraction * rotated_histogram_1 +
138  (1.f - fraction) * rotated_histogram_0;
139 }
140 
141 float MatchHistograms(const Eigen::VectorXf& submap_histogram,
142  const Eigen::VectorXf& scan_histogram) {
143  // We compute the dot product of normalized histograms as a measure of
144  // similarity.
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) {
149  return 1.f;
150  }
151  return submap_histogram.dot(scan_histogram) / normalization;
152 }
153 
154 } // namespace
155 
157  const sensor::PointCloud& point_cloud, const int histogram_size) {
158  Eigen::VectorXf histogram = Eigen::VectorXf::Zero(histogram_size);
159  std::map<int, sensor::PointCloud> slices;
160  for (const Eigen::Vector3f& point : point_cloud) {
161  slices[common::RoundToInt(point.z() / kSliceHeight)].push_back(point);
162  }
163  for (const auto& slice : slices) {
164  AddPointCloudSliceToHistogram(SortSlice(slice.second), &histogram);
165  }
166  return histogram;
167 }
168 
170  const std::vector<std::pair<Eigen::VectorXf, float>>& histograms_at_angles)
171  : histogram_(
172  Eigen::VectorXf::Zero(histograms_at_angles.at(0).first.size())) {
173  for (const auto& histogram_at_angle : histograms_at_angles) {
174  histogram_ +=
175  RotateHistogram(histogram_at_angle.first, histogram_at_angle.second);
176  }
177 }
178 
179 std::vector<float> RotationalScanMatcher::Match(
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));
188  }
189  return result;
190 }
191 
192 } // namespace scan_matching
193 } // namespace mapping
194 } // namespace cartographer
int RoundToInt(const float x)
Definition: port.h:41
T atan2(const Eigen::Matrix< T, 2, 1 > &vector)
Definition: math.h:70
std::vector< float > Match(const Eigen::VectorXf &histogram, float initial_angle, const std::vector< float > &angles) const
std::vector< Eigen::Vector3f > PointCloud
Definition: point_cloud.h:32
static Eigen::VectorXf ComputeHistogram(const sensor::PointCloud &point_cloud, int histogram_size)
RotationalScanMatcher(const std::vector< std::pair< Eigen::VectorXf, float >> &histograms_at_angles)


cartographer
Author(s): The Cartographer Authors
autogenerated on Mon Feb 28 2022 22:00:58