Classes | Typedefs | Enumerations | Functions
lanelet::geometry::internal Namespace Reference

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< BasicLineString2dextractConvex (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, BasicPoint2dprojectedBorderPoint2d (const CompoundHybridPolygon2d &l1, const CompoundHybridPolygon2d &l2)
 
std::pair< BasicPoint2d, BasicPoint2dprojectedBorderPoint2d (const ConstHybridPolygon2d &l1, const ConstHybridPolygon2d &l2)
 
std::pair< BasicPoint3d, BasicPoint3dprojectedBorderPoint3d (const CompoundHybridPolygon3d &l1, const CompoundHybridPolygon3d &l2)
 
std::pair< BasicPoint3d, BasicPoint3dprojectedBorderPoint3d (const ConstHybridPolygon3d &l1, const ConstHybridPolygon3d &l2)
 
std::pair< BasicPoint2d, BasicPoint2dprojectedPoint2d (const BasicLineString2d &l1, const BasicLineString2d &l2)
 
std::pair< BasicPoint2d, BasicPoint2dprojectedPoint2d (const BasicLineString2d &l1, const ConstHybridLineString2d &l2)
 
std::pair< BasicPoint2d, BasicPoint2dprojectedPoint2d (const CompoundHybridLineString2d &l1, const CompoundHybridLineString2d &l2)
 
std::pair< BasicPoint2d, BasicPoint2dprojectedPoint2d (const CompoundHybridLineString2d &l1, const ConstHybridLineString2d &l2)
 
std::pair< BasicPoint2d, BasicPoint2dprojectedPoint2d (const ConstHybridLineString2d &l1, const BasicLineString2d &l2)
 
std::pair< BasicPoint2d, BasicPoint2dprojectedPoint2d (const ConstHybridLineString2d &l1, const CompoundHybridLineString2d &l2)
 
std::pair< BasicPoint2d, BasicPoint2dprojectedPoint2d (const ConstHybridLineString2d &l1, const ConstHybridLineString2d &l2)
 
std::pair< BasicPoint3d, BasicPoint3dprojectedPoint3d (const BasicLineString3d &l1, const BasicLineString3d &l2)
 
std::pair< BasicPoint3d, BasicPoint3dprojectedPoint3d (const BasicLineString3d &l1, const ConstHybridLineString3d &l2)
 
std::pair< BasicPoint3d, BasicPoint3dprojectedPoint3d (const CompoundHybridLineString3d &l1, const CompoundHybridLineString3d &l2)
 
std::pair< BasicPoint3d, BasicPoint3dprojectedPoint3d (const CompoundHybridLineString3d &l1, const ConstHybridLineString3d &l2)
 
std::pair< BasicPoint3d, BasicPoint3dprojectedPoint3d (const ConstHybridLineString3d &l1, const BasicLineString3d &l2)
 
std::pair< BasicPoint3d, BasicPoint3dprojectedPoint3d (const ConstHybridLineString3d &l1, const CompoundHybridLineString3d &l2)
 
std::pair< BasicPoint3d, BasicPoint3dprojectedPoint3d (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)
 

Typedef Documentation

◆ IndexedSegment2d

Definition at line 269 of file geometry/impl/LineString.h.

◆ IndexedSegmentTree

using lanelet::geometry::internal::IndexedSegmentTree = typedef bgi::rtree<IndexedSegment2d, bgi::linear<4> >

Definition at line 270 of file geometry/impl/LineString.h.

◆ SegmentMap

Definition at line 534 of file geometry/impl/LineString.h.

◆ SegmentTree

using lanelet::geometry::internal::SegmentTree = typedef bgi::rtree<BasicSegment2d, bgi::linear<4> >

Definition at line 271 of file geometry/impl/LineString.h.

◆ SelfIntersections2d

Definition at line 24 of file geometry/impl/LineString.h.

Enumeration Type Documentation

◆ Convexity

Enumerator
Concave 
Convex 
ConvexSharp 

Definition at line 222 of file geometry/impl/LineString.h.

Function Documentation

◆ checkForInversion()

template<typename LineString2dT >
void lanelet::geometry::internal::checkForInversion ( const LineString2dT &  oldLS,
const BasicLineString2d offsetLS,
const double  distance,
const double  epsilon = 1.e-7 
)
inline

checkForInversion asserts that a shifted line string is not inverted relative to the original line string by checking the distance of those

Parameters
oldLSthe original line string
offsetLSthe shifted line string
distanceshifting distance (left is positive)
epsilonmaximum allowed difference between requested and actual minimum offset

Definition at line 423 of file geometry/impl/LineString.h.

◆ convexPartition()

BasicPolygons2d lanelet::geometry::internal::convexPartition ( const BasicPolygon2d poly)

Definition at line 453 of file PolygonTriangulationGeometry.cpp.

◆ crossProd() [1/3]

auto lanelet::geometry::internal::crossProd ( const BasicPoint2d p1,
const BasicPoint2d p2 
)
inline

Definition at line 38 of file geometry/impl/LineString.h.

◆ crossProd() [2/3]

auto lanelet::geometry::internal::crossProd ( const BasicPoint3d p1,
const BasicPoint3d p2 
)
inline

Definition at line 37 of file geometry/impl/LineString.h.

◆ crossProd() [3/3]

auto lanelet::geometry::internal::crossProd ( const Eigen::Matrix< double, 2, 1 > &  p1,
const Eigen::Matrix< double, 2, 1 > &  p2 
)
inline

Definition at line 42 of file geometry/impl/LineString.h.

◆ extractConvex()

template<typename LineString2dT >
std::vector<BasicLineString2d> lanelet::geometry::internal::extractConvex ( const LineString2dT &  lineString,
const double  distance 
)
inline

extractConvex get convex parts of line string offset by distance.

Parameters
lineStringoriginal line string
distanceoffset distance (left is positive)
Returns
list of line strings, each one is convex. Guaranteed to intersect at non-convex parts

Definition at line 514 of file geometry/impl/LineString.h.

◆ findNextPoint()

PointSearchResult lanelet::geometry::internal::findNextPoint ( const SelfIntersections2d curSegIntersections,
const BasicSegment2d seg,
const double  lastS,
const size_t  i 
)
inline

findNextPoint find next point to walk on a line strings join operation

Parameters
curSegIntersectionslist of intersections on the current segment
segsegment to evaluate
lastScoordinate along the segment to start the search on
isegment index
Returns
coordinate of next point on the walk

Definition at line 382 of file geometry/impl/LineString.h.

◆ findPoint()

template<typename LineStringT , typename BasicPointT >
auto lanelet::geometry::internal::findPoint ( const LineStringT &  ls,
const BasicPointT p 
)

Definition at line 47 of file geometry/impl/LineString.h.

◆ fromArcCoords()

template<typename HybridLineStringT >
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.

◆ getConvexity()

template<typename LineString2dT >
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.

◆ getLowestSAbove()

Optional<size_t> lanelet::geometry::internal::getLowestSAbove ( const SelfIntersections2d selfIntersections,
const double  minS 
)
inline

getLowestSAbove find self-intersection nearest to the given start point along a segment

Parameters
selfIntersectionslist of self-intersections
minSstart coordinate along the segment
Returns
index of the search result in selfIntersections

Definition at line 327 of file geometry/impl/LineString.h.

◆ getSelfIntersectionsAt()

SelfIntersections2d lanelet::geometry::internal::getSelfIntersectionsAt ( const IndexedSegmentTree tree,
const size_t  segToCheck,
const BasicSegment2d seg 
)
inline

getSelfIntersectionsAt find list of intersections based on a segment search tree

Parameters
treesegment search tree
segToCheckthe segment to be evaluated
segindex of the segment to be evaluated
Returns
a list of intersections involving the given segment

Definition at line 347 of file geometry/impl/LineString.h.

◆ invert() [1/3]

template<>
BasicLineString2d lanelet::geometry::internal::invert ( const BasicLineString2d ls)
inline

Definition at line 62 of file geometry/impl/LineString.h.

◆ invert() [2/3]

template<>
BasicLineString3d lanelet::geometry::internal::invert ( const BasicLineString3d ls)
inline

Definition at line 67 of file geometry/impl/LineString.h.

◆ invert() [3/3]

template<typename LineStringT >
LineStringT lanelet::geometry::internal::invert ( const LineStringT &  ls)

Definition at line 57 of file geometry/impl/LineString.h.

◆ isConvex()

template<typename LineString2dT >
bool lanelet::geometry::internal::isConvex ( const LineString2dT &  lineString,
const size_t  idx,
const bool  offsetPositive 
)
Returns
Point and true if convex

Definition at line 214 of file geometry/impl/LineString.h.

◆ isLeftOf()

template<typename LineStringT , typename BasicPointT >
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.

◆ joinSubStrings()

BasicLineString2d lanelet::geometry::internal::joinSubStrings ( const std::vector< BasicLineString2d > &  convexSubStrings,
const IndexedSegmentTree tree,
const SegmentMap segMap 
)
inline

joinSubStrings create one line string of several ones by walking along them and joining them at the first intersection

Parameters
convexSubStringslist of substrings. Walk will start at the first element and continue until the list is exhausted
treesearch tree
segMapmapping from segment index of uncut linestring to linestring and segment index of substring
Returns
joined line string

Definition at line 572 of file geometry/impl/LineString.h.

◆ lateralShiftPointAtIndex()

template<typename LineString2dT >
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.

Parameters
lineStringlineString to operate on
idxindex of point to shift (negative means counting from back)
distanceto shift (left = positive)

Definition at line 255 of file geometry/impl/LineString.h.

◆ makeIndexedSegmenTree()

IndexedSegmentTree lanelet::geometry::internal::makeIndexedSegmenTree ( const BasicLineString2d lineString)
inline

makeIndexedSegmenTree create search tree of segments with indices

Parameters
lineStringline string that the segments will be created from
Exceptions
InvalidInputErrorif the line string size is below 2
Returns
a search tree

Definition at line 307 of file geometry/impl/LineString.h.

◆ makeSegmentTree()

template<typename LineString2dT >
SegmentTree lanelet::geometry::internal::makeSegmentTree ( const LineString2dT &  lineString)
inline

makeIndexedSegmenTree create search tree of segments

Parameters
lineStringline string that the segments will be created from
Exceptions
InvalidInputErrorif the line string size is below 2
Returns
a search tree

Definition at line 285 of file geometry/impl/LineString.h.

◆ makeTree()

SegmentSearch lanelet::geometry::internal::makeTree ( const std::vector< BasicLineString2d > &  convexSubStrings)
inline

makeTree create search tree of segments from line strings

Parameters
convexSubStringslist of line strings
Returns
search tree and mapping from segment index of uncut linestring to linestring and segment index of substring

Definition at line 547 of file geometry/impl/LineString.h.

◆ makeVincinity()

template<typename LineString2dT >
PointVincinity lanelet::geometry::internal::makeVincinity ( const LineString2dT &  lineString,
const size_t  idx 
)

makeVincinity create pair of preceding and following point on a line string

Parameters
lineStringline string to evaluate
idxindex of point to create vincininty around
Returns
pair of preceding and following point (zero if not applicable)

Definition at line 169 of file geometry/impl/LineString.h.

◆ pointIsLeftOf()

template<typename PointT >
bool lanelet::geometry::internal::pointIsLeftOf ( const PointT &  pSeg1,
const PointT &  pSeg2,
const PointT &  p 
)

Definition at line 52 of file geometry/impl/LineString.h.

◆ project() [1/6]

BasicPoint2d lanelet::geometry::internal::project ( const BasicLineString2d lineString,
const BasicPoint2d pointToProject 
)

Definition at line 418 of file LineStringGeometry.cpp.

◆ project() [2/6]

BasicPoint3d lanelet::geometry::internal::project ( const BasicLineString3d lineString,
const BasicPoint3d pointToProject 
)

Definition at line 421 of file LineStringGeometry.cpp.

◆ project() [3/6]

BasicPoint2d lanelet::geometry::internal::project ( const CompoundHybridLineString2d lineString,
const BasicPoint2d pointToProject 
)

Definition at line 432 of file LineStringGeometry.cpp.

◆ project() [4/6]

BasicPoint3d lanelet::geometry::internal::project ( const CompoundHybridLineString3d lineString,
const BasicPoint3d pointToProject 
)

Definition at line 435 of file LineStringGeometry.cpp.

◆ project() [5/6]

BasicPoint2d lanelet::geometry::internal::project ( const ConstHybridLineString2d lineString,
const BasicPoint2d pointToProject 
)

Definition at line 425 of file LineStringGeometry.cpp.

◆ project() [6/6]

BasicPoint3d lanelet::geometry::internal::project ( const ConstHybridLineString3d lineString,
const BasicPoint3d pointToProject 
)

Definition at line 428 of file LineStringGeometry.cpp.

◆ projectedBorderPoint2d() [1/2]

std::pair<BasicPoint2d, BasicPoint2d> lanelet::geometry::internal::projectedBorderPoint2d ( const CompoundHybridPolygon2d l1,
const CompoundHybridPolygon2d l2 
)

Definition at line 369 of file LineStringGeometry.cpp.

◆ projectedBorderPoint2d() [2/2]

std::pair<BasicPoint2d, BasicPoint2d> lanelet::geometry::internal::projectedBorderPoint2d ( const ConstHybridPolygon2d l1,
const ConstHybridPolygon2d l2 
)

Definition at line 364 of file LineStringGeometry.cpp.

◆ projectedBorderPoint3d() [1/2]

std::pair< BasicPoint3d, BasicPoint3d > lanelet::geometry::internal::projectedBorderPoint3d ( const CompoundHybridPolygon3d l1,
const CompoundHybridPolygon3d l2 
)

Definition at line 412 of file LineStringGeometry.cpp.

◆ projectedBorderPoint3d() [2/2]

std::pair< BasicPoint3d, BasicPoint3d > lanelet::geometry::internal::projectedBorderPoint3d ( const ConstHybridPolygon3d l1,
const ConstHybridPolygon3d l2 
)

Definition at line 407 of file LineStringGeometry.cpp.

◆ projectedPoint2d() [1/7]

std::pair< BasicPoint2d, BasicPoint2d > lanelet::geometry::internal::projectedPoint2d ( const BasicLineString2d l1,
const BasicLineString2d l2 
)

Definition at line 360 of file LineStringGeometry.cpp.

◆ projectedPoint2d() [2/7]

std::pair< BasicPoint2d, BasicPoint2d > lanelet::geometry::internal::projectedPoint2d ( const BasicLineString2d l1,
const ConstHybridLineString2d l2 
)

Definition at line 356 of file LineStringGeometry.cpp.

◆ projectedPoint2d() [3/7]

std::pair< BasicPoint2d, BasicPoint2d > lanelet::geometry::internal::projectedPoint2d ( const CompoundHybridLineString2d l1,
const CompoundHybridLineString2d l2 
)

Definition at line 332 of file LineStringGeometry.cpp.

◆ projectedPoint2d() [4/7]

std::pair< BasicPoint2d, BasicPoint2d > lanelet::geometry::internal::projectedPoint2d ( const CompoundHybridLineString2d l1,
const ConstHybridLineString2d l2 
)

Definition at line 342 of file LineStringGeometry.cpp.

◆ projectedPoint2d() [5/7]

std::pair< BasicPoint2d, BasicPoint2d > lanelet::geometry::internal::projectedPoint2d ( const ConstHybridLineString2d l1,
const BasicLineString2d l2 
)

Definition at line 352 of file LineStringGeometry.cpp.

◆ projectedPoint2d() [6/7]

std::pair< BasicPoint2d, BasicPoint2d > lanelet::geometry::internal::projectedPoint2d ( const ConstHybridLineString2d l1,
const CompoundHybridLineString2d l2 
)

Definition at line 337 of file LineStringGeometry.cpp.

◆ projectedPoint2d() [7/7]

std::pair< BasicPoint2d, BasicPoint2d > lanelet::geometry::internal::projectedPoint2d ( const ConstHybridLineString2d l1,
const ConstHybridLineString2d l2 
)

Definition at line 347 of file LineStringGeometry.cpp.

◆ projectedPoint3d() [1/7]

std::pair< BasicPoint3d, BasicPoint3d > lanelet::geometry::internal::projectedPoint3d ( const BasicLineString3d l1,
const BasicLineString3d l2 
)

Definition at line 403 of file LineStringGeometry.cpp.

◆ projectedPoint3d() [2/7]

std::pair< BasicPoint3d, BasicPoint3d > lanelet::geometry::internal::projectedPoint3d ( const BasicLineString3d l1,
const ConstHybridLineString3d l2 
)

Definition at line 399 of file LineStringGeometry.cpp.

◆ projectedPoint3d() [3/7]

std::pair< BasicPoint3d, BasicPoint3d > lanelet::geometry::internal::projectedPoint3d ( const CompoundHybridLineString3d l1,
const CompoundHybridLineString3d l2 
)

Definition at line 375 of file LineStringGeometry.cpp.

◆ projectedPoint3d() [4/7]

std::pair< BasicPoint3d, BasicPoint3d > lanelet::geometry::internal::projectedPoint3d ( const CompoundHybridLineString3d l1,
const ConstHybridLineString3d l2 
)

Definition at line 385 of file LineStringGeometry.cpp.

◆ projectedPoint3d() [5/7]

std::pair< BasicPoint3d, BasicPoint3d > lanelet::geometry::internal::projectedPoint3d ( const ConstHybridLineString3d l1,
const BasicLineString3d l2 
)

Definition at line 395 of file LineStringGeometry.cpp.

◆ projectedPoint3d() [6/7]

std::pair< BasicPoint3d, BasicPoint3d > lanelet::geometry::internal::projectedPoint3d ( const ConstHybridLineString3d l1,
const CompoundHybridLineString3d l2 
)

Definition at line 380 of file LineStringGeometry.cpp.

◆ projectedPoint3d() [7/7]

std::pair< BasicPoint3d, BasicPoint3d > lanelet::geometry::internal::projectedPoint3d ( const ConstHybridLineString3d l1,
const ConstHybridLineString3d l2 
)

Definition at line 390 of file LineStringGeometry.cpp.

◆ removeSelfIntersections()

BasicLineString2d lanelet::geometry::internal::removeSelfIntersections ( const BasicLineString2d lineString)
inline

Definition at line 394 of file geometry/impl/LineString.h.

◆ shiftConvexSharp()

template<typename LineString2dT >
BasicLineString2d lanelet::geometry::internal::shiftConvexSharp ( const LineString2dT &  lineString,
const size_t  idx,
const double  distance,
const PointVincinity pv 
)
inline

shiftConvexSharp shift corner that is convex at a more than 90 degree angle. Inserts a new point to limit maximum offset

Parameters
lineStringoriginal line string
idxindex of point to shft
distanceoffset distance (left is positive) to shift
pvfollowing and preveding point on line string
Returns
shifted points

Definition at line 468 of file geometry/impl/LineString.h.

◆ shiftLateral()

template<typename LineString2dT >
BasicPoint2d lanelet::geometry::internal::shiftLateral ( const LineString2dT &  lineString,
const size_t  idx,
const double  offset,
const PointVincinity pv 
)

shiftLateral shift point along the bisectrix

Parameters
lineStringoriginal line string
idxindex of point to shft
offsetoffset distance (left is positive) to shift
pvfollowing and preveding point on line string
Returns
shifted point

Definition at line 191 of file geometry/impl/LineString.h.

◆ shiftPerpendicular()

template<typename LineString2dT >
BasicPoint2d lanelet::geometry::internal::shiftPerpendicular ( const LineString2dT &  lineString,
const size_t  idx,
const double  distance,
const bool  asLast,
const PointVincinity pv 
)
inline

shiftPerpendicular shift point perpendicular to either the preceding or following segment

Parameters
lineStringoriginal line string
idxindex of point to shft
distanceoffset distance (left is positive) to shift
asLastuse preceding segment as reference if true, else use following
pvfollowing and preveding point on line string
Returns
shifted point

Definition at line 445 of file geometry/impl/LineString.h.

◆ shiftPoint()

template<typename LineString2dT >
std::pair<BasicLineString2d, bool> lanelet::geometry::internal::shiftPoint ( const LineString2dT &  lineString,
const double  distance,
const size_t  idx,
const PointVincinity pv 
)
inline

shiftPoint in lateral direction

Parameters
lineStringoriginal line string
distanceoffset distance (left is positive) to shift
idxindex of point to shift
pvfollowing and preveding point on line string
Returns
shifted point(s), bool indicating insertion was still convex

Definition at line 492 of file geometry/impl/LineString.h.

◆ signedDistanceImpl()

template<typename LineStringT , typename PointT >
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.

◆ sortAlongS()

template<typename LineStringT >
BasicPoints2d lanelet::geometry::internal::sortAlongS ( const LineStringT &  ls,
const BasicPoints2d points 
)

Definition at line 237 of file geometry/impl/LineString.h.

◆ triangulate()

IndexedTriangles lanelet::geometry::internal::triangulate ( const BasicPolygon2d poly)

Definition at line 454 of file PolygonTriangulationGeometry.cpp.



lanelet2_core
Author(s): Fabian Poggenhans
autogenerated on Thu Mar 6 2025 03:25:53