geometry/Area.h
Go to the documentation of this file.
1 #pragma once
2 
6 
7 namespace lanelet {
8 namespace geometry {
15 template <typename AreaT>
16 IfAr<AreaT, bool> inside(const AreaT& area, const BasicPoint2d& point);
17 
25 template <typename AreaT>
26 IfAr<AreaT, BoundingBox2d> boundingBox2d(const AreaT& area);
27 
33 template <typename AreaT>
34 IfAr<AreaT, BoundingBox3d> boundingBox3d(const AreaT& area);
35 
37 template <typename Area1T, typename Area2T>
38 IfAr<Area1T, bool> intersects2d(const Area1T& area, const Area2T& otherArea);
39 
42 template <typename AreaT>
43 IfAr<AreaT, bool> overlaps2d(const AreaT& area, const AreaT& otherArea);
44 
47 template <typename AreaT>
48 IfAr<AreaT, bool> overlaps3d(const AreaT& area, const AreaT& otherArea, double heightTolerance);
49 
52 template <typename AreaT, typename LaneletT>
53 IfAr<AreaT, IfLL<LaneletT, bool>> overlaps2d(const AreaT& area, const LaneletT& lanelet);
54 
57 template <typename AreaT, typename LaneletT>
58 IfAr<AreaT, IfLL<LaneletT, bool>> overlaps3d(const AreaT& area, const LaneletT& lanelet, double heightTolerance);
59 
61 inline bool leftOf(const ConstLanelet& right, const ConstArea& left);
62 
64 inline bool rightOf(const ConstLanelet& left, const ConstArea& area);
65 
67 inline bool follows(const ConstLanelet& prev, const ConstArea& next);
68 
70 inline bool follows(const ConstArea& prev, const ConstLanelet& next);
71 
73 inline bool adjacent(const ConstArea& area1, const ConstArea& area2);
74 
82 
90 
98 
106 
114 
123 
132 
140 
148 } // namespace geometry
149 } // namespace lanelet
150 
151 #include "impl/Area.h"
lanelet::geometry::intersects2d
IfAr< Area1T, bool > intersects2d(const Area1T &area, const Area2T &otherArea)
test whether two areas intersect in 2d.
Definition: geometry/impl/Area.h:35
lanelet::geometry::boundingBox3d
IfAr< AreaT, BoundingBox3d > boundingBox3d(const AreaT &area)
calculates 3d bounding box
Definition: geometry/impl/Area.h:30
lanelet::geometry::determineCommonLineFollowing
Optional< ConstLineString3d > determineCommonLineFollowing(const ConstArea &ar, const ConstLanelet &ll)
Definition: geometry/impl/Area.h:98
lanelet::geometry::follows
bool follows(const ConstLanelet &prev, const ConstArea &next)
Test whether area follows lanelet.
Definition: geometry/impl/Area.h:68
lanelet
Definition: Attribute.h:13
lanelet::geometry::inside
IfAr< AreaT, bool > inside(const AreaT &area, const BasicPoint2d &point)
Checks whether a point is within or at the border of a area.
Definition: geometry/impl/Area.h:20
lanelet::ConstArea
A const (i.e. immutable) Area.
Definition: primitives/Area.h:114
lanelet::geometry::determineCommonLineFollowingOrPreceding
Optional< ConstLineString3d > determineCommonLineFollowingOrPreceding(const ConstArea &ar, const ConstLanelet &ll)
Definition: geometry/impl/Area.h:102
Polygon.h
Area.h
lanelet::geometry::determineCommonLineRight
Optional< ConstLineString3d > determineCommonLineRight(const ConstLanelet &left, const ConstArea &right)
Definition: geometry/impl/Area.h:141
lanelet::Optional
boost::optional< T > Optional
Definition: Optional.h:7
lanelet::geometry::determineCommonLineSideways
Optional< ConstLineString3d > determineCommonLineSideways(const ConstLanelet &ll, const ConstArea &ar)
Definition: geometry/impl/Area.h:110
lanelet::geometry::determineCommonLine
Optional< ConstLineString3d > determineCommonLine(const ConstArea &ar, const ConstLanelet &ll)
Definition: geometry/impl/Area.h:128
lanelet::geometry::overlaps2d
IfAr< AreaT, bool > overlaps2d(const AreaT &area, const AreaT &otherArea)
Definition: geometry/impl/Area.h:43
lanelet::BasicPoint2d
Eigen::Matrix< double, 2, 1, Eigen::DontAlign > BasicPoint2d
a simple 2d-point
Definition: primitives/Point.h:20
lanelet::geometry::overlaps3d
IfAr< AreaT, bool > overlaps3d(const AreaT &area, const AreaT &otherArea, double heightTolerance)
Definition: geometry/impl/Area.h:48
lanelet::geometry::determineCommonLinePreceding
Optional< ConstLineString3d > determineCommonLinePreceding(const ConstLanelet &ll, const ConstArea &ar)
Definition: geometry/impl/Area.h:92
Area.h
lanelet::geometry::boundingBox2d
IfAr< AreaT, BoundingBox2d > boundingBox2d(const AreaT &area)
calculates an up-right 2d bounding box
Definition: geometry/impl/Area.h:25
lanelet::geometry::leftOf
bool leftOf(const ConstLanelet &right, const ConstArea &left)
Test whether area is left of lanelet.
Definition: geometry/impl/Area.h:62
Lanelet.h
lanelet::IfAr
std::enable_if_t< traits::isAreaT< T >(), RetT > IfAr
Definition: primitives/Area.h:364
lanelet::ConstLanelet
An immutable lanelet.
Definition: primitives/Lanelet.h:131
lanelet::geometry::rightOf
bool rightOf(const ConstLanelet &left, const ConstArea &area)
Test whether area is right of lanelet.
Definition: geometry/impl/Area.h:66
lanelet::geometry::determineCommonLineLeft
Optional< ConstLineString3d > determineCommonLineLeft(const ConstLanelet &right, const ConstArea &left)
Definition: geometry/impl/Area.h:133
lanelet::geometry::adjacent
bool adjacent(const ConstArea &area1, const ConstArea &area2)
Test if two areas are adjacent.
Definition: geometry/impl/Area.h:78


lanelet2_core
Author(s): Fabian Poggenhans
autogenerated on Thu Mar 6 2025 03:25:52