geometry/Lanelet.h
Go to the documentation of this file.
1 #pragma once
2 
4 
5 namespace lanelet {
6 namespace geometry {
13 template <typename LaneletT>
14 IfLL<LaneletT, bool> inside(const LaneletT& lanelet, const BasicPoint2d& point);
15 
21 template <typename LaneletT>
22 double approximatedLength2d(const LaneletT& lanelet);
23 
29 template <typename LaneletT>
30 double length2d(const LaneletT& lanelet);
31 
37 template <typename LaneletT>
38 double length3d(const LaneletT& lanelet);
39 
48 template <typename LaneletT>
49 double distanceToCenterline2d(const LaneletT& lanelet, const BasicPoint2d& point);
50 
61 template <typename LaneletT>
62 double distanceToCenterline3d(const LaneletT& lanelet, const BasicPoint3d& point);
63 
71 template <typename LaneletT>
72 IfLL<LaneletT, BoundingBox2d> boundingBox2d(const LaneletT& lanelet);
73 
79 template <typename LaneletT>
80 IfLL<LaneletT, BoundingBox3d> boundingBox3d(const LaneletT& lanelet);
81 
92 template <typename Lanelet1T, typename Lanelet2T>
93 IfLL<Lanelet1T, bool> intersects2d(const Lanelet1T& lanelet, const Lanelet2T& otherLanelet);
94 
100 template <typename Lanelet1T, typename Lanelet2T>
101 IfLL<Lanelet1T, bool> overlaps2d(const Lanelet1T& lanelet, const Lanelet2T& otherLanelet);
111 template <typename Lanelet1T, typename Lanelet2T>
112 IfLL<Lanelet1T, bool> intersects3d(const Lanelet1T& lanelet, const Lanelet2T& otherLanelet,
113  double heightTolerance = 3.);
114 
121 template <typename Lanelet1T, typename Lanelet2T>
122 IfLL<Lanelet1T, bool> overlaps3d(const Lanelet1T& lanelet, const Lanelet2T& otherLanelet, double heightTolerance = 3);
133 template <typename Lanelet1T, typename Lanelet2T>
134 BasicPoints2d intersectCenterlines2d(const Lanelet1T& lanelet, const Lanelet2T& otherLanelet,
135  std::vector<double>* distanceThis = nullptr,
136  std::vector<double>* distanceOther = nullptr);
137 
145 template <typename Lanelet1T, typename Lanelet2T>
146 IfLL<Lanelet1T, IfLL<Lanelet2T, bool>> leftOf(const Lanelet1T& left, const Lanelet2T& right);
147 
155 template <typename Lanelet1T, typename Lanelet2T>
156 IfLL<Lanelet1T, IfLL<Lanelet2T, bool>> rightOf(const Lanelet1T& right, const Lanelet2T& left);
157 
165 template <typename Lanelet1T, typename Lanelet2T>
166 IfLL<Lanelet1T, IfLL<Lanelet2T, bool>> follows(const Lanelet1T& prev, const Lanelet2T& next);
167 
175 template <typename Lanelet1T, typename Lanelet2T>
176 IfLL<Lanelet1T, IfLL<Lanelet2T, Optional<ConstLineString3d>>> determineCommonLine(const Lanelet1T& ll,
177  const Lanelet2T& other,
178  bool allowInverted = false);
179 
189 template <typename LaneletT>
190 Velocity maxCurveSpeed(const LaneletT& lanelet, const BasicPoint2d& position,
191  const Acceleration& maxLateralAcceleration = 2.0 * units::MPS2());
192 } // namespace geometry
193 } // namespace lanelet
194 
195 #include "impl/Lanelet.h"
std::vector< Eigen::Vector2d, Eigen::aligned_allocator< Eigen::Vector2d > > BasicPoints2d
multiple simple 2d-points
IfLL< Lanelet1T, bool > intersects3d(const Lanelet1T &lanelet, const Lanelet2T &otherLanelet, double heightTolerance)
test whether two lanelets intersect in 2d.
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.
units::MPS2Quantity Acceleration
Definition: Forward.h:211
bool rightOf(const ConstLanelet &left, const ConstArea &area)
Test whether area is right of lanelet.
Eigen::Vector3d BasicPoint3d
a simple 3d-point
double distanceToCenterline3d(const LaneletT &lanelet, const BasicPoint3d &point)
calculates distance in 3d to centerline of a lanelet.
bool follows(const ConstLanelet &prev, const ConstArea &next)
Test whether area follows lanelet.
double distanceToCenterline2d(const LaneletT &lanelet, const BasicPoint2d &point)
calculates distance in 2d to the centerline of a lanelet.
double approximatedLength2d(const LaneletT &lanelet)
approximates length by sampling points along left bound
BasicPoints2d intersectCenterlines2d(const Lanelet1T &lanelet, const Lanelet2T &otherLanelet, std::vector< double > *distanceThis, std::vector< double > *distanceOther)
calculates points of intersection between centerlines in 2d.
IfAr< AreaT, bool > overlaps2d(const AreaT &area, const AreaT &otherArea)
IfAr< AreaT, bool > overlaps3d(const AreaT &area, const AreaT &otherArea, double heightTolerance)
IfAr< AreaT, BoundingBox2d > boundingBox2d(const AreaT &area)
calculates an up-right 2d bounding box
Optional< ConstLineString3d > determineCommonLine(const ConstArea &ar, const ConstLanelet &ll)
Eigen::Matrix< double, 2, 1, Eigen::DontAlign > BasicPoint2d
a simple 2d-point
boost::units::unit< boost::units::acceleration_dimension, boost::units::si::system > MPS2
Definition: Forward.h:205
Velocity maxCurveSpeed(const LaneletT &, const BasicPoint2d &, const Acceleration &)
calculates the maximum velocity without exceding a maximum lateral acceleration.
bool leftOf(const ConstLanelet &right, const ConstArea &left)
Test whether area is left of lanelet.
double length3d(const LaneletT &lanelet)
calculate length of centerline in 3d
double length2d(const LaneletT &lanelet)
calculate length of centerline in 2d
units::MPSQuantity Velocity
Definition: Forward.h:210
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