15 template <
typename AreaT>
25 template <
typename AreaT>
33 template <
typename AreaT>
37 template <
typename Area1T,
typename Area2T>
42 template <
typename AreaT>
47 template <
typename AreaT>
52 template <
typename AreaT,
typename LaneletT>
57 template <
typename AreaT,
typename LaneletT>
IfAr< Area1T, bool > intersects2d(const Area1T &area, const Area2T &otherArea)
test whether two areas intersect in 2d.
IfAr< AreaT, bool > inside(const AreaT &area, const BasicPoint2d &point)
Checks whether a point is within or at the border of a area.
bool rightOf(const ConstLanelet &left, const ConstArea &area)
Test whether area is right of lanelet.
bool follows(const ConstLanelet &prev, const ConstArea &next)
Test whether area follows lanelet.
Optional< ConstLineString3d > determineCommonLineFollowing(const ConstArea &ar, const ConstLanelet &ll)
Optional< ConstLineString3d > determineCommonLineFollowingOrPreceding(const ConstArea &ar, const ConstLanelet &ll)
IfAr< AreaT, bool > overlaps2d(const AreaT &area, const AreaT &otherArea)
boost::optional< T > Optional
IfAr< AreaT, bool > overlaps3d(const AreaT &area, const AreaT &otherArea, double heightTolerance)
Optional< ConstLineString3d > determineCommonLineSideways(const ConstLanelet &ll, const ConstArea &ar)
Optional< ConstLineString3d > determineCommonLineRight(const ConstLanelet &left, const ConstArea &right)
IfAr< AreaT, BoundingBox2d > boundingBox2d(const AreaT &area)
calculates an up-right 2d bounding box
Optional< ConstLineString3d > determineCommonLinePreceding(const ConstLanelet &ll, const ConstArea &ar)
Optional< ConstLineString3d > determineCommonLine(const ConstArea &ar, const ConstLanelet &ll)
Eigen::Matrix< double, 2, 1, Eigen::DontAlign > BasicPoint2d
a simple 2d-point
A const (i.e. immutable) Area.
Optional< ConstLineString3d > determineCommonLineLeft(const ConstLanelet &right, const ConstArea &left)
bool adjacent(const ConstArea &area1, const ConstArea &area2)
Test if two areas are adjacent.
std::enable_if_t< traits::isAreaT< T >(), RetT > IfAr
bool leftOf(const ConstLanelet &right, const ConstArea &left)
Test whether area is left of lanelet.
IfAr< AreaT, BoundingBox3d > boundingBox3d(const AreaT &area)
calculates 3d bounding box