geometry/BoundingBox.h
Go to the documentation of this file.
1 #pragma once
2 #include <boost/geometry/geometries/register/box.hpp>
3 
6 
7 // registrations for use with boost::geometry
8 BOOST_GEOMETRY_REGISTER_BOX(lanelet::BoundingBox2d, lanelet::BasicPoint2d, min(), max())
9 BOOST_GEOMETRY_REGISTER_BOX(lanelet::BoundingBox3d, lanelet::BasicPoint3d, min(), max())
10 
11 namespace lanelet {
12 namespace geometry {
17 inline BoundingBox2d boundingBox2d(const BoundingBox2d& b) { return b; }
18 inline BoundingBox3d boundingBox3d(const BoundingBox2d& b) { return traits::to3D(b); }
19 
24 inline BoundingBox3d boundingBox3d(const BoundingBox3d& b) { return b; }
25 inline BoundingBox2d boundingBox2d(const BoundingBox3d& b) { return traits::to2D(b); }
26 
32 inline BoundingBox2d boundingBox2d(const ConstPoint2d& p) { return {p.basicPoint2d(), p.basicPoint2d()}; }
33 inline BoundingBox2d boundingBox2d(const ConstPoint3d& p) { return {p.basicPoint2d(), p.basicPoint2d()}; }
34 inline BoundingBox2d boundingBox2d(const BasicPoint2d& p) { return {p, p}; }
35 inline BoundingBox2d boundingBox2d(const BasicPoint3d& p) { return {traits::to2D(p), traits::to2D(p)}; }
36 
42 inline BoundingBox3d boundingBox3d(const ConstPoint3d& p) { return BoundingBox3d(p.basicPoint(), p.basicPoint()); }
43 inline BoundingBox3d boundingBox3d(const ConstPoint2d& p) { return boundingBox3d(utils::to3D(p)); }
44 inline BoundingBox3d boundingBox3d(const BasicPoint3d& p) { return {p, p}; }
45 inline BoundingBox3d boundingBox3d(const BasicPoint2d& p) { return {traits::to3D(p), traits::to3D(p)}; }
46 } // namespace geometry
47 } // namespace lanelet
BasicPoint p
Eigen::Vector3d BasicPoint3d
a simple 3d-point
Eigen::AlignedBox3d BoundingBox3d
Convenience type for an axis aligned bounding box in 3d.
IfAr< AreaT, BoundingBox2d > boundingBox2d(const AreaT &area)
calculates an up-right 2d bounding box
Axis-Aligned bounding box in 2d.
Eigen::Matrix< double, 2, 1, Eigen::DontAlign > BasicPoint2d
a simple 2d-point
BoundingBox2d to2D(const BoundingBox3d &primitive)
BoundingBox3d to3D(const BoundingBox2d &primitive)
IfAr< AreaT, BoundingBox3d > boundingBox3d(const AreaT &area)
calculates 3d bounding box


lanelet2_core
Author(s): Fabian Poggenhans
autogenerated on Tue Jun 6 2023 02:23:32