Autoware.Auto
autoware::common::geometry::bounding_box Namespace Reference

Functions and types for generating enclosing bounding boxes around a set of points. More...

Namespaces

 details
 

Typedefs

using BoundingBox = autoware_auto_perception_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 >
void compute_height (const IT begin, const IT end, autoware_auto_perception_msgs::msg::Shape &shape)
 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)
 

Detailed Description

Functions and types for generating enclosing bounding boxes around a set of points.

Typedef Documentation

◆ BoundingBox

using autoware::common::geometry::bounding_box::BoundingBox = typedef autoware_auto_perception_msgs::msg::BoundingBox

◆ Point32VIT

using autoware::common::geometry::bounding_box::Point32VIT = typedef std::vector<Point32>::iterator

◆ PointXYZIFVIT

Function Documentation

◆ compute_height() [1/2]

template<typename IT >
void autoware::common::geometry::bounding_box::compute_height ( const IT  begin,
const IT  end,
autoware_auto_perception_msgs::msg::Shape &  shape 
)

Computes height of bounding box given a full list of points.

Parameters
[in]beginIterator pointing to the start of the range of points
[in]endIterator pointing the the end of the range of points
[out]shapeA shape in which vertices z values and height field will be set
Template Parameters
ITAn iterator type, must dereference into a point type with float member z, or appropriate point adapter defined

◆ compute_height() [2/2]

template<typename IT >
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.

Parameters
[in]beginThe start of the list of points
[in]endOne past the end of the list of points
[out]boxA box for which the z component of centroid, corners, and size gets filled
Template Parameters
ITAn iterator type, must dereference into a point type with float member z, or appropriate point adapter defined

◆ eigenbox_2d()

template<typename IT >
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.

Parameters
[in]beginAn iterator pointing to the first point in a point list
[in]endAn iterator pointing to one past the last point in the point list
Template Parameters
ITAn iterator type dereferencable into a point with float members x and y
Returns
An oriented bounding box in x-y. This bounding box has no height information

◆ eigenbox_2d< Point32VIT >()

◆ eigenbox_2d< PointXYZIFVIT >()

◆ lfit_bounding_box_2d() [1/2]

template<typename IT >
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.

Returns
An oriented bounding box in x-y. This bounding box has no height information
Parameters
[in]beginAn iterator pointing to the first point in a point list
[in]endAn iterator pointing to one past the last point in the point list
Template Parameters
ITAn iterator type dereferencable into a point with float members x and y

◆ lfit_bounding_box_2d() [2/2]

template<typename IT , typename PointT >
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".

Returns
An oriented bounding box in x-y. This bounding box has no height information
Parameters
[in]beginAn iterator pointing to the first point in a point list
[in]endAn iterator pointing to one past the last point in the point list
[in]sizeThe number of points in the point list
[in]hintAn iterator pointing to the point whose normal will be used to sort the list
Returns
A pair where the first element is an iterator pointing to the nearest point, and the second element is the size of the list
Template Parameters
ITAn iterator type dereferencable into a point with float members x and y
Exceptions
std::domain_errorIf the number of points is too few

◆ lfit_bounding_box_2d< Point32VIT >()

◆ lfit_bounding_box_2d< PointXYZIFVIT >()

◆ minimum_area_bounding_box() [1/2]

template<typename IT >
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.

Parameters
[in]beginAn iterator to the first point on a convex hull
[in]endAn iterator to one past the last point on a convex hull
Returns
A minimum area bounding box, value field is the area
Template Parameters
ITAn iterator type dereferencable into a point type with float members x and y

◆ minimum_area_bounding_box() [2/2]

template<typename PointT >
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.

Parameters
[in,out]listA list of points to form a hull around, gets reordered
Returns
A minimum area bounding box, value field is the area
Template Parameters
PointTPoint type of the lists, must have float members x and y

◆ minimum_area_bounding_box< Point32 >()

template BoundingBox autoware::common::geometry::bounding_box::minimum_area_bounding_box< Point32 > ( std::list< Point32 > &  list)

◆ minimum_area_bounding_box< PointXYZIF >()

◆ minimum_perimeter_bounding_box() [1/2]

template<typename IT >
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.

Parameters
[in]beginAn iterator to the first point on a convex hull
[in]endAn iterator to one past the last point on a convex hull
Returns
A minimum perimeter bounding box, value field is half the perimeter
Template Parameters
ITAn iterator type dereferencable into a point type with float members x and y

◆ minimum_perimeter_bounding_box() [2/2]

template<typename PointT >
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.

Parameters
[in,out]listA list of points to form a hull around, gets reordered
Returns
A minimum perimeter bounding box, value field is half the perimeter
Template Parameters
PointTPoint type of the lists, must have float members x and y

◆ minimum_perimeter_bounding_box< Point32 >()

template BoundingBox autoware::common::geometry::bounding_box::minimum_perimeter_bounding_box< Point32 > ( std::list< Point32 > &  list)

◆ minimum_perimeter_bounding_box< PointXYZIF >()