2 #include <boost/geometry/algorithms/intersects.hpp> 3 #include <boost/geometry/algorithms/length.hpp> 4 #include <boost/geometry/geometries/register/linestring.hpp> 5 #include <boost/geometry/geometries/register/segment.hpp> 35 using boost::geometry::intersects;
36 using boost::geometry::length;
37 using boost::geometry::overlaps;
38 using boost::geometry::touches;
40 template <
typename LineStringIterator>
41 double rangedLength(LineStringIterator start, LineStringIterator end);
54 template <
typename LineStringT>
55 std::vector<double>
lengthRatios(
const LineStringT& lineString);
66 template <
typename LineStringT>
82 template <
typename LineString3dT>
98 template <
typename LineString2dT>
110 template <
typename Po
int2dT>
111 double curvature2d(
const Point2dT&
p1,
const Point2dT&
p2,
const Point2dT& p3);
121 template <
typename LineString2dT>
136 template <
typename LineStringT>
150 template <
typename LineStringT>
154 template <
typename LineString3dT>
155 IfLS<LineString3dT, BoundingBox3d>
boundingBox3d(
const LineString3dT& lineString);
158 template <
typename LineString2dT>
159 IfLS<LineString2dT, BoundingBox2d>
boundingBox2d(
const LineString2dT& lineString);
169 template <
typename LineString3dT,
typename = std::enable_if_t<traits::is3D<LineString3dT>()>>
173 template <
typename LineString2dT,
typename = std::enable_if_t<traits::is2D<LineString2dT>()>>
185 template <
typename LineString2dT>
186 IfLS<LineString2dT, std::pair<BasicPoint2d, BasicPoint2d>>
projectedPoint2d(
const LineString2dT& l1,
187 const LineString2dT& l2);
195 template <
typename LineString3dT>
196 IfLS<LineString3dT, std::pair<BasicPoint3d, BasicPoint3d>>
projectedPoint3d(
const LineString3dT& l1,
197 const LineString3dT& l2);
206 template <
typename LineString3dT>
207 IfLS<LineString3dT, bool>
intersects3d(
const LineString3dT& linestring,
const LineString3dT& otherLinestring,
208 double heightTolerance = 3.);
228 template <
typename LineString1T,
typename LineString2T>
229 std::pair<LineString1T, LineString2T>
align(LineString1T left, LineString2T right);
236 template <
typename LineString2dT>
252 template <
typename LineString2dT>
266 template <
typename LineString2dT>
IfLL< Lanelet1T, bool > intersects3d(const Lanelet1T &lanelet, const Lanelet2T &otherLanelet, double heightTolerance)
test whether two lanelets intersect in 2d.
BasicPoints3d BasicLineString3d
double rangedLength(LineStringIterator start, LineStringIterator end)
A Linestring that returns BasicPoint2d instead of Point2d.
A Compound linestring in 3d (returns Point3d)
Eigen::Vector3d BasicPoint3d
a simple 3d-point
BasicLineString2d offsetNoThrow(const LineString2dT &lineString, const double distance)
create a linestring that is offset to the original one. the result.
std::pair< PointT, PointT > Segment
traits::BasicPointT< traits::PointType< LineStringT > > interpolatedPointAtDistance(LineStringT lineString, double dist)
BasicPoint2d fromArcCoordinates(const LineString2dT &lineString, const ArcCoordinates &arcCoords)
create a point by moving laterally arcCoords.distance from the linestring point at arcCoords...
Segment< BasicPoint3d > BasicSegment3d
A hybrid compound linestring in 2d (returns BasicPoint2d)
std::vector< double > lengthRatios(const LineStringT &lineString)
BasicPoint3d project(const LineString3dT &lineString, const BasicPoint3d &pointToProject)
Projects the given point in 3d to the LineString.
A normal 3d linestring with immutable data.
traits::PointType< LineStringT > nearestPointAtDistance(LineStringT lineString, double dist)
returns the cosest point to a position on the linestring
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.
A normal 3d linestring with mutable data.
double curvature2d(const Point2dT &p1, const Point2dT &p2, const Point2dT &p3)
std::vector< double > accumulatedLengthRatios(const LineStringT &lineString)
A Compound linestring in 2d (returns Point2d)
BasicPoints2d BasicLineString2d
IfAr< AreaT, BoundingBox2d > boundingBox2d(const AreaT &area)
calculates an up-right 2d bounding box
Optional< double > distance
A Linestring that returns BasicPoint3d instead of Point3d.
Eigen::Matrix< double, 2, 1, Eigen::DontAlign > BasicPoint2d
a simple 2d-point
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:...
A hybrid compound linestring in 3d (returns BasicPoint3d)
double signedDistance(const LineString3dT &lineString, const BasicPoint3d &p)
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.
BasicLineString2d offset(const LineString2dT &lineString, const double distance)
create a linestring that is offset to the original one. Guarantees no self-intersections and no inver...
A normal 2d linestring with immutable data.
ArcCoordinates toArcCoordinates(const LineString2dT &lineString, const BasicPoint2d &point)
Transform a point to the coordinates of the linestring.
A normal 2d linestring with mutable data.
Segment< BasicPoint2d > BasicSegment2d
std::pair< LineString1T, LineString2T > align(LineString1T left, LineString2T right)
inverts the two linestrings such that they are parallel
IfAr< AreaT, BoundingBox3d > boundingBox3d(const AreaT &area)
calculates 3d bounding box