Namespaces | |
internal | |
Typedefs | |
using | IndexedTriangle = std::array< size_t, 3 > |
using | IndexedTriangles = std::vector< IndexedTriangle > |
Functions | |
template<typename LineStringT > | |
std::vector< double > | accumulatedLengthRatios (const LineStringT &lineString) |
bool | adjacent (const ConstArea &area1, const ConstArea &area2) |
Test if two areas are adjacent. More... | |
template<typename LineString1T , typename LineString2T > | |
std::pair< LineString1T, LineString2T > | align (LineString1T left, LineString2T right) |
inverts the two linestrings such that they are parallel More... | |
template<typename LaneletT > | |
double | approximatedLength2d (const LaneletT &lanelet) |
approximates length by sampling points along left bound More... | |
template<typename AreaT > | |
IfAr< AreaT, BoundingBox2d > | boundingBox2d (const AreaT &area) |
calculates an up-right 2d bounding box More... | |
template<typename LaneletT > | |
IfLL< LaneletT, BoundingBox2d > | boundingBox2d (const LaneletT &lanelet) |
calculates an up-right 2d bounding box More... | |
template<typename LineString2dT > | |
IfLS< LineString2dT, BoundingBox2d > | boundingBox2d (const LineString2dT &lineString) |
Get the surrounding axis-aligned bounding box in 2d. More... | |
template<typename Polygon2dT > | |
IfPoly< Polygon2dT, BoundingBox2d > | boundingBox2d (const Polygon2dT &polygon) |
BoundingBox2d | boundingBox2d (const RegulatoryElement ®Elem) |
compute the 2d bounding box around all RuleParameters contained in this RegulatoryElement More... | |
BoundingBox2d | boundingBox2d (const RegulatoryElementConstPtr ®Elem) |
compute bounding box in 2d More... | |
template<typename AreaT > | |
IfAr< AreaT, BoundingBox3d > | boundingBox3d (const AreaT &area) |
calculates 3d bounding box More... | |
template<typename LaneletT > | |
IfLL< LaneletT, BoundingBox3d > | boundingBox3d (const LaneletT &lanelet) |
calculates 3d bounding box More... | |
template<typename LineString3dT > | |
IfLS< LineString3dT, BoundingBox3d > | boundingBox3d (const LineString3dT &lineString) |
Get the surrounding axis-aligned bounding box in 3d. More... | |
template<typename Polygon3dT > | |
IfPoly< Polygon3dT, BoundingBox3d > | boundingBox3d (const Polygon3dT &polygon) |
BoundingBox3d | boundingBox3d (const RegulatoryElement ®Elem) |
compute the 3d bounding box around all RuleParameters contained in this RegulatoryElement More... | |
BoundingBox3d | boundingBox3d (const RegulatoryElementConstPtr ®Elem) |
Segment< BasicPoint2d > | closestSegment (const BasicLineString2d &lineString, const BasicPoint2d &pointToProject) |
find the segment on a 2d line string that is closest to a given point, determined by boost::geometry::distance More... | |
Segment< BasicPoint3d > | closestSegment (const BasicLineString3d &lineString, const BasicPoint3d &pointToProject) |
find the segment on a 3d line string that is closest to a given point, determined by boost::geometry::distance More... | |
Segment< BasicPoint2d > | closestSegment (const CompoundHybridLineString2d &lineString, const BasicPoint2d &pointToProject) |
Segment< BasicPoint3d > | closestSegment (const CompoundHybridLineString3d &lineString, const BasicPoint3d &pointToProject) |
Segment< ConstPoint2d > | closestSegment (const CompoundLineString2d &lineString, const BasicPoint2d &pointToProject) |
Segment< ConstPoint3d > | closestSegment (const CompoundLineString3d &lineString, const BasicPoint3d &pointToProject) |
Segment< BasicPoint2d > | closestSegment (const ConstHybridLineString2d &lineString, const BasicPoint2d &pointToProject) |
Segment< BasicPoint3d > | closestSegment (const ConstHybridLineString3d &lineString, const BasicPoint3d &pointToProject) |
Segment< ConstPoint2d > | closestSegment (const ConstLineString2d &lineString, const BasicPoint2d &pointToProject) |
Segment< ConstPoint3d > | closestSegment (const ConstLineString3d &lineString, const BasicPoint3d &pointToProject) |
template<typename Polygon2dT > | |
IfPoly< Polygon2dT, BasicPolygons2d > | convexPartition (const Polygon2dT &poly) |
Split a concave polygon into convex parts. More... | |
template<> | |
IfPoly< BasicPolygon2d, BasicPolygons2d > | convexPartition< BasicPolygon2d > (const BasicPolygon2d &poly) |
Split a concave polygon into convex parts. More... | |
template<typename Point2dT > | |
double | curvature2d (const Point2dT &p1, const Point2dT &p2, const Point2dT &p3) |
Optional< ConstLineString3d > | determineCommonLine (const ConstArea &ar, const ConstLanelet &ll) |
Optional< ConstLineString3d > | determineCommonLine (const ConstArea &ar1, const ConstArea &ar2) |
template<typename Lanelet1T , typename Lanelet2T > | |
IfLL< Lanelet1T, IfLL< Lanelet2T, Optional< ConstLineString3d > > > | determineCommonLine (const Lanelet1T &ll, const Lanelet2T &other, bool allowInverted=false) |
find a common line string in ll and other. More... | |
Optional< ConstLineString3d > | determineCommonLineFollowing (const ConstArea &ar, const ConstLanelet &ll) |
Optional< ConstLineString3d > | determineCommonLineFollowingOrPreceding (const ConstArea &ar, const ConstLanelet &ll) |
Optional< ConstLineString3d > | determineCommonLineLeft (const ConstLanelet &right, const ConstArea &left) |
Optional< ConstLineString3d > | determineCommonLinePreceding (const ConstLanelet &ll, const ConstArea &ar) |
Optional< ConstLineString3d > | determineCommonLineRight (const ConstLanelet &left, const ConstArea &right) |
Optional< ConstLineString3d > | determineCommonLineSideways (const ConstArea &ar, const ConstLanelet &ll) |
Optional< ConstLineString3d > | determineCommonLineSideways (const ConstLanelet &ll, const ConstArea &ar) |
double | distance2d (const RegulatoryElement ®Elem, const BasicPoint2d &p) |
double | distance2d (const RegulatoryElementConstPtr ®Elem1, const BasicPoint2d &p) |
See non-shared-ptr version. More... | |
template<typename LineString3d1T , typename LineString3d2T > | |
IfLS2< LineString3d1T, LineString3d2T, double > | distance3d (const LineString3d1T &l1, const LineString3d2T &l2) |
template<typename Polygon3dT > | |
IfPoly< Polygon3dT, double > | distanceToBorder3d (const Polygon3dT &poly1, const Polygon3dT &poly2) |
computes the distance of the outer bounds of two polygons in 3d. More... | |
template<typename LaneletT > | |
double | distanceToCenterline2d (const LaneletT &lanelet, const BasicPoint2d &point) |
calculates distance in 2d to the centerline of a lanelet. More... | |
template<typename LaneletT > | |
double | distanceToCenterline3d (const LaneletT &lanelet, const BasicPoint3d &point) |
calculates distance in 3d to centerline of a lanelet. More... | |
EXTERN_CONST_FIND_NEAREST (Area) | |
EXTERN_CONST_FIND_NEAREST (Lanelet) | |
EXTERN_CONST_FIND_NEAREST (LineString3d) | |
EXTERN_CONST_FIND_NEAREST (Point3d) | |
EXTERN_CONST_FIND_NEAREST (Polygon3d) | |
EXTERN_CONST_FIND_NEAREST (RegulatoryElementPtr) | |
EXTERN_FIND_NEAREST (Area) | |
EXTERN_FIND_NEAREST (Lanelet) | |
EXTERN_FIND_NEAREST (LineString3d) | |
EXTERN_FIND_NEAREST (Point3d) | |
EXTERN_FIND_NEAREST (Polygon3d) | |
EXTERN_FIND_NEAREST (RegulatoryElementPtr) | |
template<typename PrimT > | |
std::vector< std::pair< double, traits::ConstPrimitiveType< PrimT > > > | findNearest (const PrimitiveLayer< PrimT > &map, const BasicPoint2d &pt, unsigned count) |
template<typename PrimT > | |
std::vector< std::pair< double, PrimT > > | findNearest (PrimitiveLayer< PrimT > &map, const BasicPoint2d &pt, unsigned count) |
returns the nearest n primitives to a point. More... | |
template<typename LayerT , typename GeometryT > | |
auto | findWithin2d (LayerT &layer, const GeometryT &geometry, double maxDist=0.) -> std::vector< std::pair< double, traits::LayerPrimitiveType< LayerT >>> |
Returns all elements that are closer than maxDist to a geometry in 2d. More... | |
template<typename LayerT , typename GeometryT > | |
auto | findWithin3d (LayerT &layer, const GeometryT &geometry, double maxDist=0.) -> std::vector< std::pair< double, traits::LayerPrimitiveType< LayerT >>> |
Returns all elements that are closer than maxDist to a geometry in 3d. More... | |
bool | follows (const ConstArea &prev, const ConstLanelet &next) |
Test whether lanelet follows area. More... | |
bool | follows (const ConstLanelet &prev, const ConstArea &next) |
Test whether area follows lanelet. More... | |
template<typename Lanelet1T , typename Lanelet2T > | |
IfLL< Lanelet1T, IfLL< Lanelet2T, bool > > | follows (const Lanelet1T &prev, const Lanelet2T &next) |
checks if a lanelet is the direct successor by checking if they share the same start/endpoints More... | |
template<typename LineString2dT > | |
BasicPoint2d | fromArcCoordinates (const LineString2dT &lineString, const ArcCoordinates &arcCoords) |
create a point by moving laterally arcCoords.distance from the linestring point at arcCoords.length More... | |
template<typename AreaT > | |
IfAr< AreaT, bool > | inside (const AreaT &area, const BasicPoint2d &point) |
Checks whether a point is within or at the border of a area. More... | |
template<typename LaneletT > | |
IfLL< LaneletT, bool > | inside (const LaneletT &lanelet, const BasicPoint2d &point) |
Checks whether a point is within or at the border of a lanelet. More... | |
INSTANCIATE_CONST_FIND_NEAREST (Area, ConstArea) | |
INSTANCIATE_CONST_FIND_NEAREST (Lanelet, ConstLanelet) | |
INSTANCIATE_CONST_FIND_NEAREST (LineString3d, ConstLineString3d) | |
INSTANCIATE_CONST_FIND_NEAREST (Point3d, ConstPoint3d) | |
INSTANCIATE_CONST_FIND_NEAREST (Polygon3d, ConstPolygon3d) | |
INSTANCIATE_CONST_FIND_NEAREST (RegulatoryElementPtr, RegulatoryElementConstPtr) | |
INSTANCIATE_FIND_NEAREST (Area) | |
INSTANCIATE_FIND_NEAREST (Lanelet) | |
INSTANCIATE_FIND_NEAREST (LineString3d) | |
INSTANCIATE_FIND_NEAREST (Point3d) | |
INSTANCIATE_FIND_NEAREST (Polygon3d) | |
INSTANCIATE_FIND_NEAREST (RegulatoryElementPtr) | |
template<typename LineStringT > | |
traits::BasicPointT< traits::PointType< LineStringT > > | interpolatedPointAtDistance (LineStringT lineString, double dist) |
template<typename Lanelet1T , typename Lanelet2T > | |
BasicPoints2d | intersectCenterlines2d (const Lanelet1T &lanelet, const Lanelet2T &otherLanelet, std::vector< double > *distanceThis=nullptr, std::vector< double > *distanceOther=nullptr) |
calculates points of intersection between centerlines in 2d. More... | |
template<typename Area1T , typename Area2T > | |
IfAr< Area1T, bool > | intersects2d (const Area1T &area, const Area2T &otherArea) |
test whether two areas intersect in 2d. More... | |
template<typename Lanelet1T , typename Lanelet2T > | |
IfLL< Lanelet1T, bool > | intersects2d (const Lanelet1T &lanelet, const Lanelet2T &otherLanelet) |
test whether two lanelets intersect in 2d. More... | |
template<typename Lanelet1T , typename Lanelet2T > | |
IfLL< Lanelet1T, bool > | intersects3d (const Lanelet1T &lanelet, const Lanelet2T &otherLanelet, double heightTolerance=3.) |
test whether two lanelets intersect in 2d. More... | |
template<typename LineString3dT > | |
IfLS< LineString3dT, bool > | intersects3d (const LineString3dT &linestring, const LineString3dT &otherLinestring, double heightTolerance=3.) |
test whether two linestrings intersect in 3d. More... | |
bool | leftOf (const ConstLanelet &right, const ConstArea &left) |
Test whether area is left of lanelet. More... | |
template<typename Lanelet1T , typename Lanelet2T > | |
IfLL< Lanelet1T, IfLL< Lanelet2T, bool > > | leftOf (const Lanelet1T &left, const Lanelet2T &right) |
checks if a lanelet is direcly left of another by checking if they share the same boundary More... | |
template<typename LaneletT > | |
double | length2d (const LaneletT &lanelet) |
calculate length of centerline in 2d More... | |
template<typename LaneletT > | |
double | length3d (const LaneletT &lanelet) |
calculate length of centerline in 3d More... | |
template<typename LineStringT > | |
std::vector< double > | lengthRatios (const LineStringT &lineString) |
template<typename LaneletT > | |
Velocity | maxCurveSpeed (const LaneletT &lanelet, const BasicPoint2d &position, const Acceleration &maxLateralAcceleration=2.0 *units::MPS2()) |
calculates the maximum velocity without exceding a maximum lateral acceleration. More... | |
template<typename LineStringT > | |
traits::PointType< LineStringT > | nearestPointAtDistance (LineStringT lineString, double dist) |
returns the cosest point to a position on the linestring More... | |
template<typename LineString2dT > | |
BasicLineString2d | offset (const LineString2dT &lineString, double distance) |
create a linestring that is offset to the original one. Guarantees no self-intersections and no inversions in the result. More... | |
template<typename LineString2dT > | |
BasicLineString2d | offsetNoThrow (const LineString2dT &lineString, double distance) |
create a linestring that is offset to the original one. the result. More... | |
template<typename AreaT > | |
IfAr< AreaT, bool > | overlaps2d (const AreaT &area, const AreaT &otherArea) |
template<typename AreaT , typename LaneletT > | |
IfAr< AreaT, IfLL< LaneletT, bool > > | overlaps2d (const AreaT &area, const LaneletT &lanelet) |
template<typename Lanelet1T , typename Lanelet2T > | |
IfLL< Lanelet1T, bool > | overlaps2d (const Lanelet1T &lanelet, const Lanelet2T &otherLanelet) |
test whether two lanelets overlap in 2d. More... | |
template<typename Polygon2dT > | |
IfPoly< Polygon2dT, bool > | overlaps2d (const Polygon2dT &poly1, const Polygon2dT &poly2) |
template<typename AreaT > | |
IfAr< AreaT, bool > | overlaps3d (const AreaT &area, const AreaT &otherArea, double heightTolerance) |
template<typename AreaT , typename LaneletT > | |
IfAr< AreaT, IfLL< LaneletT, bool > > | overlaps3d (const AreaT &area, const LaneletT &lanelet, double heightTolerance) |
template<typename Lanelet1T , typename Lanelet2T > | |
IfLL< Lanelet1T, bool > | overlaps3d (const Lanelet1T &lanelet, const Lanelet2T &otherLanelet, double heightTolerance=3) |
test whether two lanelets overlap in 3d. More... | |
template<typename Polygon3dT > | |
IfPoly< Polygon3dT, bool > | overlaps3d (const Polygon3dT &poly1, const Polygon3dT &poly2, double heightTolerance) |
BasicPoint2d | project (const BasicSegment2d &segment, const BasicPoint2d &pointToProject) |
BasicPoint3d | project (const BasicSegment3d &segment, const BasicPoint3d &pointToProject) |
template<typename LineString2dT , typename > | |
BasicPoint2d | project (const LineString2dT &lineString, const BasicPoint2d &pointToProject) |
Projects the given point in 2d to the LineString. More... | |
template<typename LineString3dT , typename > | |
BasicPoint3d | project (const LineString3dT &lineString, const BasicPoint3d &pointToProject) |
Projects the given point in 3d to the LineString. More... | |
template<typename Polygon3dT > | |
IfPoly< Polygon3dT, std::pair< BasicPoint3d, BasicPoint3d > > | projectedBorderPoint3d (const Polygon3dT &l1, const Polygon3dT &l2) |
template<typename LineString2dT > | |
IfLS< LineString2dT, std::pair< BasicPoint2d, BasicPoint2d > > | projectedPoint2d (const LineString2dT &l1, const LineString2dT &l2) |
Computes the projected points on the two linestrings for the shortest distance. More... | |
template<typename LineString3dT > | |
IfLS< LineString3dT, std::pair< BasicPoint3d, BasicPoint3d > > | projectedPoint3d (const LineString3dT &l1, const LineString3dT &l2) |
Computes the projected points on the two linestrings for the shortest distance. More... | |
template<typename LineStringIterator > | |
double | rangedLength (LineStringIterator start, LineStringIterator end) |
bool | rightOf (const ConstLanelet &left, const ConstArea &area) |
Test whether area is right of lanelet. More... | |
template<typename Lanelet1T , typename Lanelet2T > | |
IfLL< Lanelet1T, IfLL< Lanelet2T, bool > > | rightOf (const Lanelet1T &right, const Lanelet2T &left) |
checks if a lanelet is direcly right of another by checking if they share the same boundary More... | |
template<typename Point2dT > | |
double | signedCurvature2d (const Point2dT &p1, const Point2dT &p2, const Point2dT &p3) |
template<typename LineString2dT > | |
double | signedDistance (const LineString2dT &lineString, const BasicPoint2d &p) |
template<typename LineString3dT > | |
double | signedDistance (const LineString3dT &lineString, const BasicPoint3d &p) |
template<typename LineString2dT > | |
ArcCoordinates | toArcCoordinates (const LineString2dT &lineString, const BasicPoint2d &point) |
Transform a point to the coordinates of the linestring. More... | |
template<typename PolygonT > | |
IfPoly< PolygonT, bool > | touches2d (const PolygonT &poly1, const PolygonT &poly2) |
template<typename Polygon2dT > | |
IfPoly< Polygon2dT, IndexedTriangles > | triangulate (const Polygon2dT &poly) |
Split a concave polygon into triangles. More... | |
template<> | |
IfPoly< BasicPolygon2d, IndexedTriangles > | triangulate< BasicPolygon2d > (const BasicPolygon2d &poly) |
Split a concave polygon into triangles. More... | |
using lanelet::geometry::IndexedTriangle = typedef std::array<size_t, 3> |
Definition at line 318 of file geometry/Polygon.h.
using lanelet::geometry::IndexedTriangles = typedef std::vector<IndexedTriangle> |
Definition at line 319 of file geometry/Polygon.h.
std::vector< double > lanelet::geometry::accumulatedLengthRatios | ( | const LineStringT & | lineString | ) |
Calculates the accumulated length ratios for the lines in the LineString.
lineString | the LineString to do this for. |
The last element will aways be (near) 1
Definition at line 634 of file geometry/impl/LineString.h.
Test if two areas are adjacent.
Definition at line 78 of file geometry/impl/Area.h.
std::pair< LineString1T, LineString2T > lanelet::geometry::align | ( | LineString1T | left, |
LineString2T | right | ||
) |
inverts the two linestrings such that they are parallel
left | the designated left linestring |
right | the designated right linestring |
Example input: <<<<<<<<LeftLinestring<<<<<<<
>>>>>>>>RightLinestring>>>>>>
Example output. Left was inverted: >>>>>>>>First>>>>>>>>>>>>>>>>
>>>>>>>>Second>>>>>>>>>>>>>>>
Definition at line 809 of file geometry/impl/LineString.h.
double lanelet::geometry::approximatedLength2d | ( | const LaneletT & | lanelet | ) |
approximates length by sampling points along left bound
avoids to calculate the centerline which might be expensive.
Definition at line 174 of file geometry/impl/Lanelet.h.
IfAr< AreaT, BoundingBox2d > lanelet::geometry::boundingBox2d | ( | const AreaT & | area | ) |
calculates an up-right 2d bounding box
area | area to calculate it from |
Linear on number of points.
Definition at line 25 of file geometry/impl/Area.h.
IfLL< LaneletT, BoundingBox2d > lanelet::geometry::boundingBox2d | ( | const LaneletT & | lanelet | ) |
calculates an up-right 2d bounding box
lanelet | lanelet to calculate it from |
Linear on number of points.
Definition at line 40 of file geometry/impl/Lanelet.h.
IfLS< LineString2dT, BoundingBox2d > lanelet::geometry::boundingBox2d | ( | const LineString2dT & | lineString | ) |
Get the surrounding axis-aligned bounding box in 2d.
Definition at line 753 of file geometry/impl/LineString.h.
IfPoly< Polygon2dT, BoundingBox2d > lanelet::geometry::boundingBox2d | ( | const Polygon2dT & | polygon | ) |
Definition at line 269 of file geometry/Polygon.h.
BoundingBox2d lanelet::geometry::boundingBox2d | ( | const RegulatoryElement & | regElem | ) |
compute the 2d bounding box around all RuleParameters contained in this RegulatoryElement
Note that this does not include the lanelet that refers to this regulatry element, only the the roles in the regulatory element. The bounding box can also be empty if the RegulatoryElement does not contain any data.
Definition at line 73 of file RegulatoryElementGeometry.cpp.
|
inline |
compute bounding box in 2d
See non-shared-ptr version.
Definition at line 23 of file geometry/RegulatoryElement.h.
IfAr< AreaT, BoundingBox3d > lanelet::geometry::boundingBox3d | ( | const AreaT & | area | ) |
calculates 3d bounding box
area | area to calculate it from. |
Definition at line 30 of file geometry/impl/Area.h.
IfLL< LaneletT, BoundingBox3d > lanelet::geometry::boundingBox3d | ( | const LaneletT & | lanelet | ) |
calculates 3d bounding box
lanelet | lanelet to calculate it from. |
Definition at line 47 of file geometry/impl/Lanelet.h.
IfLS< LineString3dT, BoundingBox3d > lanelet::geometry::boundingBox3d | ( | const LineString3dT & | lineString | ) |
Get the surrounding axis-aligned bounding box in 3d.
Definition at line 743 of file geometry/impl/LineString.h.
IfPoly< Polygon3dT, BoundingBox3d > lanelet::geometry::boundingBox3d | ( | const Polygon3dT & | polygon | ) |
Get the surrounding bounding box
Definition at line 259 of file geometry/Polygon.h.
BoundingBox3d lanelet::geometry::boundingBox3d | ( | const RegulatoryElement & | regElem | ) |
compute the 3d bounding box around all RuleParameters contained in this RegulatoryElement
Note that this does not include the lanelet that refers to this regulatry element, only the the roles in the regulatory element. The bounding box can also be empty if the regulatory elemnt does not contain any data.
Definition at line 79 of file RegulatoryElementGeometry.cpp.
|
inline |
Definition at line 35 of file geometry/RegulatoryElement.h.
Segment< BasicPoint2d > lanelet::geometry::closestSegment | ( | const BasicLineString2d & | lineString, |
const BasicPoint2d & | pointToProject | ||
) |
find the segment on a 2d line string that is closest to a given point, determined by boost::geometry::distance
lineString | the line string the distance function is evaluated on |
pointToProject | 2d point that is projected on to the linestring |
Definition at line 442 of file LineStringGeometry.cpp.
Segment< BasicPoint3d > lanelet::geometry::closestSegment | ( | const BasicLineString3d & | lineString, |
const BasicPoint3d & | pointToProject | ||
) |
find the segment on a 3d line string that is closest to a given point, determined by boost::geometry::distance
lineString | the line string the distance function is evaluated on |
pointToProject | 3d point that is projected on to the linestring |
Definition at line 445 of file LineStringGeometry.cpp.
Segment< BasicPoint2d > lanelet::geometry::closestSegment | ( | const CompoundHybridLineString2d & | lineString, |
const BasicPoint2d & | pointToProject | ||
) |
Definition at line 470 of file LineStringGeometry.cpp.
Segment< BasicPoint3d > lanelet::geometry::closestSegment | ( | const CompoundHybridLineString3d & | lineString, |
const BasicPoint3d & | pointToProject | ||
) |
Definition at line 473 of file LineStringGeometry.cpp.
Segment< ConstPoint2d > lanelet::geometry::closestSegment | ( | const CompoundLineString2d & | lineString, |
const BasicPoint2d & | pointToProject | ||
) |
Definition at line 463 of file LineStringGeometry.cpp.
Segment< ConstPoint3d > lanelet::geometry::closestSegment | ( | const CompoundLineString3d & | lineString, |
const BasicPoint3d & | pointToProject | ||
) |
Definition at line 466 of file LineStringGeometry.cpp.
Segment< BasicPoint2d > lanelet::geometry::closestSegment | ( | const ConstHybridLineString2d & | lineString, |
const BasicPoint2d & | pointToProject | ||
) |
Definition at line 456 of file LineStringGeometry.cpp.
Segment< BasicPoint3d > lanelet::geometry::closestSegment | ( | const ConstHybridLineString3d & | lineString, |
const BasicPoint3d & | pointToProject | ||
) |
Definition at line 459 of file LineStringGeometry.cpp.
Segment< ConstPoint2d > lanelet::geometry::closestSegment | ( | const ConstLineString2d & | lineString, |
const BasicPoint2d & | pointToProject | ||
) |
Definition at line 449 of file LineStringGeometry.cpp.
Segment< ConstPoint3d > lanelet::geometry::closestSegment | ( | const ConstLineString3d & | lineString, |
const BasicPoint3d & | pointToProject | ||
) |
Definition at line 452 of file LineStringGeometry.cpp.
IfPoly< Polygon2dT, BasicPolygons2d > lanelet::geometry::convexPartition | ( | const Polygon2dT & | poly | ) |
Split a concave polygon into convex parts.
Internally computes a Delaunay triangulation which is greedily merged into convex parts. Guaranteed to deliver a partition with at most 2N+1 parts if N is minimum partition. Since boost only allows integral types, the triangulation is only millimeter-accurate, even though the resulting points are identical to the input points.
Polygon2dT | Polygon Type |
poly | Polygon to partition |
Definition at line 82 of file geometry/impl/Polygon.h.
|
inline |
Split a concave polygon into convex parts.
Internally computes a Delaunay triangulation which is greedily merged into convex parts. Guaranteed to deliver a partition with at most 2N+1 parts if N is minimum partition. Since boost only allows integral types, the triangulation is only millimeter-accurate, even though the resulting points are identical to the input points.
poly | BasicPolygon2d to partition |
Definition at line 94 of file geometry/impl/Polygon.h.
double lanelet::geometry::curvature2d | ( | const Point2dT & | p1, |
const Point2dT & | p2, | ||
const Point2dT & | p3 | ||
) |
Calculate the curvature value given 3 consecutive points. The curvature value is always positive.
p1,p2,p3 | are the points |
If any 2 of the 3 points duplicate, return infinity.
Definition at line 705 of file geometry/impl/LineString.h.
|
inline |
Find line string in area ar that borders Lanelet ll anywhere
Definition at line 128 of file geometry/impl/Area.h.
|
inline |
Find Line String in Area ar1 that is common with Area ar2
Definition at line 121 of file geometry/impl/Area.h.
IfLL< Lanelet1T, IfLL< Lanelet2T, Optional< ConstLineString3d > > > lanelet::geometry::determineCommonLine | ( | const Lanelet1T & | ll, |
const Lanelet2T & | other, | ||
bool | allowInverted = false |
||
) |
find a common line string in ll and other.
ll | Lanelet |
other | Lanelet |
allowInverted | if true, the orientation of the line strings is ignored |
Definition at line 146 of file geometry/impl/Lanelet.h.
|
inline |
Find line string in area ar that borders Lanelet ll if ar precedes ll
Definition at line 98 of file geometry/impl/Area.h.
|
inline |
Find line string in area ar that borders Lanelet ll if ar precedes or follows ll
Definition at line 102 of file geometry/impl/Area.h.
|
inline |
Find line string in Lanelet right that borders Area left if ar is left of ll.
Definition at line 133 of file geometry/impl/Area.h.
|
inline |
Find line string in area ar that borders Lanelet ll if ar follows ll
Definition at line 92 of file geometry/impl/Area.h.
|
inline |
Find line string in Lanelet left that borders Area right if ar is right of ll.
Definition at line 141 of file geometry/impl/Area.h.
|
inline |
Find line string in Area ar that borders Lanelet ll if ar is left or right of ll. Same as determineCommonLineSideways(ll, ar) but returned line string is guaranteed to be in ar
Definition at line 115 of file geometry/impl/Area.h.
|
inline |
Find line string in Lanelet ll that borders Area ar if ar is left or right of ll. Same as determineCommonLineSideways(ar, ll) but returned line string is guaranteed to be in ll
Definition at line 110 of file geometry/impl/Area.h.
double lanelet::geometry::distance2d | ( | const RegulatoryElement & | regElem, |
const BasicPoint2d & | p | ||
) |
computes the distance between a point and the closest RuleParameter of a RegulatoryElement
Definition at line 85 of file RegulatoryElementGeometry.cpp.
|
inline |
See non-shared-ptr version.
Definition at line 42 of file geometry/RegulatoryElement.h.
IfLS2<LineString3d1T, LineString3d2T, double> lanelet::geometry::distance3d | ( | const LineString3d1T & | l1, |
const LineString3d2T & | l2 | ||
) |
Definition at line 803 of file geometry/impl/LineString.h.
IfPoly< Polygon3dT, double > lanelet::geometry::distanceToBorder3d | ( | const Polygon3dT & | poly1, |
const Polygon3dT & | poly2 | ||
) |
computes the distance of the outer bounds of two polygons in 3d.
There is no such implementation in boost::geometry, so we implemented our own solution using an RTree for more efficient computation.
Definition at line 37 of file geometry/impl/Polygon.h.
double lanelet::geometry::distanceToCenterline2d | ( | const LaneletT & | lanelet, |
const BasicPoint2d & | point | ||
) |
calculates distance in 2d to the centerline of a lanelet.
lanelet | lanelet to take the centerline from |
point | the point |
Has linear complexity on the number of points in the lanelet.
Definition at line 30 of file geometry/impl/Lanelet.h.
double lanelet::geometry::distanceToCenterline3d | ( | const LaneletT & | lanelet, |
const BasicPoint3d & | point | ||
) |
calculates distance in 3d to centerline of a lanelet.
calculates distance in 2d to the centerline of a lanelet.
lanelet | lanelet to take the centerline from |
point | the point |
Unlike distance3d, the surface does not have to be planar. Has linear complexity on the number of points in the lanelet.
Definition at line 35 of file geometry/impl/Lanelet.h.
lanelet::geometry::EXTERN_CONST_FIND_NEAREST | ( | Area | ) |
lanelet::geometry::EXTERN_CONST_FIND_NEAREST | ( | Lanelet | ) |
lanelet::geometry::EXTERN_CONST_FIND_NEAREST | ( | LineString3d | ) |
lanelet::geometry::EXTERN_CONST_FIND_NEAREST | ( | Point3d | ) |
lanelet::geometry::EXTERN_CONST_FIND_NEAREST | ( | Polygon3d | ) |
lanelet::geometry::EXTERN_CONST_FIND_NEAREST | ( | RegulatoryElementPtr | ) |
lanelet::geometry::EXTERN_FIND_NEAREST | ( | Area | ) |
lanelet::geometry::EXTERN_FIND_NEAREST | ( | Lanelet | ) |
lanelet::geometry::EXTERN_FIND_NEAREST | ( | LineString3d | ) |
lanelet::geometry::EXTERN_FIND_NEAREST | ( | Point3d | ) |
lanelet::geometry::EXTERN_FIND_NEAREST | ( | Polygon3d | ) |
lanelet::geometry::EXTERN_FIND_NEAREST | ( | RegulatoryElementPtr | ) |
std::vector< std::pair< double, traits::ConstPrimitiveType< PrimT > > > lanelet::geometry::findNearest | ( | const PrimitiveLayer< PrimT > & | map, |
const BasicPoint2d & | pt, | ||
unsigned | count | ||
) |
Definition at line 992 of file LaneletMap.cpp.
std::vector< std::pair< double, PrimT > > lanelet::geometry::findNearest | ( | PrimitiveLayer< PrimT > & | map, |
const BasicPoint2d & | pt, | ||
unsigned | count | ||
) |
returns the nearest n primitives to a point.
Other than than LaneletLayer::nearest, this returns the actually closest primitives, not only the closest bounding boxes. This comes at a slightly higher cost, because more primitives from the R-Tree need to be checked.
Example: std::vector<std::pair<double, Lanelet>> closeLanelets = findNearest(laneletMap.laneletLayer, BasicPoint2d(1,0), 5);
Definition at line 987 of file LaneletMap.cpp.
auto lanelet::geometry::findWithin2d | ( | LayerT & | layer, |
const GeometryT & | geometry, | ||
double | maxDist = 0. |
||
) | -> std::vector< std::pair< double, traits::LayerPrimitiveType< LayerT >>> |
Returns all elements that are closer than maxDist to a geometry in 2d.
layer | for the check (a layer of LaneletMap) |
geometry | to check (any 2d geometry) |
maxDist | maximum distance to the input geometry. If zero, only primitives containing the element are returned. Be aware that rounding errors can affect the result for primitives directly on (or very close to) the boundary. |
Definition at line 14 of file geometry/impl/LaneletMap.h.
auto lanelet::geometry::findWithin3d | ( | LayerT & | layer, |
const GeometryT & | geometry, | ||
double | maxDist = 0. |
||
) | -> std::vector< std::pair< double, traits::LayerPrimitiveType< LayerT >>> |
Returns all elements that are closer than maxDist to a geometry in 3d.
layer | for the check (a layer of LaneletMap) |
geometry | to check (any 3d geometry) |
maxDist | maximum distance to the input geometry. If zero, only primitives containing the element are returned. Be aware that rounding errors can affect the result for primitives directly on (or very close to) the boundary. |
Definition at line 38 of file geometry/impl/LaneletMap.h.
|
inline |
Test whether lanelet follows area.
Definition at line 76 of file geometry/impl/Area.h.
|
inline |
Test whether area follows lanelet.
Definition at line 68 of file geometry/impl/Area.h.
IfLL< Lanelet1T, IfLL< Lanelet2T, bool > > lanelet::geometry::follows | ( | const Lanelet1T & | prev, |
const Lanelet2T & | next | ||
) |
checks if a lanelet is the direct successor by checking if they share the same start/endpoints
Be aware that the orientation of the lanelets (see Lanelet::invert()) is important.
Definition at line 139 of file geometry/impl/Lanelet.h.
BasicPoint2d lanelet::geometry::fromArcCoordinates | ( | const LineString2dT & | lineString, |
const ArcCoordinates & | arcCoords | ||
) |
create a point by moving laterally arcCoords.distance from the linestring point at arcCoords.length
lineString | line string of which an offset point is generated |
arcCoords | the coordinates the resulting point has (arcLength.distance > 0 creates a point on the left) |
Definition at line 832 of file geometry/impl/LineString.h.
IfAr< AreaT, bool > lanelet::geometry::inside | ( | const AreaT & | area, |
const BasicPoint2d & | point | ||
) |
Checks whether a point is within or at the border of a area.
area | for the check |
point | point to check |
Definition at line 20 of file geometry/impl/Area.h.
IfLL< LaneletT, bool > lanelet::geometry::inside | ( | const LaneletT & | lanelet, |
const BasicPoint2d & | point | ||
) |
Checks whether a point is within or at the border of a lanelet.
lanelet | for the check |
point | point to check |
Definition at line 25 of file geometry/impl/Lanelet.h.
lanelet::geometry::INSTANCIATE_CONST_FIND_NEAREST | ( | Lanelet | , |
ConstLanelet | |||
) |
lanelet::geometry::INSTANCIATE_CONST_FIND_NEAREST | ( | LineString3d | , |
ConstLineString3d | |||
) |
lanelet::geometry::INSTANCIATE_CONST_FIND_NEAREST | ( | Point3d | , |
ConstPoint3d | |||
) |
lanelet::geometry::INSTANCIATE_CONST_FIND_NEAREST | ( | Polygon3d | , |
ConstPolygon3d | |||
) |
lanelet::geometry::INSTANCIATE_CONST_FIND_NEAREST | ( | RegulatoryElementPtr | , |
RegulatoryElementConstPtr | |||
) |
lanelet::geometry::INSTANCIATE_FIND_NEAREST | ( | Area | ) |
lanelet::geometry::INSTANCIATE_FIND_NEAREST | ( | Lanelet | ) |
lanelet::geometry::INSTANCIATE_FIND_NEAREST | ( | LineString3d | ) |
lanelet::geometry::INSTANCIATE_FIND_NEAREST | ( | Point3d | ) |
lanelet::geometry::INSTANCIATE_FIND_NEAREST | ( | Polygon3d | ) |
lanelet::geometry::INSTANCIATE_FIND_NEAREST | ( | RegulatoryElementPtr | ) |
traits::BasicPointT< traits::PointType< LineStringT > > lanelet::geometry::interpolatedPointAtDistance | ( | LineStringT | lineString, |
double | dist | ||
) |
Returns the piecewise linearly interpolated point at the given distance. Negative distances are interpreted backwards from the end.
lineString | the lineString to iterate. Size must be >0. |
dist | distance along linestring. If negative, the lineString is iterated in reversed order. |
This function works in 2d or 3d, depending on the type of the lineString. If the distance is greater length, the end point is returned (or start point if <0).
Definition at line 641 of file geometry/impl/LineString.h.
BasicPoints2d lanelet::geometry::intersectCenterlines2d | ( | const Lanelet1T & | lanelet, |
const Lanelet2T & | otherLanelet, | ||
std::vector< double > * | distanceThis = nullptr , |
||
std::vector< double > * | distanceOther = nullptr |
||
) |
calculates points of intersection between centerlines in 2d.
lanelet | first lanelet to calculate from |
otherLanelet | second lanelet to calculate from |
distanceThis | optional: if not null will contain distances to travel along the centerline to each intersection point. Same size as the returned result. |
distanceOther | optional: same for the other lanelet |
Definition at line 93 of file geometry/impl/Lanelet.h.
IfAr< Area1T, bool > lanelet::geometry::intersects2d | ( | const Area1T & | area, |
const Area2T & | otherArea | ||
) |
test whether two areas intersect in 2d.
Definition at line 35 of file geometry/impl/Area.h.
IfLL< Lanelet1T, bool > lanelet::geometry::intersects2d | ( | const Lanelet1T & | lanelet, |
const Lanelet2T & | otherLanelet | ||
) |
test whether two lanelets intersect in 2d.
lanelet | lanelet to check for |
otherLanelet | other lanelet to check for |
This also returns true if the two lanelets only touch each other. Use overlaps if you do not want this.
Definition at line 54 of file geometry/impl/Lanelet.h.
IfLL< Lanelet1T, bool > lanelet::geometry::intersects3d | ( | const Lanelet1T & | lanelet, |
const Lanelet2T & | otherLanelet, | ||
double | heightTolerance = 3. |
||
) |
test whether two lanelets intersect in 2d.
lanelet | lanelet to check for |
otherLanelet | other lanelet to check for |
heightTolerance | distance in z below which lanelets are considered as intersecting |
Definition at line 111 of file geometry/impl/Lanelet.h.
IfLS< LineString3dT, bool > lanelet::geometry::intersects3d | ( | const LineString3dT & | linestring, |
const LineString3dT & | otherLinestring, | ||
double | heightTolerance = 3. |
||
) |
test whether two linestrings intersect in 3d.
linestring | lanelet to check for |
otherLinestring | other lanelet to check for |
heightTolerance | distance in z below which linestrings are considered as intersecting (in m) |
Definition at line 774 of file geometry/impl/LineString.h.
|
inline |
Test whether area is left of lanelet.
Definition at line 62 of file geometry/impl/Area.h.
IfLL< Lanelet1T, IfLL< Lanelet2T, bool > > lanelet::geometry::leftOf | ( | const Lanelet1T & | left, |
const Lanelet2T & | right | ||
) |
checks if a lanelet is direcly left of another by checking if they share the same boundary
Be aware that the orientation of the lanelets (see Lanelet::invert()) is important
Definition at line 129 of file geometry/impl/Lanelet.h.
double lanelet::geometry::length2d | ( | const LaneletT & | lanelet | ) |
calculate length of centerline in 2d
lanelet | lanelet to do this for |
Definition at line 188 of file geometry/impl/Lanelet.h.
double lanelet::geometry::length3d | ( | const LaneletT & | lanelet | ) |
calculate length of centerline in 3d
lanelet | lanelet to do this for |
Definition at line 193 of file geometry/impl/Lanelet.h.
std::vector< double > lanelet::geometry::lengthRatios | ( | const LineStringT & | lineString | ) |
Calculates the length ratios for the lines in the LineString.
The length ratio of a line is the line's length divided by the LineString's length.
lineString | the linestring to do this for. |
The function is templated to work on all LineString types, 2d or 3d. Depending on the type, the result will be computed in 2d or 3d.
Definition at line 617 of file geometry/impl/LineString.h.
Velocity lanelet::geometry::maxCurveSpeed | ( | const LaneletT & | lanelet, |
const BasicPoint2d & | position, | ||
const Acceleration & | maxLateralAcceleration = 2.0 *units::MPS2() |
||
) |
calculates the maximum velocity without exceding a maximum lateral acceleration.
lanelet | lanelet to calculate this from |
position | position in 2d next to the lanelet |
maxLateralAcceleration | the maximum desired acceleration |
<
Definition at line 167 of file geometry/impl/Lanelet.h.
traits::PointType< LineStringT > lanelet::geometry::nearestPointAtDistance | ( | LineStringT | lineString, |
double | dist | ||
) |
returns the cosest point to a position on the linestring
lineString | the lineString to iterate. Size must be >0. |
dist | distance along linestring. If negative, the lineString is iterated in reversed order. |
This function works in 2d or 3d, depending on the type of the lineString. If the distance is greater length, the end point is returned (or start point if <0).
Definition at line 667 of file geometry/impl/LineString.h.
BasicLineString2d lanelet::geometry::offset | ( | const LineString2dT & | lineString, |
double | distance | ||
) |
create a linestring that is offset to the original one. Guarantees no self-intersections and no inversions in the result.
lineString | linestring to offset |
distance | offset distance (left = positive) |
InvalidInpuError | if the linestring has less than 2 points |
GeometryError | if the linestring is partially inverted after applying offset |
The offset is generated by shifting points of the line string and making a new line string from them. The distance of any points on the generated line string is guaranteed to be between 1 and sqrt(2) times the specified offset distance. Notice that the reversed case is not true. On angles exceeding 90 degrees, a new point is introduced to the resulting line string to fulfill this guarantee.
Definition at line 865 of file geometry/impl/LineString.h.
BasicLineString2d lanelet::geometry::offsetNoThrow | ( | const LineString2dT & | lineString, |
double | distance | ||
) |
create a linestring that is offset to the original one. the result.
lineString | linestring to offset |
distance | offset distance (left = positive) |
InvalidInpuError | if the linestring has less than 2 points |
GeometryError | if the linestring is partially inverted after applying offset |
The offset is generated by shifting points of the line string and making a new line string from them. No exception is thrown when
Definition at line 857 of file geometry/impl/LineString.h.
IfAr< AreaT, bool > lanelet::geometry::overlaps2d | ( | const AreaT & | area, |
const AreaT & | otherArea | ||
) |
test whether two areas overlap in 2d (common area < 0). This is an approximation that ignores the holes of the areas!
Definition at line 43 of file geometry/impl/Area.h.
IfAr< AreaT, IfLL< LaneletT, bool > > lanelet::geometry::overlaps2d | ( | const AreaT & | area, |
const LaneletT & | lanelet | ||
) |
test whether an area and a lanelet overlap in 2d This is an approximation that uses the overlap of the outer bound
Definition at line 53 of file geometry/impl/Area.h.
IfLL< Lanelet1T, bool > lanelet::geometry::overlaps2d | ( | const Lanelet1T & | lanelet, |
const Lanelet2T & | otherLanelet | ||
) |
test whether two lanelets overlap in 2d.
Returns true if the area shared by the two lanelets is >0.
Definition at line 64 of file geometry/impl/Lanelet.h.
IfPoly< Polygon2dT, bool > lanelet::geometry::overlaps2d | ( | const Polygon2dT & | poly1, |
const Polygon2dT & | poly2 | ||
) |
Definition at line 57 of file geometry/impl/Polygon.h.
IfAr< AreaT, bool > lanelet::geometry::overlaps3d | ( | const AreaT & | area, |
const AreaT & | otherArea, | ||
double | heightTolerance | ||
) |
test whether two areas overlap in 3d. This is an approximation that uses the overlap of the outer bound
Definition at line 48 of file geometry/impl/Area.h.
IfAr< AreaT, IfLL< LaneletT, bool > > lanelet::geometry::overlaps3d | ( | const AreaT & | area, |
const LaneletT & | lanelet, | ||
double | heightTolerance | ||
) |
test whether an area and a lanelet overlap in 3d This is an approximation that uses the overlap of the outer bound
Definition at line 58 of file geometry/impl/Area.h.
IfLL< Lanelet1T, bool > lanelet::geometry::overlaps3d | ( | const Lanelet1T & | lanelet, |
const Lanelet2T & | otherLanelet, | ||
double | heightTolerance = 3 |
||
) |
test whether two lanelets overlap in 3d.
Returns true if the area shared by the two lanelets is >0.
Definition at line 120 of file geometry/impl/Lanelet.h.
IfPoly< Polygon3dT, bool > lanelet::geometry::overlaps3d | ( | const Polygon3dT & | poly1, |
const Polygon3dT & | poly2, | ||
double | heightTolerance | ||
) |
Definition at line 72 of file geometry/impl/Polygon.h.
BasicPoint2d lanelet::geometry::project | ( | const BasicSegment2d & | segment, |
const BasicPoint2d & | pointToProject | ||
) |
Definition at line 477 of file LineStringGeometry.cpp.
BasicPoint3d lanelet::geometry::project | ( | const BasicSegment3d & | segment, |
const BasicPoint3d & | pointToProject | ||
) |
Definition at line 480 of file LineStringGeometry.cpp.
BasicPoint2d lanelet::geometry::project | ( | const LineString2dT & | lineString, |
const BasicPoint2d & | pointToProject | ||
) |
Projects the given point in 2d to the LineString.
Definition at line 768 of file geometry/impl/LineString.h.
BasicPoint3d lanelet::geometry::project | ( | const LineString3dT & | lineString, |
const BasicPoint3d & | pointToProject | ||
) |
Projects the given point in 3d to the LineString.
If the point is before or behind the lineString, this will be the respective endpoint of the lineString. If not, this will be some interpolated point on the linestring that minimizes the distance between pointToProject and the lineString
Definition at line 762 of file geometry/impl/LineString.h.
IfPoly< Polygon3dT, std::pair< BasicPoint3d, BasicPoint3d > > lanelet::geometry::projectedBorderPoint3d | ( | const Polygon3dT & | l1, |
const Polygon3dT & | l2 | ||
) |
Definition at line 30 of file geometry/impl/Polygon.h.
IfLS< LineString2dT, std::pair< BasicPoint2d, BasicPoint2d > > lanelet::geometry::projectedPoint2d | ( | const LineString2dT & | l1, |
const LineString2dT & | l2 | ||
) |
Computes the projected points on the two linestrings for the shortest distance.
First element of the pair is located on l1, second on l2
Definition at line 789 of file geometry/impl/LineString.h.
IfLS< LineString3dT, std::pair< BasicPoint3d, BasicPoint3d > > lanelet::geometry::projectedPoint3d | ( | const LineString3dT & | l1, |
const LineString3dT & | l2 | ||
) |
Computes the projected points on the two linestrings for the shortest distance.
First element of the pair is located on l1, second on l2
Definition at line 796 of file geometry/impl/LineString.h.
double lanelet::geometry::rangedLength | ( | LineStringIterator | start, |
LineStringIterator | end | ||
) |
Definition at line 610 of file geometry/impl/LineString.h.
|
inline |
Test whether area is right of lanelet.
Definition at line 66 of file geometry/impl/Area.h.
IfLL< Lanelet1T, IfLL< Lanelet2T, bool > > lanelet::geometry::rightOf | ( | const Lanelet1T & | right, |
const Lanelet2T & | left | ||
) |
checks if a lanelet is direcly right of another by checking if they share the same boundary
Be aware that the orientation of the lanelets (see Lanelet::invert()) is important.
Definition at line 134 of file geometry/impl/Lanelet.h.
double lanelet::geometry::signedCurvature2d | ( | const Point2dT & | p1, |
const Point2dT & | p2, | ||
const Point2dT & | p3 | ||
) |
Calculate the signed curvature value given 3 consecutive points. The signed curvature value is positive if the consecutive points describe a left turn, negative otherwise.
p1,p2,p3 | are the points |
If any 2 of the 3 points duplicate, return infinity.
Definition at line 710 of file geometry/impl/LineString.h.
double lanelet::geometry::signedDistance | ( | const LineString2dT & | lineString, |
const BasicPoint2d & | p | ||
) |
Calculate the metric signed distance from p to the LineString. The sign is positive if the point is left of the linestring when projecting to the xy-plane.
lineString | the linestring to check for |
p | point to check for |
If the point is before or behind the linestring, this is checked by extrapolating the first or last segment.
Definition at line 699 of file geometry/impl/LineString.h.
double lanelet::geometry::signedDistance | ( | const LineString3dT & | lineString, |
const BasicPoint3d & | p | ||
) |
Calculate the metric signed distance from p to the LineString. The sign is positive if the point is left of the linestring when projecting to the xy-plane.
lineString | the linestring to check for |
p | the point to check for |
If the point is before or behind the linestring, this is checked by extrapolating the first or last segment.
Definition at line 693 of file geometry/impl/LineString.h.
ArcCoordinates lanelet::geometry::toArcCoordinates | ( | const LineString2dT & | lineString, |
const BasicPoint2d & | point | ||
) |
Transform a point to the coordinates of the linestring.
This computes the Distance along the LineString and distance to the LineString for the point on the LineString that is closest to the input point.
Definition at line 724 of file geometry/impl/LineString.h.
IfPoly< PolygonT, bool > lanelet::geometry::touches2d | ( | const PolygonT & | poly1, |
const PolygonT & | poly2 | ||
) |
Definition at line 44 of file geometry/impl/Polygon.h.
IfPoly< Polygon2dT, IndexedTriangles > lanelet::geometry::triangulate | ( | const Polygon2dT & | poly | ) |
Split a concave polygon into triangles.
Internally computes a Delaunay triangulation.
Polygon2dT | Polygon Type |
poly | Polygon to partition |
Definition at line 88 of file geometry/impl/Polygon.h.
|
inline |
Split a concave polygon into triangles.
Internally computes a Delaunay triangulation.
poly | Polygon to partition |
Definition at line 99 of file geometry/impl/Polygon.h.