13 template <
typename LaneletT>
21 template <
typename LaneletT>
29 template <
typename LaneletT>
37 template <
typename LaneletT>
48 template <
typename LaneletT>
61 template <
typename LaneletT>
71 template <
typename LaneletT>
79 template <
typename LaneletT>
92 template <
typename Lanelet1T,
typename Lanelet2T>
93 IfLL<Lanelet1T, bool>
intersects2d(
const Lanelet1T&
lanelet,
const Lanelet2T& otherLanelet);
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.);
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>
135 std::vector<double>* distanceThis =
nullptr,
136 std::vector<double>* distanceOther =
nullptr);
145 template <
typename Lanelet1T,
typename Lanelet2T>
146 IfLL<Lanelet1T, IfLL<Lanelet2T, bool>>
leftOf(
const Lanelet1T& left,
const Lanelet2T& right);
155 template <
typename Lanelet1T,
typename Lanelet2T>
156 IfLL<Lanelet1T, IfLL<Lanelet2T, bool>>
rightOf(
const Lanelet1T& right,
const Lanelet2T& left);
165 template <
typename Lanelet1T,
typename Lanelet2T>
166 IfLL<Lanelet1T, IfLL<Lanelet2T, bool>>
follows(
const Lanelet1T& prev,
const Lanelet2T& next);
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);
189 template <
typename LaneletT>
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
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
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
IfAr< AreaT, BoundingBox3d > boundingBox3d(const AreaT &area)
calculates 3d bounding box