Autoware.Auto
eigenbox_2d.hpp
Go to the documentation of this file.
1 // Copyright 2017-2019 the Autoware Foundation
2 //
3 // Licensed under the Apache License, Version 2.0 (the "License");
4 // you may not use this file except in compliance with the License.
5 // You may obtain a copy of the License at
6 //
7 //    http://www.apache.org/licenses/LICENSE-2.0
8 //
9 // Unless required by applicable law or agreed to in writing, software
10 // distributed under the License is distributed on an "AS IS" BASIS,
11 // WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
12 // See the License for the specific language governing permissions and
13 // limitations under the License.
14 //
15 // Co-developed by Tier IV, Inc. and Apex.AI, Inc.
16 
20 
21 #ifndef GEOMETRY__BOUNDING_BOX__EIGENBOX_2D_HPP_
22 #define GEOMETRY__BOUNDING_BOX__EIGENBOX_2D_HPP_
23 
25 #include <limits>
26 #include <utility>
27 
28 namespace autoware
29 {
30 namespace common
31 {
32 namespace geometry
33 {
34 namespace bounding_box
35 {
36 namespace details
37 {
38 
41 {
49  std::size_t num_points;
50 }; // struct Covariance2d
51 
57 template<typename IT>
58 Covariance2d covariance_2d(const IT begin, const IT end)
59 {
60  Covariance2d ret{0.0F, 0.0F, 0.0F, 0U};
61  float32_t ux = 0.0F;
62  float32_t uy = 0.0F;
63  float32_t num_points = 0.0F;
64  using point_adapter::x_;
65  using point_adapter::y_;
66  for (auto it = begin; it != end; ++it) {
67  ++ret.num_points;
68  num_points = static_cast<float32_t>(ret.num_points);
69  const auto & pt = *it;
70  // update mean x
71  const float32_t dx = x_(pt) - ux;
72  ux = ux + (dx / num_points);
73  // update cov
74  const float32_t dy = y_(pt) - uy;
75  ret.xy += (x_(pt) - ux) * (dy);
76  // update mean y
77  uy = uy + (dy / num_points);
78  // update M2
79  ret.xx += dx * (x_(pt) - ux);
80  ret.yy += dy * (y_(pt) - uy);
81  }
82  // finalize sample (co-)variance
83  if (ret.num_points > 1U) {
84  num_points = num_points - 1.0F;
85  }
86  ret.xx /= num_points;
87  ret.yy /= num_points;
88  ret.xy /= num_points;
89 
90  return ret;
91 }
92 
100 template<typename PointT>
101 std::pair<float32_t, float32_t> eig_2d(
102  const Covariance2d & cov, PointT & eigvec1, PointT & eigvec2)
103 {
104  const float32_t tr_2 = (cov.xx + cov.yy) * 0.5F;
105  const float32_t det = (cov.xx * cov.yy) - (cov.xy * cov.xy);
106  // Add a small fudge to alleviate floating point errors
107  float32_t disc = ((tr_2 * tr_2) - det) + std::numeric_limits<float32_t>::epsilon();
108  if (disc < 0.0F) {
109  throw std::runtime_error(
110  "pca_2d: negative discriminant! Should never happen for well formed "
111  "covariance matrix");
112  }
113  disc = sqrtf(disc);
114  // compute eigenvalues
115  const auto ret = std::make_pair(tr_2 + disc, tr_2 - disc);
116  // compute eigenvectors
117  using point_adapter::xr_;
118  using point_adapter::yr_;
119  // We compare squared value against floating epsilon to make sure that eigen vectors
120  // are persistent against further calculations.
121  // (e.g. taking cross product of two eigen vectors)
122  if (fabsf(cov.xy * cov.xy) > std::numeric_limits<float32_t>::epsilon()) {
123  xr_(eigvec1) = cov.xy;
124  yr_(eigvec1) = ret.first - cov.xx;
125  xr_(eigvec2) = cov.xy;
126  yr_(eigvec2) = ret.second - cov.xx;
127  } else {
128  if (cov.xx > cov.yy) {
129  xr_(eigvec1) = 1.0F;
130  yr_(eigvec1) = 0.0F;
131  xr_(eigvec2) = 0.0F;
132  yr_(eigvec2) = 1.0F;
133  } else {
134  xr_(eigvec1) = 0.0F;
135  yr_(eigvec1) = 1.0F;
136  xr_(eigvec2) = 1.0F;
137  yr_(eigvec2) = 0.0F;
138  }
139  }
140  return ret;
141 }
142 
143 
154 template<typename IT, typename PointT>
156  const IT begin,
157  const IT end,
158  const PointT & eig1,
159  const PointT & eig2,
160  Point4<IT> & support)
161 {
162  const bool8_t ret = cross_2d(eig1, eig2) >= 0.0F;
163  std::array<float32_t, 4U> metrics{{
164  -std::numeric_limits<float32_t>::max(),
165  -std::numeric_limits<float32_t>::max(),
166  std::numeric_limits<float32_t>::max(),
167  std::numeric_limits<float32_t>::max()
168  }};
169  for (auto it = begin; it != end; ++it) {
170  const PointT & pt = *it;
171  float32_t val = dot_2d(ret ? eig1 : eig2, pt);
172  if (val > metrics[0U]) {
173  metrics[0U] = val;
174  support[0U] = it;
175  }
176  if (val < metrics[2U]) {
177  metrics[2U] = val;
178  support[2U] = it;
179  }
180  val = dot_2d(ret ? eig2 : eig1, pt);
181  if (val > metrics[1U]) {
182  metrics[1U] = val;
183  support[1U] = it;
184  }
185  if (val < metrics[3U]) {
186  metrics[3U] = val;
187  support[3U] = it;
188  }
189  }
190  return ret;
191 }
192 
201 template<typename IT, typename PointT>
203  const PointT & ax1,
204  const PointT & ax2,
205  const Point4<IT> & supports)
206 {
207  decltype(BoundingBox::corners) corners;
208  const Point4<PointT> directions{{ax1, ax2, minus_2d(ax1), minus_2d(ax2)}};
209  compute_corners(corners, supports, directions);
210 
211  // build box
212  BoundingBox bbox;
213  finalize_box(corners, bbox);
214  size_2d(corners, bbox.size);
215  return bbox;
216 }
217 } // namespace details
218 
225 template<typename IT>
226 BoundingBox eigenbox_2d(const IT begin, const IT end)
227 {
228  // compute covariance
230 
231  // compute eigenvectors
232  using PointT = details::base_type<decltype(*begin)>;
233  PointT eig1;
234  PointT eig2;
235  const auto eigv = details::eig_2d(cov, eig1, eig2);
236 
237  // find extreme points
238  details::Point4<IT> supports;
239  const bool8_t is_ccw = details::compute_supports(begin, end, eig1, eig2, supports);
240  // build box
241  if (is_ccw) {
242  std::swap(eig1, eig2);
243  }
244  BoundingBox bbox = details::compute_bounding_box(eig1, eig2, supports);
245  bbox.value = eigv.first;
246 
247  return bbox;
248 }
249 } // namespace bounding_box
250 } // namespace geometry
251 } // namespace common
252 } // namespace autoware
253 
254 #endif // GEOMETRY__BOUNDING_BOX__EIGENBOX_2D_HPP_
autoware::common::geometry::bounding_box::details::compute_supports
bool8_t compute_supports(const IT begin, const IT end, const PointT &eig1, const PointT &eig2, Point4< IT > &support)
Given eigenvectors, compute support (furthest) point in each direction.
Definition: eigenbox_2d.hpp:155
autoware::common::geometry::bounding_box::BoundingBox
autoware_auto_msgs::msg::BoundingBox BoundingBox
Definition: bounding_box_common.hpp:38
autoware::common::geometry::cross_2d
auto cross_2d(const T1 &pt, const T2 &q)
compute p x q = p1 * q2 - p2 * q1
Definition: common_2d.hpp:134
autoware::common::geometry::point_adapter::x_
auto x_(const PointT &pt)
Gets the x value for a point.
Definition: common_2d.hpp:47
autoware::common::geometry::bounding_box::details::Covariance2d::xy
float32_t xy
x-y covariance
Definition: eigenbox_2d.hpp:47
autoware::common::geometry::bounding_box::details::compute_corners
void compute_corners(decltype(BoundingBox::corners) &corners, const Point4< IT > &supports, const Point4< PointT > &directions)
given support points and two orthogonal directions, compute corners of bounding box
Definition: bounding_box_common.hpp:111
catr_diff.dx
dx
Definition: catr_diff.py:38
autoware::common::geometry::bounding_box::details::Covariance2d::yy
float32_t yy
Variance in the y direction.
Definition: eigenbox_2d.hpp:45
autoware::common::geometry::dot_2d
auto dot_2d(const T1 &pt, const T2 &q)
compute p * q = p1 * q1 + p2 * q2
Definition: common_2d.hpp:147
autoware::common::types::bool8_t
bool bool8_t
Definition: types.hpp:39
autoware::common::geometry::bounding_box::eigenbox_2d
BoundingBox eigenbox_2d(const IT begin, const IT end)
Compute oriented bounding box using PCA. This uses all points in a list, and does not modify the list...
Definition: eigenbox_2d.hpp:226
autoware::common::geometry::bounding_box::details::compute_bounding_box
BoundingBox compute_bounding_box(const PointT &ax1, const PointT &ax2, const Point4< IT > &supports)
Compute bounding box given a pair of basis directions.
Definition: eigenbox_2d.hpp:202
autoware
This file defines the lanelet2_map_provider_node class.
Definition: quick_sort.hpp:24
autoware::common::geometry::point_adapter::yr_
auto & yr_(PointT &pt)
Gets a reference to the y value for a point.
Definition: common_2d.hpp:83
autoware::common::geometry::bounding_box::details::Covariance2d::xx
float32_t xx
Variance in the x direction.
Definition: eigenbox_2d.hpp:43
bounding_box_common.hpp
Common functionality for bounding box computation algorithms.
autoware::common::types::float32_t
float float32_t
Definition: types.hpp:45
autoware::common::geometry::point_adapter::xr_
auto & xr_(PointT &pt)
Gets a reference to the x value for a point.
Definition: common_2d.hpp:74
autoware::common::geometry::bounding_box::details::covariance_2d
Covariance2d covariance_2d(const IT begin, const IT end)
Compute 2d covariance matrix of a list of points using Welford's online algorithm.
Definition: eigenbox_2d.hpp:58
autoware::common::geometry::minus_2d
T minus_2d(const T &p, const T &q)
Compute the 2d difference between two points, p - q.
Definition: common_2d.hpp:161
autoware::common::geometry::bounding_box::details::Covariance2d
Simplified 2d covariance matrix.
Definition: eigenbox_2d.hpp:40
autoware::common::geometry::bounding_box::details::Covariance2d::num_points
std::size_t num_points
Number of points.
Definition: eigenbox_2d.hpp:49
autoware::common::geometry::bounding_box::details::eig_2d
std::pair< float32_t, float32_t > eig_2d(const Covariance2d &cov, PointT &eigvec1, PointT &eigvec2)
Compute eigenvectors and eigenvalues.
Definition: eigenbox_2d.hpp:101
autoware::common::geometry::point_adapter::y_
auto y_(const PointT &pt)
Gets the y value for a point.
Definition: common_2d.hpp:56
autoware::common::geometry::bounding_box::details::base_type
typename std::remove_cv< typename std::remove_reference< T >::type >::type base_type
Templated alias for getting a type without CV or reference qualification.
Definition: bounding_box_common.hpp:72
autoware::common::geometry::bounding_box::details::size_2d
void GEOMETRY_PUBLIC size_2d(const decltype(BoundingBox::corners) &corners, geometry_msgs::msg::Point32 &ret)
Compute length, width, area of bounding box.
Definition: bounding_box.cpp:39
autoware::common::geometry::bounding_box::details::Point4
std::array< PointT, 4U > Point4
Templated alias for an array of 4 objects of type PointT.
Definition: bounding_box_common.hpp:76
autoware::common::geometry::bounding_box::details::finalize_box
void GEOMETRY_PUBLIC finalize_box(const decltype(BoundingBox::corners) &corners, BoundingBox &box)
Computes centroid and orientation of a box given corners.
Definition: bounding_box.cpp:55
catr_diff.dy
dy
Definition: catr_diff.py:39
get_open_port.end
end
Definition: scripts/get_open_port.py:23