|
Autoware.Auto
|
|
Functions and types for generating enclosing bounding boxes around a set of points. More...
Namespaces | |
| details | |
Typedefs | |
| using | BoundingBox = autoware_auto_msgs::msg::BoundingBox |
| using | PointXYZIFVIT = std::vector< PointXYZIF >::iterator |
| using | Point32VIT = std::vector< Point32 >::iterator |
Functions | |
| template<typename IT > | |
| void | compute_height (const IT begin, const IT end, BoundingBox &box) |
| Computes height of bounding box given a full list of points. More... | |
| template<typename IT > | |
| 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. The resulting bounding box is not necessarily minimum in any way. More... | |
| template<typename IT , typename PointT > | |
| 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-shape fitting of laser scanner data for vehicle pose estimation". More... | |
| template<typename IT > | |
| BoundingBox | lfit_bounding_box_2d (const IT begin, const IT end) |
| Compute bounding box which best fits an L-shaped cluster. Uses the method proposed in "Efficient L-shape fitting of laser scanner data for vehicle pose estimation". This implementation sorts the list using std::sort. More... | |
| template<typename IT > | |
| BoundingBox | minimum_area_bounding_box (const IT begin, const IT end) |
| Compute the minimum area bounding box given a convex hull of points. This function is exposed in case a user might already have a convex hull via other methods. More... | |
| template<typename IT > | |
| BoundingBox | minimum_perimeter_bounding_box (const IT begin, const IT end) |
| Compute the minimum perimeter bounding box given a convex hull of points This function is exposed in case a user might already have a convex hull via other methods. More... | |
| template<typename PointT > | |
| BoundingBox | minimum_area_bounding_box (std::list< PointT > &list) |
| Compute the minimum area bounding box given an unstructured list of points. Only a list is supported as it enables the convex hull to be formed in O(n log n) time and without memory allocation. More... | |
| template<typename PointT > | |
| BoundingBox | minimum_perimeter_bounding_box (std::list< PointT > &list) |
| Compute the minimum perimeter bounding box given an unstructured list of points Only a list is supported as it enables the convex hull to be formed in O(n log n) time and without memory allocation. More... | |
| template BoundingBox | minimum_area_bounding_box< PointXYZIF > (std::list< PointXYZIF > &list) |
| template BoundingBox | minimum_perimeter_bounding_box< PointXYZIF > (std::list< PointXYZIF > &list) |
| template BoundingBox | eigenbox_2d< PointXYZIFVIT > (const PointXYZIFVIT begin, const PointXYZIFVIT end) |
| template BoundingBox | lfit_bounding_box_2d< PointXYZIFVIT > (const PointXYZIFVIT begin, const PointXYZIFVIT end) |
| template BoundingBox | minimum_area_bounding_box< Point32 > (std::list< Point32 > &list) |
| template BoundingBox | minimum_perimeter_bounding_box< Point32 > (std::list< Point32 > &list) |
| template BoundingBox | eigenbox_2d< Point32VIT > (const Point32VIT begin, const Point32VIT end) |
| template BoundingBox | lfit_bounding_box_2d< Point32VIT > (const Point32VIT begin, const Point32VIT end) |
Functions and types for generating enclosing bounding boxes around a set of points.
| using autoware::common::geometry::bounding_box::BoundingBox = typedef autoware_auto_msgs::msg::BoundingBox |
| using autoware::common::geometry::bounding_box::Point32VIT = typedef std::vector<Point32>::iterator |
| using autoware::common::geometry::bounding_box::PointXYZIFVIT = typedef std::vector<PointXYZIF>::iterator |
| void autoware::common::geometry::bounding_box::compute_height | ( | const IT | begin, |
| const IT | end, | ||
| BoundingBox & | box | ||
| ) |
Computes height of bounding box given a full list of points.
| [in] | begin | The start of the list of points |
| [in] | end | One past the end of the list of points |
| [out] | box | A box for which the z component of centroid, corners, and size gets filled |
| IT | An iterator type, must dereference into a point type with float member z, or appropriate point adapter defined |
| BoundingBox autoware::common::geometry::bounding_box::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. The resulting bounding box is not necessarily minimum in any way.
| [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 |
| template BoundingBox autoware::common::geometry::bounding_box::eigenbox_2d< Point32VIT > | ( | const Point32VIT | begin, |
| const Point32VIT | end | ||
| ) |
| template BoundingBox autoware::common::geometry::bounding_box::eigenbox_2d< PointXYZIFVIT > | ( | const PointXYZIFVIT | begin, |
| const PointXYZIFVIT | end | ||
| ) |
| BoundingBox autoware::common::geometry::bounding_box::lfit_bounding_box_2d | ( | const IT | begin, |
| const IT | end | ||
| ) |
Compute bounding box which best fits an L-shaped cluster. Uses the method proposed in "Efficient L-shape fitting of laser scanner data for vehicle pose estimation". This implementation sorts the list using std::sort.
| [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 |
| BoundingBox autoware::common::geometry::bounding_box::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-shape fitting of laser scanner data for vehicle pose estimation".
| [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 |
| [in] | hint | An iterator pointing to the point whose normal will be used to sort the list |
| IT | An iterator type dereferencable into a point with float members x and y |
| std::domain_error | If the number of points is too few |
| template BoundingBox autoware::common::geometry::bounding_box::lfit_bounding_box_2d< Point32VIT > | ( | const Point32VIT | begin, |
| const Point32VIT | end | ||
| ) |
| template BoundingBox autoware::common::geometry::bounding_box::lfit_bounding_box_2d< PointXYZIFVIT > | ( | const PointXYZIFVIT | begin, |
| const PointXYZIFVIT | end | ||
| ) |
| BoundingBox autoware::common::geometry::bounding_box::minimum_area_bounding_box | ( | const IT | begin, |
| const IT | end | ||
| ) |
Compute the minimum area bounding box given a convex hull of points. This function is exposed in case a user might already have a convex hull via other methods.
| [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 |
| IT | An iterator type dereferencable into a point type with float members x and y |
| BoundingBox autoware::common::geometry::bounding_box::minimum_area_bounding_box | ( | std::list< PointT > & | list | ) |
Compute the minimum area bounding box given an unstructured list of points. Only a list is supported as it enables the convex hull to be formed in O(n log n) time and without memory allocation.
| [in,out] | list | A list of points to form a hull around, gets reordered |
| PointT | Point type of the lists, must have float members x and y |
| template BoundingBox autoware::common::geometry::bounding_box::minimum_area_bounding_box< Point32 > | ( | std::list< Point32 > & | list | ) |
| template BoundingBox autoware::common::geometry::bounding_box::minimum_area_bounding_box< PointXYZIF > | ( | std::list< PointXYZIF > & | list | ) |
| BoundingBox autoware::common::geometry::bounding_box::minimum_perimeter_bounding_box | ( | const IT | begin, |
| const IT | end | ||
| ) |
Compute the minimum perimeter bounding box given a convex hull of points This function is exposed in case a user might already have a convex hull via other methods.
| [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 |
| IT | An iterator type dereferencable into a point type with float members x and y |
| BoundingBox autoware::common::geometry::bounding_box::minimum_perimeter_bounding_box | ( | std::list< PointT > & | list | ) |
Compute the minimum perimeter bounding box given an unstructured list of points Only a list is supported as it enables the convex hull to be formed in O(n log n) time and without memory allocation.
| [in,out] | list | A list of points to form a hull around, gets reordered |
| PointT | Point type of the lists, must have float members x and y |
| template BoundingBox autoware::common::geometry::bounding_box::minimum_perimeter_bounding_box< Point32 > | ( | std::list< Point32 > & | list | ) |
| template BoundingBox autoware::common::geometry::bounding_box::minimum_perimeter_bounding_box< PointXYZIF > | ( | std::list< PointXYZIF > & | list | ) |