Go to the documentation of this file.
21 #ifndef GEOMETRY__BOUNDING_BOX__LFIT_HPP_
22 #define GEOMETRY__BOUNDING_BOX__LFIT_HPP_
34 namespace bounding_box
78 const auto & pt = *begin;
92 for (; it !=
end; ++it) {
93 const auto & qt = *it;
109 template<
typename Po
intT>
121 const auto eigv =
eig_2d(M, eig1, dir);
129 template<
typename Po
intT>
138 ws.
m22b += 2.0F * px * py;
139 const float32_t px2y2 = (px - py) * (px + py);
145 template<
typename Po
intT>
153 : m_nx(point_adapter::
x_(hint)),
154 m_ny(point_adapter::
y_(hint))
167 return ((
x_(p) * m_nx) + (
y_(p) * m_ny)) < ((
x_(q) * m_nx) + (
y_(q) * m_ny));
182 template<
typename IT>
194 for (; it !=
end; ++it) {
203 decltype(best_normal) dir;
206 if (score < min_eig) {
212 const auto inorm = 1.0F /
norm_2d(best_normal);
213 if (!std::isnormal(inorm)) {
214 throw std::runtime_error{
"LFit: Abnormal norm"};
216 best_normal =
times_2d(best_normal, inorm);
222 std::swap(best_normal, best_tangent);
225 bbox.value = min_eig;
242 template<
typename IT,
typename Po
intT>
247 const std::size_t size)
250 throw std::domain_error(
"LFit requires >= 2 points!");
267 template<
typename IT>
284 #endif // GEOMETRY__BOUNDING_BOX__LFIT_HPP_
LFitCompare(const PointT &hint)
Constructor, initializes normal direction.
Definition: lfit.hpp:152
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
T times_2d(const T &p, const float32_t a)
The scalar multiplication operation, p * a.
Definition: common_2d.hpp:192
void init_lfit_ws(const IT begin, const IT end, const std::size_t size, LFitWs &ws)
Initialize M matrix for L-fit algorithm.
Definition: lfit.hpp:71
autoware_auto_msgs::msg::BoundingBox BoundingBox
Definition: bounding_box_common.hpp:38
T get_normal(const T &pt)
compute q s.t. p T q, or p * q = 0 This is the equivalent of a 90 degree ccw rotation
Definition: common_2d.hpp:265
float32_t m12b
Sum of y values in first partition.
Definition: lfit.hpp:50
auto x_(const PointT &pt)
Gets the x value for a point.
Definition: common_2d.hpp:47
This file implements 2D pca on a linked list of points to estimate an oriented bounding box.
float32_t m22a
Sum_p x_2 + sum_q y_2.
Definition: lfit.hpp:57
bool bool8_t
Definition: types.hpp:33
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
float32_t solve_lfit(const LFitWs &ws, PointT &dir)
Solves the L fit problem for a given M matrix.
Definition: lfit.hpp:110
This file defines the lanelet2_map_provider_node class.
Definition: quick_sort.hpp:24
float32_t m22b
Sum_p x*y - sum_q x*y.
Definition: lfit.hpp:59
auto norm_2d(const T &pt)
get magnitude of x and y components:
Definition: common_2d.hpp:278
std::size_t p
Number of points in the first partition.
Definition: lfit.hpp:43
BoundingBox lfit_bounding_box_2d_impl(const IT begin, const IT end, const std::size_t size)
The main implementation of L-fitting a bounding box to a list of points. Assumes sufficiently valid,...
Definition: lfit.hpp:183
float float32_t
Definition: types.hpp:36
float32_t m22d
Sum_p y_2 + sum_x y_2.
Definition: lfit.hpp:61
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
bool8_t operator()(const PointT &p, const PointT &q) const
Comparator operation, returns true if the projection of a the tangent line is smaller than the projec...
Definition: lfit.hpp:163
Simplified 2d covariance matrix.
Definition: eigenbox_2d.hpp:40
std::pair< float32_t, float32_t > eig_2d(const Covariance2d &cov, PointT &eigvec1, PointT &eigvec2)
Compute eigenvectors and eigenvalues.
Definition: eigenbox_2d.hpp:101
auto y_(const PointT &pt)
Gets the y value for a point.
Definition: common_2d.hpp:56
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
void increment_lfit_ws(const PointT &pt, LFitWs &ws)
Increments L fit M matrix with information in the point.
Definition: lfit.hpp:130
float32_t m12c
Sum of y values in second partition.
Definition: lfit.hpp:52
std::array< PointT, 4U > Point4
Templated alias for an array of 4 objects of type PointT.
Definition: bounding_box_common.hpp:76
float32_t m12d
Negative sum of x values in second partition.
Definition: lfit.hpp:54
std::size_t q
Number of points in the second partition.
Definition: lfit.hpp:45
end
Definition: scripts/get_open_port.py:23
float32_t m12a
Sum of x values in first partition.
Definition: lfit.hpp:48
BoundingBox lfit_bounding_box_2d(const IT begin, const IT end, const PointT hint, const std::size_t size)
Compute bounding box which best fits an L-shaped cluster. Uses the method proposed in "Efficient L-sh...
Definition: lfit.hpp:243
A representation of the M matrix for the L-fit algorithm.
Definition: lfit.hpp:40