Classes | Namespaces | Typedefs | Enumerations | Functions
geometry/impl/LineString.h File Reference
#include <boost/geometry/algorithms/equals.hpp>
#include <boost/geometry/algorithms/intersection.hpp>
#include "lanelet2_core/geometry/GeometryHelper.h"
#include "lanelet2_core/geometry/Point.h"
#include "lanelet2_core/primitives/LineString.h"
#include "lanelet2_core/primitives/Traits.h"
Include dependency graph for geometry/impl/LineString.h:
This graph shows which files directly or indirectly include this file:

Go to the source code of this file.

Classes

struct  lanelet::geometry::internal::GetGeometry< T, IfLS< T, void > >
 
struct  lanelet::geometry::internal::LineStringsCoordinate
 
struct  lanelet::geometry::internal::PointSearchResult
 
struct  lanelet::geometry::internal::PointVincinity
 
struct  lanelet::geometry::internal::ProjectedPointInfo< PointT >
 
struct  lanelet::geometry::internal::SegmentSearch
 
struct  lanelet::geometry::internal::SelfIntersection2d
 
struct  lanelet::geometry::internal::SelfIntersectionLong
 

Namespaces

 lanelet
 
 lanelet::geometry
 
 lanelet::geometry::internal
 

Typedefs

using lanelet::geometry::internal::IndexedSegment2d = std::pair< BasicSegment2d, size_t >
 
using lanelet::geometry::internal::IndexedSegmentTree = bgi::rtree< IndexedSegment2d, bgi::linear< 4 > >
 
using lanelet::geometry::internal::SegmentMap = std::map< size_t, LineStringsCoordinate >
 
using lanelet::geometry::internal::SegmentTree = bgi::rtree< BasicSegment2d, bgi::linear< 4 > >
 
using lanelet::geometry::internal::SelfIntersections2d = std::vector< SelfIntersection2d >
 

Enumerations

enum  lanelet::geometry::internal::Convexity { lanelet::geometry::internal::Convexity::Concave, lanelet::geometry::internal::Convexity::Convex, lanelet::geometry::internal::Convexity::ConvexSharp }
 

Functions

template<typename LineStringT >
std::vector< double > lanelet::geometry::accumulatedLengthRatios (const LineStringT &lineString)
 
template<typename LineString1T , typename LineString2T >
std::pair< LineString1T, LineString2T > lanelet::geometry::align (LineString1T left, LineString2T right)
 inverts the two linestrings such that they are parallel More...
 
template<typename LineString2dT >
IfLS< LineString2dT, BoundingBox2d > lanelet::geometry::boundingBox2d (const LineString2dT &lineString)
 Get the surrounding axis-aligned bounding box in 2d. More...
 
template<typename LineString3dT >
IfLS< LineString3dT, BoundingBox3d > lanelet::geometry::boundingBox3d (const LineString3dT &lineString)
 Get the surrounding axis-aligned bounding box in 3d. More...
 
template<typename LineString2dT >
void lanelet::geometry::internal::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...
 
auto lanelet::geometry::internal::crossProd (const BasicPoint3d &p1, const BasicPoint3d &p2)
 
auto lanelet::geometry::internal::crossProd (const BasicPoint2d &p1, const BasicPoint2d &p2)
 
auto lanelet::geometry::internal::crossProd (const Eigen::Matrix< double, 2, 1 > &p1, const Eigen::Matrix< double, 2, 1 > &p2)
 
template<typename Point2dT >
double lanelet::geometry::curvature2d (const Point2dT &p1, const Point2dT &p2, const Point2dT &p3)
 
template<typename LineString3d1T , typename LineString3d2T >
IfLS2< LineString3d1T, LineString3d2T, double > lanelet::geometry::distance3d (const LineString3d1T &l1, const LineString3d2T &l2)
 
template<typename LineString2dT >
std::vector< BasicLineString2d > lanelet::geometry::internal::extractConvex (const LineString2dT &lineString, const double distance)
 extractConvex get convex parts of line string offset by distance. More...
 
PointSearchResult lanelet::geometry::internal::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 lanelet::geometry::internal::findPoint (const LineStringT &ls, const BasicPointT &p)
 
template<typename LineString2dT >
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 More...
 
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)
 
template<typename LineString2dT >
Convexity lanelet::geometry::internal::getConvexity (const LineString2dT &lineString, const size_t idx, const PointVincinity &pv, const bool offsetPositive)
 
Optional< size_t > lanelet::geometry::internal::getLowestSAbove (const SelfIntersections2d &selfIntersections, const double minS)
 getLowestSAbove find self-intersection nearest to the given start point along a segment More...
 
SelfIntersections2d lanelet::geometry::internal::getSelfIntersectionsAt (const IndexedSegmentTree &tree, const size_t segToCheck, const BasicSegment2d &seg)
 getSelfIntersectionsAt find list of intersections based on a segment search tree More...
 
template<typename LineStringT >
traits::BasicPointT< traits::PointType< LineStringT > > lanelet::geometry::interpolatedPointAtDistance (LineStringT lineString, double dist)
 
template<typename LineString3dT >
IfLS< LineString3dT, bool > lanelet::geometry::intersects3d (const LineString3dT &linestring, const LineString3dT &otherLinestring, double heightTolerance=3.)
 test whether two linestrings intersect in 3d. More...
 
template<typename LineStringT >
LineStringT lanelet::geometry::internal::invert (const LineStringT &ls)
 
template<>
BasicLineString2d lanelet::geometry::internal::invert (const BasicLineString2d &ls)
 
template<>
BasicLineString3d lanelet::geometry::internal::invert (const BasicLineString3d &ls)
 
template<typename LineString2dT >
bool lanelet::geometry::internal::isConvex (const LineString2dT &lineString, const size_t idx, const bool offsetPositive)
 
template<typename LineStringT , typename BasicPointT >
bool lanelet::geometry::internal::isLeftOf (const LineStringT &ls, const BasicPointT &p, const ProjectedPointInfo< BasicPointT > &ppInfo)
 
BasicLineString2d lanelet::geometry::internal::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 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. More...
 
template<typename LineStringT >
std::vector< double > lanelet::geometry::lengthRatios (const LineStringT &lineString)
 
IndexedSegmentTree lanelet::geometry::internal::makeIndexedSegmenTree (const BasicLineString2d &lineString)
 makeIndexedSegmenTree create search tree of segments with indices More...
 
template<typename LineString2dT >
SegmentTree lanelet::geometry::internal::makeSegmentTree (const LineString2dT &lineString)
 makeIndexedSegmenTree create search tree of segments More...
 
SegmentSearch lanelet::geometry::internal::makeTree (const std::vector< BasicLineString2d > &convexSubStrings)
 makeTree create search tree of segments from line strings More...
 
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 More...
 
template<typename LineStringT >
traits::PointType< LineStringT > lanelet::geometry::nearestPointAtDistance (LineStringT lineString, double dist)
 returns the cosest point to a position on the linestring More...
 
template<typename LineString2dT >
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. More...
 
template<typename LineString2dT >
BasicLineString2d lanelet::geometry::offsetNoThrow (const LineString2dT &lineString, double distance)
 create a linestring that is offset to the original one. the result. More...
 
template<typename PointT >
bool lanelet::geometry::internal::pointIsLeftOf (const PointT &pSeg1, const PointT &pSeg2, const PointT &p)
 
BasicPoint2d lanelet::geometry::internal::project (const BasicLineString2d &lineString, const BasicPoint2d &pointToProject)
 
BasicPoint3d lanelet::geometry::internal::project (const BasicLineString3d &lineString, const BasicPoint3d &pointToProject)
 
BasicPoint2d lanelet::geometry::internal::project (const ConstHybridLineString2d &lineString, const BasicPoint2d &pointToProject)
 
BasicPoint3d lanelet::geometry::internal::project (const ConstHybridLineString3d &lineString, const BasicPoint3d &pointToProject)
 
BasicPoint2d lanelet::geometry::internal::project (const CompoundHybridLineString2d &lineString, const BasicPoint2d &pointToProject)
 
BasicPoint3d lanelet::geometry::internal::project (const CompoundHybridLineString3d &lineString, const BasicPoint3d &pointToProject)
 
template<typename LineString3dT , typename >
BasicPoint3d lanelet::geometry::project (const LineString3dT &lineString, const BasicPoint3d &pointToProject)
 Projects the given point in 3d to the LineString. More...
 
template<typename LineString2dT , typename >
BasicPoint2d lanelet::geometry::project (const LineString2dT &lineString, const BasicPoint2d &pointToProject)
 Projects the given point in 2d to the LineString. More...
 
std::pair< BasicPoint2d, BasicPoint2d > lanelet::geometry::internal::projectedPoint2d (const ConstHybridLineString2d &l1, const ConstHybridLineString2d &l2)
 
std::pair< BasicPoint2d, BasicPoint2d > lanelet::geometry::internal::projectedPoint2d (const CompoundHybridLineString2d &l1, const CompoundHybridLineString2d &l2)
 
std::pair< BasicPoint2d, BasicPoint2d > lanelet::geometry::internal::projectedPoint2d (const ConstHybridLineString2d &l1, const CompoundHybridLineString2d &l2)
 
std::pair< BasicPoint2d, BasicPoint2d > lanelet::geometry::internal::projectedPoint2d (const CompoundHybridLineString2d &l1, const ConstHybridLineString2d &l2)
 
std::pair< BasicPoint2d, BasicPoint2d > lanelet::geometry::internal::projectedPoint2d (const ConstHybridLineString2d &l1, const BasicLineString2d &l2)
 
std::pair< BasicPoint2d, BasicPoint2d > lanelet::geometry::internal::projectedPoint2d (const BasicLineString2d &l1, const ConstHybridLineString2d &l2)
 
std::pair< BasicPoint2d, BasicPoint2d > lanelet::geometry::internal::projectedPoint2d (const BasicLineString2d &l1, const BasicLineString2d &l2)
 
template<typename LineString2dT >
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. More...
 
std::pair< BasicPoint3d, BasicPoint3d > lanelet::geometry::internal::projectedPoint3d (const ConstHybridLineString3d &l1, const ConstHybridLineString3d &l2)
 
std::pair< BasicPoint3d, BasicPoint3d > lanelet::geometry::internal::projectedPoint3d (const CompoundHybridLineString3d &l1, const CompoundHybridLineString3d &l2)
 
std::pair< BasicPoint3d, BasicPoint3d > lanelet::geometry::internal::projectedPoint3d (const ConstHybridLineString3d &l1, const CompoundHybridLineString3d &l2)
 
std::pair< BasicPoint3d, BasicPoint3d > lanelet::geometry::internal::projectedPoint3d (const CompoundHybridLineString3d &l1, const ConstHybridLineString3d &l2)
 
std::pair< BasicPoint3d, BasicPoint3d > lanelet::geometry::internal::projectedPoint3d (const ConstHybridLineString3d &l1, const BasicLineString3d &l2)
 
std::pair< BasicPoint3d, BasicPoint3d > lanelet::geometry::internal::projectedPoint3d (const BasicLineString3d &l1, const ConstHybridLineString3d &l2)
 
std::pair< BasicPoint3d, BasicPoint3d > lanelet::geometry::internal::projectedPoint3d (const BasicLineString3d &l1, const BasicLineString3d &l2)
 
template<typename LineString3dT >
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. More...
 
template<typename LineStringIterator >
double lanelet::geometry::rangedLength (LineStringIterator start, LineStringIterator end)
 
BasicLineString2d lanelet::geometry::internal::removeSelfIntersections (const BasicLineString2d &lineString)
 
template<typename LineString2dT >
BasicLineString2d lanelet::geometry::internal::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 lanelet::geometry::internal::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 lanelet::geometry::internal::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 > lanelet::geometry::internal::shiftPoint (const LineString2dT &lineString, const double distance, const size_t idx, const PointVincinity &pv)
 shiftPoint in lateral direction More...
 
template<typename LineString3dT >
double lanelet::geometry::signedDistance (const LineString3dT &lineString, const BasicPoint3d &p)
 
template<typename LineString2dT >
double lanelet::geometry::signedDistance (const LineString2dT &lineString, const BasicPoint2d &p)
 
template<typename LineStringT , typename PointT >
std::pair< double, ProjectedPointInfo< traits::BasicPointT< PointT > > > lanelet::geometry::internal::signedDistanceImpl (const LineStringT lineString, const PointT &p)
 
template<typename LineStringT >
BasicPoints2d lanelet::geometry::internal::sortAlongS (const LineStringT &ls, const BasicPoints2d &points)
 
template<typename LineString2dT >
ArcCoordinates lanelet::geometry::toArcCoordinates (const LineString2dT &lineString, const BasicPoint2d &point)
 Transform a point to the coordinates of the linestring. More...
 


lanelet2_core
Author(s): Fabian Poggenhans
autogenerated on Tue Jun 6 2023 02:23:32