|
Autoware.Auto
|
|
Classes | |
| struct | array_size |
| Helper struct for compile time introspection of array size from stackoverflow.com/questions/16866033/getting-the-number-of-elements-in-stdarray-at-compile-time. More... | |
| struct | array_size< std::array< T, N > > |
| struct | Covariance2d |
| Simplified 2d covariance matrix. More... | |
| class | LFitCompare |
| struct | LFitWs |
| A representation of the M matrix for the L-fit algorithm. More... | |
Typedefs | |
| template<typename T > | |
| using | base_type = typename std::remove_cv< typename std::remove_reference< T >::type >::type |
| Templated alias for getting a type without CV or reference qualification. More... | |
| template<typename PointT > | |
| using | Point4 = std::array< PointT, 4U > |
| Templated alias for an array of 4 objects of type PointT. More... | |
Functions | |
| void GEOMETRY_PUBLIC | size_2d (const decltype(BoundingBox::corners) &corners, geometry_msgs::msg::Point32 &ret) |
| Compute length, width, area of bounding box. More... | |
| void GEOMETRY_PUBLIC | finalize_box (const decltype(BoundingBox::corners) &corners, BoundingBox &box) |
| Computes centroid and orientation of a box given corners. More... | |
| template<typename IT , typename PointT > | |
| 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 More... | |
| template<typename IT > | |
| Covariance2d | covariance_2d (const IT begin, const IT end) |
| Compute 2d covariance matrix of a list of points using Welford's online algorithm. More... | |
| template<typename PointT > | |
| std::pair< float32_t, float32_t > | eig_2d (const Covariance2d &cov, PointT &eigvec1, PointT &eigvec2) |
| Compute eigenvectors and eigenvalues. More... | |
| template<typename IT , typename PointT > | |
| 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. More... | |
| template<typename IT , typename PointT > | |
| BoundingBox | compute_bounding_box (const PointT &ax1, const PointT &ax2, const Point4< IT > &supports) |
| Compute bounding box given a pair of basis directions. More... | |
| template<typename IT > | |
| void | init_lfit_ws (const IT begin, const IT end, const std::size_t size, LFitWs &ws) |
| Initialize M matrix for L-fit algorithm. More... | |
| template<typename PointT > | |
| float32_t | solve_lfit (const LFitWs &ws, PointT &dir) |
| Solves the L fit problem for a given M matrix. More... | |
| template<typename PointT > | |
| void | increment_lfit_ws (const PointT &pt, LFitWs &ws) |
| Increments L fit M matrix with information in the point. More... | |
| template<typename IT > | |
| 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, large enough, and appropriately ordered point list. More... | |
| template<typename PointT > | |
| uint32_t | update_angles (const Point4< PointT > &edges, Point4< PointT > &directions) |
| Find which (next) edge has smallest angle delta to directions, rotate directions. More... | |
| template<typename IT , typename PointT > | |
| void | init_edges (const IT begin, const IT end, const Point4< IT > &support, Point4< PointT > &edges) |
| Given support points i, find direction of edge: e = P[i+1] - P[i]. More... | |
| template<typename IT > | |
| void | init_bbox (const IT begin, const IT end, Point4< IT > &support) |
| Scan through list to find support points for bounding box oriented in direction of u = P[1] - P[0]. More... | |
| template<typename IT , typename MetricF > | |
| BoundingBox | rotating_calipers_impl (const IT begin, const IT end, const MetricF metric_fn) |
| Compute the minimum bounding box for a convex hull using the rotating calipers method. This function may possibly also be used for computing the width of a convex hull, as it uses the external supports of a single convex hull. More... | |
| using autoware::common::geometry::bounding_box::details::base_type = typedef typename std::remove_cv<typename std::remove_reference<T>::type>::type |
Templated alias for getting a type without CV or reference qualification.
| using autoware::common::geometry::bounding_box::details::Point4 = typedef std::array<PointT, 4U> |
Templated alias for an array of 4 objects of type PointT.
| BoundingBox autoware::common::geometry::bounding_box::details::compute_bounding_box | ( | const PointT & | ax1, |
| const PointT & | ax2, | ||
| const Point4< IT > & | supports | ||
| ) |
Compute bounding box given a pair of basis directions.
| IT | An iterator type dereferencable into a point with float members x and y |
| PointT | Point type of the lists, must have float members x and y |
| [in] | ax1 | First basis direction, assumed to be normal to ax2 |
| [in] | ax2 | Second basis direction, assumed to be normal to ax1, assumed to be ccw wrt ax1 |
| [in] | supports | Array of iterators referring to points that are most extreme in each basis direction. Should be result of compute_supports function |
| void autoware::common::geometry::bounding_box::details::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
| PointT | Type of a point, must have float members x and y` |
| IT | An iterator dereferencable into PointT |
| [out] | corners | Gets filled with corner points of bounding box |
| [in] | supports | Iterators referring to support points of current bounding box e.g. bounding box is touching these points |
| [in] | directions | Directions of each edge of the bounding box from each support point |
| bool8_t autoware::common::geometry::bounding_box::details::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.
| IT | An iterator type dereferencable into a point with float members x and y |
| PointT | type of a point with float members x and y |
| [in] | begin | An iterator pointing to the first point in a point list |
| [in] | end | An iterator pointing to one past the last point in the point list |
| [in] | eig1 | First principal component of cluster |
| [in] | eig2 | Second principal component of cluster |
| [out] | support | Array to get filled with extreme points in each of the principal components |
| Covariance2d autoware::common::geometry::bounding_box::details::covariance_2d | ( | const IT | begin, |
| const IT | end | ||
| ) |
Compute 2d covariance matrix of a list of points using Welford's online algorithm.
| [in] | begin | An iterator pointing to the first point in a point list |
| [in] | end | An iterator pointing to one past the last point in the point list |
| IT | An iterator type dereferencable into a point with float members x and y |
| std::pair<float32_t, float32_t> autoware::common::geometry::bounding_box::details::eig_2d | ( | const Covariance2d & | cov, |
| PointT & | eigvec1, | ||
| PointT & | eigvec2 | ||
| ) |
Compute eigenvectors and eigenvalues.
| [in] | cov | 2d Covariance matrix |
| [out] | eigvec1 | First eigenvector |
| [out] | eigvec2 | Second eigenvector |
| PointT | Point type that has at least float members x and y |
| std::runtime | error if you would get degenerate covariance |
| void autoware::common::geometry::bounding_box::details::finalize_box | ( | const decltype(BoundingBox::corners) & | corners, |
| BoundingBox & | box | ||
| ) |
Computes centroid and orientation of a box given corners.
| [in] | corners | Array of final corners of bounding box |
| [out] | box | Message to have corners, orientation, and centroid updated |
| void autoware::common::geometry::bounding_box::details::increment_lfit_ws | ( | const PointT & | pt, |
| LFitWs & | ws | ||
| ) |
Increments L fit M matrix with information in the point.
| PointT | The point type |
| [in] | pt | The point to increment the M matrix with |
| [in,out] | ws | A representation of the M matrix |
| void autoware::common::geometry::bounding_box::details::init_bbox | ( | const IT | begin, |
| const IT | end, | ||
| Point4< IT > & | support | ||
| ) |
Scan through list to find support points for bounding box oriented in direction of u = P[1] - P[0].
| IT | The iterator type, should dereference to a point type with float members x and y |
| [in] | begin | An iterator pointing to the first point in a point list |
| [in] | end | An iterator pointing to one past the last point in the point list |
| [out] | support | Array that gets filled with pointers to points that are most extreme in each direction aligned with and orthogonal to the first polygon edge. Most extreme = max/min wrt u = P[1]-P0 |
| void autoware::common::geometry::bounding_box::details::init_edges | ( | const IT | begin, |
| const IT | end, | ||
| const Point4< IT > & | support, | ||
| Point4< PointT > & | edges | ||
| ) |
Given support points i, find direction of edge: e = P[i+1] - P[i].
| PointT | Point type of the lists, must have float members x and y |
| IT | The iterator type, should dereference to a point type with float members x and y |
| [in] | begin | An iterator pointing to the first point in a point list |
| [in] | end | An iterator pointing to one past the last point in the point list |
| [in] | support | Array of points that are most extreme in 4 directions for current OBB |
| [out] | edges | An array to be filled with the polygon edges next from support points |
| void autoware::common::geometry::bounding_box::details::init_lfit_ws | ( | const IT | begin, |
| const IT | end, | ||
| const std::size_t | size, | ||
| LFitWs & | ws | ||
| ) |
Initialize M matrix for L-fit algorithm.
| [in] | begin | An iterator pointing to the first point in a point list |
| [in] | end | An iterator one past the last point in the point list |
| [in] | size | The number of points in the point list |
| [out] | ws | A representation of the M matrix to get initialized |
| IT | The iterator type, should dereference to a point type with float members x and y |
| BoundingBox autoware::common::geometry::bounding_box::details::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, large enough, and appropriately ordered point list.
| [in] | begin | An iterator pointing to the first point in a point list |
| [in] | end | An iterator pointing to one past the last point in the point list |
| [in] | size | The number of points in the point list |
| IT | An iterator type dereferencable into a point with float members x and y |
| BoundingBox autoware::common::geometry::bounding_box::details::rotating_calipers_impl | ( | const IT | begin, |
| const IT | end, | ||
| const MetricF | metric_fn | ||
| ) |
Compute the minimum bounding box for a convex hull using the rotating calipers method. This function may possibly also be used for computing the width of a convex hull, as it uses the external supports of a single convex hull.
| [in] | begin | An iterator to the first point on a convex hull |
| [in] | end | An iterator to one past the last point on a convex hull |
| [in] | metric_fn | A functor determining what measure the bounding box is minimum with respect to |
| IT | An iterator type dereferencable into a point type with float members x and y |
| MetricF | A functor that computes a float measure from the x and y size (width and length) of a bounding box, assumed to be packed in a Point32 message. |
| std::domain_error | if the list of points is too small to reasonable generate a bounding box |
| void autoware::common::geometry::bounding_box::details::size_2d | ( | const decltype(BoundingBox::corners) & | corners, |
| geometry_msgs::msg::Point32 & | ret | ||
| ) |
Compute length, width, area of bounding box.
| [in] | corners | Corners of the current bounding box |
| [out] | ret | A point struct used to hold size of box defined by corners |
| float32_t autoware::common::geometry::bounding_box::details::solve_lfit | ( | const LFitWs & | ws, |
| PointT & | dir | ||
| ) |
Solves the L fit problem for a given M matrix.
| PointT | The point type of the cluster being L-fitted |
| [in] | ws | A representation of the M Matrix |
| [out] | dir | The best fit direction for this partition/M matrix |
| uint32_t autoware::common::geometry::bounding_box::details::update_angles | ( | const Point4< PointT > & | edges, |
| Point4< PointT > & | directions | ||
| ) |
Find which (next) edge has smallest angle delta to directions, rotate directions.
| [in,out] | edges | Array of edges on polygon after each anchor point (in ccw order). E.g. if anchor point = p_i, edge = P[i+1] - P[i] |
| [in,out] | directions | Array of directions of current bounding box (in ccw order) |
| PointT | Point type of the lists, must have float members x and y |