Classes | |
| struct | GetGeometry< T, IfAr< T, void > > |
| struct | GetGeometry< T, IfLL< T, void > > |
| struct | GetGeometry< T, IfLS< T, void > > |
| struct | GetGeometry< T, IfPoly< T, void > > |
| struct | LineStringsCoordinate |
| struct | PointSearchResult |
| struct | PointVincinity |
| struct | ProjectedPointInfo |
| struct | SegmentSearch |
| struct | SelfIntersection2d |
| struct | SelfIntersectionLong |
Typedefs | |
| using | IndexedSegment2d = std::pair< BasicSegment2d, size_t > |
| using | IndexedSegmentTree = bgi::rtree< IndexedSegment2d, bgi::linear< 4 > > |
| using | SegmentMap = std::map< size_t, LineStringsCoordinate > |
| using | SegmentTree = bgi::rtree< BasicSegment2d, bgi::linear< 4 > > |
| using | SelfIntersections2d = std::vector< SelfIntersection2d > |
Enumerations | |
| enum | Convexity { Convexity::Concave, Convexity::Convex, Convexity::ConvexSharp } |
Functions | |
| template<typename LineString2dT > | |
| void | checkForInversion (const LineString2dT &oldLS, const BasicLineString2d &offsetLS, const double distance, const double epsilon=1.e-7) |
| checkForInversion asserts that a shifted line string is not inverted relative to the original line string by checking the distance of those More... | |
| BasicPolygons2d | convexPartition (const BasicPolygon2d &poly) |
| auto | crossProd (const BasicPoint2d &p1, const BasicPoint2d &p2) |
| auto | crossProd (const BasicPoint3d &p1, const BasicPoint3d &p2) |
| auto | crossProd (const Eigen::Matrix< double, 2, 1 > &p1, const Eigen::Matrix< double, 2, 1 > &p2) |
| template<typename LineString2dT > | |
| std::vector< BasicLineString2d > | extractConvex (const LineString2dT &lineString, const double distance) |
| extractConvex get convex parts of line string offset by distance. More... | |
| PointSearchResult | findNextPoint (const SelfIntersections2d &curSegIntersections, const BasicSegment2d &seg, const double lastS, const size_t i) |
| findNextPoint find next point to walk on a line strings join operation More... | |
| template<typename LineStringT , typename BasicPointT > | |
| auto | findPoint (const LineStringT &ls, const BasicPointT &p) |
| template<typename HybridLineStringT > | |
| BasicPoint2d | fromArcCoords (const HybridLineStringT &hLineString, const BasicPoint2d &projStart, const size_t startIdx, const size_t endIdx, const double distance) |
| template<typename LineString2dT > | |
| Convexity | getConvexity (const LineString2dT &lineString, const size_t idx, const PointVincinity &pv, const bool offsetPositive) |
| Optional< size_t > | getLowestSAbove (const SelfIntersections2d &selfIntersections, const double minS) |
| getLowestSAbove find self-intersection nearest to the given start point along a segment More... | |
| SelfIntersections2d | getSelfIntersectionsAt (const IndexedSegmentTree &tree, const size_t segToCheck, const BasicSegment2d &seg) |
| getSelfIntersectionsAt find list of intersections based on a segment search tree More... | |
| template<> | |
| BasicLineString2d | invert (const BasicLineString2d &ls) |
| template<> | |
| BasicLineString3d | invert (const BasicLineString3d &ls) |
| template<typename LineStringT > | |
| LineStringT | invert (const LineStringT &ls) |
| template<typename LineString2dT > | |
| bool | isConvex (const LineString2dT &lineString, const size_t idx, const bool offsetPositive) |
| template<typename LineStringT , typename BasicPointT > | |
| bool | isLeftOf (const LineStringT &ls, const BasicPointT &p, const ProjectedPointInfo< BasicPointT > &ppInfo) |
| BasicLineString2d | joinSubStrings (const std::vector< BasicLineString2d > &convexSubStrings, const IndexedSegmentTree &tree, const SegmentMap &segMap) |
| joinSubStrings create one line string of several ones by walking along them and joining them at the first intersection More... | |
| template<typename LineString2dT > | |
| BasicPoint2d | lateralShiftPointAtIndex (const LineString2dT &lineString, const int idx, const double distance) |
| create a point by moving distance laterally from the linestring at the point idx. The direction is the average of the directions orthogonal to the segments neighbouring the point. More... | |
| IndexedSegmentTree | makeIndexedSegmenTree (const BasicLineString2d &lineString) |
| makeIndexedSegmenTree create search tree of segments with indices More... | |
| template<typename LineString2dT > | |
| SegmentTree | makeSegmentTree (const LineString2dT &lineString) |
| makeIndexedSegmenTree create search tree of segments More... | |
| SegmentSearch | makeTree (const std::vector< BasicLineString2d > &convexSubStrings) |
| makeTree create search tree of segments from line strings More... | |
| template<typename LineString2dT > | |
| PointVincinity | makeVincinity (const LineString2dT &lineString, const size_t idx) |
| makeVincinity create pair of preceding and following point on a line string More... | |
| template<typename PointT > | |
| bool | pointIsLeftOf (const PointT &pSeg1, const PointT &pSeg2, const PointT &p) |
| BasicPoint2d | project (const BasicLineString2d &lineString, const BasicPoint2d &pointToProject) |
| BasicPoint3d | project (const BasicLineString3d &lineString, const BasicPoint3d &pointToProject) |
| BasicPoint2d | project (const CompoundHybridLineString2d &lineString, const BasicPoint2d &pointToProject) |
| BasicPoint3d | project (const CompoundHybridLineString3d &lineString, const BasicPoint3d &pointToProject) |
| BasicPoint2d | project (const ConstHybridLineString2d &lineString, const BasicPoint2d &pointToProject) |
| BasicPoint3d | project (const ConstHybridLineString3d &lineString, const BasicPoint3d &pointToProject) |
| std::pair< BasicPoint2d, BasicPoint2d > | projectedBorderPoint2d (const CompoundHybridPolygon2d &l1, const CompoundHybridPolygon2d &l2) |
| std::pair< BasicPoint2d, BasicPoint2d > | projectedBorderPoint2d (const ConstHybridPolygon2d &l1, const ConstHybridPolygon2d &l2) |
| std::pair< BasicPoint3d, BasicPoint3d > | projectedBorderPoint3d (const CompoundHybridPolygon3d &l1, const CompoundHybridPolygon3d &l2) |
| std::pair< BasicPoint3d, BasicPoint3d > | projectedBorderPoint3d (const ConstHybridPolygon3d &l1, const ConstHybridPolygon3d &l2) |
| std::pair< BasicPoint2d, BasicPoint2d > | projectedPoint2d (const BasicLineString2d &l1, const BasicLineString2d &l2) |
| std::pair< BasicPoint2d, BasicPoint2d > | projectedPoint2d (const BasicLineString2d &l1, const ConstHybridLineString2d &l2) |
| std::pair< BasicPoint2d, BasicPoint2d > | projectedPoint2d (const CompoundHybridLineString2d &l1, const CompoundHybridLineString2d &l2) |
| std::pair< BasicPoint2d, BasicPoint2d > | projectedPoint2d (const CompoundHybridLineString2d &l1, const ConstHybridLineString2d &l2) |
| std::pair< BasicPoint2d, BasicPoint2d > | projectedPoint2d (const ConstHybridLineString2d &l1, const BasicLineString2d &l2) |
| std::pair< BasicPoint2d, BasicPoint2d > | projectedPoint2d (const ConstHybridLineString2d &l1, const CompoundHybridLineString2d &l2) |
| std::pair< BasicPoint2d, BasicPoint2d > | projectedPoint2d (const ConstHybridLineString2d &l1, const ConstHybridLineString2d &l2) |
| std::pair< BasicPoint3d, BasicPoint3d > | projectedPoint3d (const BasicLineString3d &l1, const BasicLineString3d &l2) |
| std::pair< BasicPoint3d, BasicPoint3d > | projectedPoint3d (const BasicLineString3d &l1, const ConstHybridLineString3d &l2) |
| std::pair< BasicPoint3d, BasicPoint3d > | projectedPoint3d (const CompoundHybridLineString3d &l1, const CompoundHybridLineString3d &l2) |
| std::pair< BasicPoint3d, BasicPoint3d > | projectedPoint3d (const CompoundHybridLineString3d &l1, const ConstHybridLineString3d &l2) |
| std::pair< BasicPoint3d, BasicPoint3d > | projectedPoint3d (const ConstHybridLineString3d &l1, const BasicLineString3d &l2) |
| std::pair< BasicPoint3d, BasicPoint3d > | projectedPoint3d (const ConstHybridLineString3d &l1, const CompoundHybridLineString3d &l2) |
| std::pair< BasicPoint3d, BasicPoint3d > | projectedPoint3d (const ConstHybridLineString3d &l1, const ConstHybridLineString3d &l2) |
| BasicLineString2d | removeSelfIntersections (const BasicLineString2d &lineString) |
| template<typename LineString2dT > | |
| BasicLineString2d | shiftConvexSharp (const LineString2dT &lineString, const size_t idx, const double distance, const PointVincinity &pv) |
| shiftConvexSharp shift corner that is convex at a more than 90 degree angle. Inserts a new point to limit maximum offset More... | |
| template<typename LineString2dT > | |
| BasicPoint2d | shiftLateral (const LineString2dT &lineString, const size_t idx, const double offset, const PointVincinity &pv) |
| shiftLateral shift point along the bisectrix More... | |
| template<typename LineString2dT > | |
| BasicPoint2d | shiftPerpendicular (const LineString2dT &lineString, const size_t idx, const double distance, const bool asLast, const PointVincinity &pv) |
| shiftPerpendicular shift point perpendicular to either the preceding or following segment More... | |
| template<typename LineString2dT > | |
| std::pair< BasicLineString2d, bool > | shiftPoint (const LineString2dT &lineString, const double distance, const size_t idx, const PointVincinity &pv) |
| shiftPoint in lateral direction More... | |
| template<typename LineStringT , typename PointT > | |
| std::pair< double, ProjectedPointInfo< traits::BasicPointT< PointT > > > | signedDistanceImpl (const LineStringT lineString, const PointT &p) |
| template<typename LineStringT > | |
| BasicPoints2d | sortAlongS (const LineStringT &ls, const BasicPoints2d &points) |
| IndexedTriangles | triangulate (const BasicPolygon2d &poly) |
| using lanelet::geometry::internal::IndexedSegment2d = typedef std::pair<BasicSegment2d, size_t> |
Definition at line 269 of file geometry/impl/LineString.h.
| using lanelet::geometry::internal::IndexedSegmentTree = typedef bgi::rtree<IndexedSegment2d, bgi::linear<4> > |
Definition at line 270 of file geometry/impl/LineString.h.
| using lanelet::geometry::internal::SegmentMap = typedef std::map<size_t, LineStringsCoordinate> |
Definition at line 534 of file geometry/impl/LineString.h.
| using lanelet::geometry::internal::SegmentTree = typedef bgi::rtree<BasicSegment2d, bgi::linear<4> > |
Definition at line 271 of file geometry/impl/LineString.h.
| using lanelet::geometry::internal::SelfIntersections2d = typedef std::vector<SelfIntersection2d> |
Definition at line 24 of file geometry/impl/LineString.h.
|
strong |
| Enumerator | |
|---|---|
| Concave | |
| Convex | |
| ConvexSharp | |
Definition at line 222 of file geometry/impl/LineString.h.
|
inline |
checkForInversion asserts that a shifted line string is not inverted relative to the original line string by checking the distance of those
| oldLS | the original line string |
| offsetLS | the shifted line string |
| distance | shifting distance (left is positive) |
| epsilon | maximum allowed difference between requested and actual minimum offset |
Definition at line 423 of file geometry/impl/LineString.h.
| BasicPolygons2d lanelet::geometry::internal::convexPartition | ( | const BasicPolygon2d & | poly | ) |
Definition at line 453 of file PolygonTriangulationGeometry.cpp.
|
inline |
Definition at line 38 of file geometry/impl/LineString.h.
|
inline |
Definition at line 37 of file geometry/impl/LineString.h.
|
inline |
Definition at line 42 of file geometry/impl/LineString.h.
|
inline |
extractConvex get convex parts of line string offset by distance.
| lineString | original line string |
| distance | offset distance (left is positive) |
Definition at line 514 of file geometry/impl/LineString.h.
|
inline |
findNextPoint find next point to walk on a line strings join operation
| curSegIntersections | list of intersections on the current segment |
| seg | segment to evaluate |
| lastS | coordinate along the segment to start the search on |
| i | segment index |
Definition at line 382 of file geometry/impl/LineString.h.
| auto lanelet::geometry::internal::findPoint | ( | const LineStringT & | ls, |
| const BasicPointT & | p | ||
| ) |
Definition at line 47 of file geometry/impl/LineString.h.
| BasicPoint2d lanelet::geometry::internal::fromArcCoords | ( | const HybridLineStringT & | hLineString, |
| const BasicPoint2d & | projStart, | ||
| const size_t | startIdx, | ||
| const size_t | endIdx, | ||
| const double | distance | ||
| ) |
Definition at line 140 of file geometry/impl/LineString.h.
| Convexity lanelet::geometry::internal::getConvexity | ( | const LineString2dT & | lineString, |
| const size_t | idx, | ||
| const PointVincinity & | pv, | ||
| const bool | offsetPositive | ||
| ) |
Definition at line 225 of file geometry/impl/LineString.h.
|
inline |
getLowestSAbove find self-intersection nearest to the given start point along a segment
| selfIntersections | list of self-intersections |
| minS | start coordinate along the segment |
Definition at line 327 of file geometry/impl/LineString.h.
|
inline |
getSelfIntersectionsAt find list of intersections based on a segment search tree
| tree | segment search tree |
| segToCheck | the segment to be evaluated |
| seg | index of the segment to be evaluated |
Definition at line 347 of file geometry/impl/LineString.h.
|
inline |
Definition at line 62 of file geometry/impl/LineString.h.
|
inline |
Definition at line 67 of file geometry/impl/LineString.h.
| LineStringT lanelet::geometry::internal::invert | ( | const LineStringT & | ls | ) |
Definition at line 57 of file geometry/impl/LineString.h.
| bool lanelet::geometry::internal::isConvex | ( | const LineString2dT & | lineString, |
| const size_t | idx, | ||
| const bool | offsetPositive | ||
| ) |
Definition at line 214 of file geometry/impl/LineString.h.
| bool lanelet::geometry::internal::isLeftOf | ( | const LineStringT & | ls, |
| const BasicPointT & | p, | ||
| const ProjectedPointInfo< BasicPointT > & | ppInfo | ||
| ) |
Definition at line 78 of file geometry/impl/LineString.h.
|
inline |
joinSubStrings create one line string of several ones by walking along them and joining them at the first intersection
| convexSubStrings | list of substrings. Walk will start at the first element and continue until the list is exhausted |
| tree | search tree |
| segMap | mapping from segment index of uncut linestring to linestring and segment index of substring |
Definition at line 572 of file geometry/impl/LineString.h.
| BasicPoint2d lanelet::geometry::internal::lateralShiftPointAtIndex | ( | const LineString2dT & | lineString, |
| const int | idx, | ||
| const double | distance | ||
| ) |
create a point by moving distance laterally from the linestring at the point idx. The direction is the average of the directions orthogonal to the segments neighbouring the point.
| lineString | lineString to operate on |
| idx | index of point to shift (negative means counting from back) |
| distance | to shift (left = positive) |
Definition at line 255 of file geometry/impl/LineString.h.
|
inline |
makeIndexedSegmenTree create search tree of segments with indices
| lineString | line string that the segments will be created from |
| InvalidInputError | if the line string size is below 2 |
Definition at line 307 of file geometry/impl/LineString.h.
|
inline |
makeIndexedSegmenTree create search tree of segments
| lineString | line string that the segments will be created from |
| InvalidInputError | if the line string size is below 2 |
Definition at line 285 of file geometry/impl/LineString.h.
|
inline |
makeTree create search tree of segments from line strings
| convexSubStrings | list of line strings |
Definition at line 547 of file geometry/impl/LineString.h.
| PointVincinity lanelet::geometry::internal::makeVincinity | ( | const LineString2dT & | lineString, |
| const size_t | idx | ||
| ) |
makeVincinity create pair of preceding and following point on a line string
| lineString | line string to evaluate |
| idx | index of point to create vincininty around |
Definition at line 169 of file geometry/impl/LineString.h.
| bool lanelet::geometry::internal::pointIsLeftOf | ( | const PointT & | pSeg1, |
| const PointT & | pSeg2, | ||
| const PointT & | p | ||
| ) |
Definition at line 52 of file geometry/impl/LineString.h.
| BasicPoint2d lanelet::geometry::internal::project | ( | const BasicLineString2d & | lineString, |
| const BasicPoint2d & | pointToProject | ||
| ) |
Definition at line 418 of file LineStringGeometry.cpp.
| BasicPoint3d lanelet::geometry::internal::project | ( | const BasicLineString3d & | lineString, |
| const BasicPoint3d & | pointToProject | ||
| ) |
Definition at line 421 of file LineStringGeometry.cpp.
| BasicPoint2d lanelet::geometry::internal::project | ( | const CompoundHybridLineString2d & | lineString, |
| const BasicPoint2d & | pointToProject | ||
| ) |
Definition at line 432 of file LineStringGeometry.cpp.
| BasicPoint3d lanelet::geometry::internal::project | ( | const CompoundHybridLineString3d & | lineString, |
| const BasicPoint3d & | pointToProject | ||
| ) |
Definition at line 435 of file LineStringGeometry.cpp.
| BasicPoint2d lanelet::geometry::internal::project | ( | const ConstHybridLineString2d & | lineString, |
| const BasicPoint2d & | pointToProject | ||
| ) |
Definition at line 425 of file LineStringGeometry.cpp.
| BasicPoint3d lanelet::geometry::internal::project | ( | const ConstHybridLineString3d & | lineString, |
| const BasicPoint3d & | pointToProject | ||
| ) |
Definition at line 428 of file LineStringGeometry.cpp.
| std::pair<BasicPoint2d, BasicPoint2d> lanelet::geometry::internal::projectedBorderPoint2d | ( | const CompoundHybridPolygon2d & | l1, |
| const CompoundHybridPolygon2d & | l2 | ||
| ) |
Definition at line 369 of file LineStringGeometry.cpp.
| std::pair<BasicPoint2d, BasicPoint2d> lanelet::geometry::internal::projectedBorderPoint2d | ( | const ConstHybridPolygon2d & | l1, |
| const ConstHybridPolygon2d & | l2 | ||
| ) |
Definition at line 364 of file LineStringGeometry.cpp.
| std::pair< BasicPoint3d, BasicPoint3d > lanelet::geometry::internal::projectedBorderPoint3d | ( | const CompoundHybridPolygon3d & | l1, |
| const CompoundHybridPolygon3d & | l2 | ||
| ) |
Definition at line 412 of file LineStringGeometry.cpp.
| std::pair< BasicPoint3d, BasicPoint3d > lanelet::geometry::internal::projectedBorderPoint3d | ( | const ConstHybridPolygon3d & | l1, |
| const ConstHybridPolygon3d & | l2 | ||
| ) |
Definition at line 407 of file LineStringGeometry.cpp.
| std::pair< BasicPoint2d, BasicPoint2d > lanelet::geometry::internal::projectedPoint2d | ( | const BasicLineString2d & | l1, |
| const BasicLineString2d & | l2 | ||
| ) |
Definition at line 360 of file LineStringGeometry.cpp.
| std::pair< BasicPoint2d, BasicPoint2d > lanelet::geometry::internal::projectedPoint2d | ( | const BasicLineString2d & | l1, |
| const ConstHybridLineString2d & | l2 | ||
| ) |
Definition at line 356 of file LineStringGeometry.cpp.
| std::pair< BasicPoint2d, BasicPoint2d > lanelet::geometry::internal::projectedPoint2d | ( | const CompoundHybridLineString2d & | l1, |
| const CompoundHybridLineString2d & | l2 | ||
| ) |
Definition at line 332 of file LineStringGeometry.cpp.
| std::pair< BasicPoint2d, BasicPoint2d > lanelet::geometry::internal::projectedPoint2d | ( | const CompoundHybridLineString2d & | l1, |
| const ConstHybridLineString2d & | l2 | ||
| ) |
Definition at line 342 of file LineStringGeometry.cpp.
| std::pair< BasicPoint2d, BasicPoint2d > lanelet::geometry::internal::projectedPoint2d | ( | const ConstHybridLineString2d & | l1, |
| const BasicLineString2d & | l2 | ||
| ) |
Definition at line 352 of file LineStringGeometry.cpp.
| std::pair< BasicPoint2d, BasicPoint2d > lanelet::geometry::internal::projectedPoint2d | ( | const ConstHybridLineString2d & | l1, |
| const CompoundHybridLineString2d & | l2 | ||
| ) |
Definition at line 337 of file LineStringGeometry.cpp.
| std::pair< BasicPoint2d, BasicPoint2d > lanelet::geometry::internal::projectedPoint2d | ( | const ConstHybridLineString2d & | l1, |
| const ConstHybridLineString2d & | l2 | ||
| ) |
Definition at line 347 of file LineStringGeometry.cpp.
| std::pair< BasicPoint3d, BasicPoint3d > lanelet::geometry::internal::projectedPoint3d | ( | const BasicLineString3d & | l1, |
| const BasicLineString3d & | l2 | ||
| ) |
Definition at line 403 of file LineStringGeometry.cpp.
| std::pair< BasicPoint3d, BasicPoint3d > lanelet::geometry::internal::projectedPoint3d | ( | const BasicLineString3d & | l1, |
| const ConstHybridLineString3d & | l2 | ||
| ) |
Definition at line 399 of file LineStringGeometry.cpp.
| std::pair< BasicPoint3d, BasicPoint3d > lanelet::geometry::internal::projectedPoint3d | ( | const CompoundHybridLineString3d & | l1, |
| const CompoundHybridLineString3d & | l2 | ||
| ) |
Definition at line 375 of file LineStringGeometry.cpp.
| std::pair< BasicPoint3d, BasicPoint3d > lanelet::geometry::internal::projectedPoint3d | ( | const CompoundHybridLineString3d & | l1, |
| const ConstHybridLineString3d & | l2 | ||
| ) |
Definition at line 385 of file LineStringGeometry.cpp.
| std::pair< BasicPoint3d, BasicPoint3d > lanelet::geometry::internal::projectedPoint3d | ( | const ConstHybridLineString3d & | l1, |
| const BasicLineString3d & | l2 | ||
| ) |
Definition at line 395 of file LineStringGeometry.cpp.
| std::pair< BasicPoint3d, BasicPoint3d > lanelet::geometry::internal::projectedPoint3d | ( | const ConstHybridLineString3d & | l1, |
| const CompoundHybridLineString3d & | l2 | ||
| ) |
Definition at line 380 of file LineStringGeometry.cpp.
| std::pair< BasicPoint3d, BasicPoint3d > lanelet::geometry::internal::projectedPoint3d | ( | const ConstHybridLineString3d & | l1, |
| const ConstHybridLineString3d & | l2 | ||
| ) |
Definition at line 390 of file LineStringGeometry.cpp.
|
inline |
Definition at line 394 of file geometry/impl/LineString.h.
|
inline |
shiftConvexSharp shift corner that is convex at a more than 90 degree angle. Inserts a new point to limit maximum offset
| lineString | original line string |
| idx | index of point to shft |
| distance | offset distance (left is positive) to shift |
| pv | following and preveding point on line string |
Definition at line 468 of file geometry/impl/LineString.h.
| BasicPoint2d lanelet::geometry::internal::shiftLateral | ( | const LineString2dT & | lineString, |
| const size_t | idx, | ||
| const double | offset, | ||
| const PointVincinity & | pv | ||
| ) |
shiftLateral shift point along the bisectrix
| lineString | original line string |
| idx | index of point to shft |
| offset | offset distance (left is positive) to shift |
| pv | following and preveding point on line string |
Definition at line 191 of file geometry/impl/LineString.h.
|
inline |
shiftPerpendicular shift point perpendicular to either the preceding or following segment
| lineString | original line string |
| idx | index of point to shft |
| distance | offset distance (left is positive) to shift |
| asLast | use preceding segment as reference if true, else use following |
| pv | following and preveding point on line string |
Definition at line 445 of file geometry/impl/LineString.h.
|
inline |
shiftPoint in lateral direction
| lineString | original line string |
| distance | offset distance (left is positive) to shift |
| idx | index of point to shift |
| pv | following and preveding point on line string |
Definition at line 492 of file geometry/impl/LineString.h.
| std::pair<double, ProjectedPointInfo<traits::BasicPointT<PointT> > > lanelet::geometry::internal::signedDistanceImpl | ( | const LineStringT | lineString, |
| const PointT & | p | ||
| ) |
Definition at line 128 of file geometry/impl/LineString.h.
| BasicPoints2d lanelet::geometry::internal::sortAlongS | ( | const LineStringT & | ls, |
| const BasicPoints2d & | points | ||
| ) |
Definition at line 237 of file geometry/impl/LineString.h.
| IndexedTriangles lanelet::geometry::internal::triangulate | ( | const BasicPolygon2d & | poly | ) |
Definition at line 454 of file PolygonTriangulationGeometry.cpp.