scenario_simulator_v2 C++ API
Classes | Namespaces | Typedefs | Functions
bounding_box.hpp File Reference
#include <boost/assert.hpp>
#include <boost/assign/list_of.hpp>
#include <boost/geometry.hpp>
#include <boost/geometry/algorithms/disjoint.hpp>
#include <boost/geometry/geometries/linestring.hpp>
#include <boost/geometry/geometries/point_xy.hpp>
#include <boost/numeric/conversion/bounds.hpp>
#include <geometry/transform.hpp>
#include <geometry_msgs/msg/pose.hpp>
#include <optional>
#include <traffic_simulator_msgs/msg/bounding_box.hpp>
#include <vector>
Include dependency graph for bounding_box.hpp:
This graph shows which files directly or indirectly include this file:

Go to the source code of this file.

Classes

struct  math::geometry::DistancesFromCenterToEdge
 

Namespaces

 math
 
 math::geometry
 

Typedefs

typedef boost::geometry::model::d2::point_xy< double > math::geometry::boost_point
 
typedef boost::geometry::model::polygon< boost_point > math::geometry::boost_polygon
 

Functions

std::optional< double > math::geometry::getPolygonDistance (const geometry_msgs::msg::Pose &pose0, const traffic_simulator_msgs::msg::BoundingBox &bbox0, const geometry_msgs::msg::Pose &pose1, const traffic_simulator_msgs::msg::BoundingBox &bbox1)
 Get the Polygon Distance object. More...
 
std::optional< std::pair< geometry_msgs::msg::Pose, geometry_msgs::msg::Pose > > math::geometry::getClosestPoses (const geometry_msgs::msg::Pose &pose0, const traffic_simulator_msgs::msg::BoundingBox &bbox0, const geometry_msgs::msg::Pose &pose1, const traffic_simulator_msgs::msg::BoundingBox &bbox1)
 
boost_point math::geometry::pointToSegmentProjection (const boost_point &p, const boost_point &p1, const boost_point &p2)
 
boost_point math::geometry::toBoostPoint (const geometry_msgs::msg::Point &point)
 
boost_polygon math::geometry::toBoostPolygon (const std::vector< geometry_msgs::msg::Point > &points)
 
geometry_msgs::msg::Pose math::geometry::toPose (const boost_point &point)
 
geometry_msgs::msg::Pose math::geometry::subtractPoses (const geometry_msgs::msg::Pose &pose1, const geometry_msgs::msg::Pose &pose2)
 
auto math::geometry::toPolygon2D (const traffic_simulator_msgs::msg::BoundingBox &bounding_box) -> std::vector< geometry_msgs::msg::Point >
 
auto math::geometry::toPolygon2D (const geometry_msgs::msg::Pose &pose, const traffic_simulator_msgs::msg::BoundingBox &bounding_box) -> const boost_polygon
 
std::vector< geometry_msgs::msg::Point > math::geometry::getPointsFromBbox (traffic_simulator_msgs::msg::BoundingBox bounding_box, double width_extension_right=0.0, double width_extension_left=0.0, double length_extension_front=0.0, double length_extension_rear=0.0)
 
DistancesFromCenterToEdge math::geometry::getDistancesFromCenterToEdge (const traffic_simulator_msgs::msg::BoundingBox &bounding_box)