Autoware.Auto
bounding_box_common.hpp File Reference

Common functionality for bounding box computation algorithms. More...

#include <autoware_auto_perception_msgs/msg/bounding_box.hpp>
#include <autoware_auto_perception_msgs/msg/detected_object.hpp>
#include <autoware_auto_perception_msgs/msg/shape.hpp>
#include <geometry/visibility_control.hpp>
#include <geometry/common_2d.hpp>
#include <geometry_msgs/msg/pose.hpp>
#include <array>
#include <limits>
#include <vector>
Include dependency graph for bounding_box_common.hpp:
This graph shows which files directly or indirectly include this file:

Go to the source code of this file.

Classes

struct  autoware::common::geometry::bounding_box::details::array_size< typename >
 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  autoware::common::geometry::bounding_box::details::array_size< std::array< T, N > >
 

Namespaces

 autoware
 This file defines the lanelet2_map_provider_node class.
 
 autoware::common
 
 autoware::common::geometry
 
 autoware::common::geometry::bounding_box
 Functions and types for generating enclosing bounding boxes around a set of points.
 
 autoware::common::geometry::bounding_box::details
 

Typedefs

using autoware::common::geometry::bounding_box::BoundingBox = autoware_auto_perception_msgs::msg::BoundingBox
 
template<typename T >
using autoware::common::geometry::bounding_box::details::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 autoware::common::geometry::bounding_box::details::Point4 = std::array< PointT, 4U >
 Templated alias for an array of 4 objects of type PointT. More...
 

Functions

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. More...
 
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. More...
 
void GEOMETRY_PUBLIC 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. More...
 
void GEOMETRY_PUBLIC autoware::common::geometry::bounding_box::details::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 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 More...
 
autoware_auto_perception_msgs::msg::Shape GEOMETRY_PUBLIC autoware::common::geometry::bounding_box::details::make_shape (const BoundingBox &box)
 Copy vertices of the given box into a Shape type. More...
 
geometry_msgs::msg::Pose GEOMETRY_PUBLIC autoware::common::geometry::bounding_box::details::make_pose (const BoundingBox &box)
 Copy centroid and orientation info of the box into Pose type. More...
 
autoware_auto_perception_msgs::msg::DetectedObject GEOMETRY_PUBLIC autoware::common::geometry::bounding_box::details::make_detected_object (const BoundingBox &box)
 Fill DetectedObject type with contents from a BoundingBox type. More...
 
std::vector< geometry_msgs::msg::Point32 > GEOMETRY_PUBLIC autoware::common::geometry::bounding_box::details::get_transformed_corners (const autoware_auto_perception_msgs::msg::Shape &shape_msg, const geometry_msgs::msg::Point &centroid, const geometry_msgs::msg::Quaternion &orientation)
 Transform corners from object-local coordinates using the given centroid and orientation. More...
 

Detailed Description

Common functionality for bounding box computation algorithms.