Go to the documentation of this file.
20 #ifndef GEOMETRY__BOUNDING_BOX__BOUNDING_BOX_COMMON_HPP_
21 #define GEOMETRY__BOUNDING_BOX__BOUNDING_BOX_COMMON_HPP_
23 #include <autoware_auto_msgs/msg/bounding_box.hpp>
36 namespace bounding_box
49 float32_t max_z = -std::numeric_limits<float32_t>::max();
50 float32_t min_z = std::numeric_limits<float32_t>::max();
51 for (
auto it = begin; it !=
end; ++it) {
60 box.centroid.z = (max_z + min_z) * 0.5F;
61 for (
auto & corner : box.corners) {
62 corner.z = box.centroid.z;
64 box.size.z = (max_z - min_z) * 0.5F;
72 using base_type =
typename std::remove_cv<typename std::remove_reference<T>::type>::type;
75 template<
typename Po
intT>
76 using Point4 = std::array<PointT, 4U>;
82 template<
typename T, std::
size_t N>
85 static std::size_t
const size = N;
89 "Bounding box does not have the right number of corners");
95 const decltype(BoundingBox::corners) & corners,
96 geometry_msgs::msg::Point32 & ret);
101 const decltype(BoundingBox::corners) & corners,
BoundingBox & box);
110 template<
typename IT,
typename Po
intT>
112 decltype(BoundingBox::corners) & corners,
116 for (uint32_t idx = 0U; idx < corners.size(); ++idx) {
117 const uint32_t jdx = (idx != 3U) ? (idx + 1U) : 0U;
119 intersection_2d(*supports[idx], directions[idx], *supports[jdx], directions[jdx]);
133 #endif // GEOMETRY__BOUNDING_BOX__BOUNDING_BOX_COMMON_HPP_
autoware_auto_msgs::msg::BoundingBox BoundingBox
Definition: bounding_box_common.hpp:38
auto x_(const PointT &pt)
Gets the x value for a point.
Definition: common_2d.hpp:47
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
This file includes common functionality for 2D geometry, such as dot products.
This file defines the lanelet2_map_provider_node class.
Definition: quick_sort.hpp:24
auto & yr_(PointT &pt)
Gets a reference to the y value for a point.
Definition: common_2d.hpp:83
float float32_t
Definition: types.hpp:36
auto & xr_(PointT &pt)
Gets a reference to the x value for a point.
Definition: common_2d.hpp:74
autoware_auto_msgs::msg::BoundingBox BoundingBox
Definition: tf2_autoware_auto_msgs.hpp:36
T intersection_2d(const T &pt, const T &u, const T &q, const T &v)
solve p + t * u = q + s * v Ref: https://stackoverflow.com/questions/563198/ whats-the-most-efficent-...
Definition: common_2d.hpp:211
Helper struct for compile time introspection of array size from stackoverflow.com/questions/16866033/...
Definition: bounding_box_common.hpp:81
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 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
std::array< PointT, 4U > Point4
Templated alias for an array of 4 objects of type PointT.
Definition: bounding_box_common.hpp:76
auto z_(const PointT &pt)
Gets the z value for a point.
Definition: common_2d.hpp:65
void compute_height(const IT begin, const IT end, BoundingBox &box)
Computes height of bounding box given a full list of points.
Definition: bounding_box_common.hpp:47
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:47
end
Definition: scripts/get_open_port.py:23