test_linestring.cpp
Go to the documentation of this file.
1 #include <gtest/gtest.h>
2 
3 #include <boost/geometry/algorithms/equals.hpp>
4 #include <vector>
5 
8 #include "primitives/Traits.h"
9 using namespace lanelet;
10 
11 class LineStringPoints : public ::testing::Test {
12  protected:
13  void SetUp() override {
14  Id id{1};
15  p11 = Point3d(++id, 0., 0., 0.);
16  p12 = Point3d(++id, 0., 1., 0.);
17  p13 = Point3d(++id, 0., 2., 1.);
18  p21 = Point3d(++id, 1., 0., 0.);
19  p22 = Point3d(++id, 2., 0., 0.);
20  p23 = Point3d(++id, -1., 2., 0.);
21  p31 = Point3d(++id, -1., 0., 2.);
22  p32 = Point3d(++id, 0., 1., 2.);
23  p33 = Point3d(++id, 1., 2., 2.);
24  p43 = Point3d(++id, 1, 1. + sqrt(3) / 3., 0.);
25  }
26 
27  public:
28  Point3d p11, p12, p13;
29  Point3d p21, p22, p23;
30  Point3d p31, p32, p33;
32 };
33 
34 template <typename T>
35 class Point2dTypeTest : public ::testing::Test {
36  protected:
37  using Point2dT = T;
38  void SetUp() override {
39  Id id{1};
40  p1 = Point2d(++id, 1., 0., 0.);
41  p2 = Point2d(++id, 0., 1., 0.);
42  p3 = Point2d(++id, -1., 0., 0.);
43  p4 = Point2d(++id, 0., 1., 0.);
44  }
45 
46  public:
47  Point2dT p1, p2, p3, p4;
48 };
49 
50 template <typename T>
52  protected:
53  using LineStringT = T;
54  void SetUp() override {
56  Id id{10};
57  ls1 =
59  ls2 = LineStringT(++id, {p21, p22, p23});
60  ls3 = LineStringT(++id, {p31, p32, p33});
61  ls4 = LineStringT(++id, {p11, p12, p43});
62  }
63 
64  public:
65  static LineStringT getLinestringAt(double y, size_t n = 100) {
66  Id id{10};
67  std::vector<Point3d> points;
68  for (auto i = 0; i < n; i++) {
69  points.push_back(Point3d(++id, i, y, 0));
70  }
71  return LineStringT(++id, points);
72  }
73  LineStringT ls1, ls2, ls3, ls4;
74 };
75 
76 template <typename T>
78  protected:
79  using BaseLinestringT = T;
80  using LineStringT = typename T::BasicLineString;
81  void SetUp() override {
83  Id id{10};
84  ls1 = BaseLinestringT(++id, {p11, p12, p13},
86  .basicLineString();
87  ls2 = BaseLinestringT(++id, {p21, p22, p23}).basicLineString();
88  ls3 = BaseLinestringT(++id, {p31, p32, p33}).basicLineString();
89  ls4 = BaseLinestringT(++id, {p11, p12, p43}).basicLineString();
90  }
91 
92  public:
93  static LineStringT getLinestringAt(double y, size_t n = 100) {
94  Id id{10};
95  std::vector<Point3d> points;
96  for (auto i = 0; i < n; i++) {
97  points.push_back(Point3d(++id, i, y, 0));
98  }
99  return BaseLinestringT(++id, points).basicLineString();
100  }
101  LineStringT ls1, ls2, ls3, ls4;
102 };
103 
104 template <typename T>
106  protected:
107  using LineStringT = T;
108  void SetUp() override {
110  Id id{10};
111  LineString3d tempLs1 = LineString3d{++id, {p11, p12}};
112  LineString3d tempLs2 = LineString3d{++id, {p12, p13}};
113  LineString3d tempLs3 = LineString3d{++id, {p21, p22}};
114  LineString3d tempLs4 = LineString3d{++id, {p22, p23}};
115  LineString3d tempLs5 = LineString3d{++id, {p12, p43}};
116  ls1 = LineStringT({tempLs1, tempLs2});
117  ls2 = LineStringT({tempLs3, tempLs4});
118  ls3 = LineStringT({LineString3d(++id, {p31, p32, p33})});
119  ls4 = LineStringT({tempLs1, tempLs5});
120  }
121 
122  public:
123  static LineStringT getLinestringAt(double y, size_t n = 100) {
125  }
126 
127  LineStringT ls1, ls2, ls3, ls4;
128 };
129 
130 template <typename T>
131 auto getZ(const T& p) -> std::enable_if_t<!traits::is2D<T>(), double> {
132  return p.z();
133 }
134 template <typename T>
135 auto getZ(const T& /*p*/) -> std::enable_if_t<traits::is2D<T>(), double> {
136  return 0.;
137 }
138 
139 template <>
140 class LineStringTypeTest<CompoundLineString2d> : public CompoundLineStringTypeTest<CompoundLineString2d> {};
141 
142 template <>
143 class LineStringTypeTest<CompoundLineString3d> : public CompoundLineStringTypeTest<CompoundLineString3d> {};
144 
145 template <>
146 class LineStringTypeTest<CompoundHybridLineString2d> : public CompoundLineStringTypeTest<CompoundHybridLineString2d> {};
147 
148 template <>
149 class LineStringTypeTest<CompoundHybridLineString3d> : public CompoundLineStringTypeTest<CompoundHybridLineString3d> {};
150 
151 template <>
153 template <>
155 
156 template <typename T>
158 
159 template <typename T>
161 
162 template <typename T>
164 
165 template <typename T>
167 
168 template <typename T>
170 
171 template <typename T>
173 
174 template <typename T>
176 
177 template <typename T>
179 
180 template <typename T>
181 class TwoDPointsTest : public Point2dTypeTest<T> {};
182 
183 template <typename T>
185 using TwoDPoints = testing::Types<BasicPoint2d, Point2d, ConstPoint2d>;
189 using NormalLineStrings = testing::Types<LineString2d, LineString3d, ConstLineString2d, ConstLineString3d>;
194 using MutableLineStrings = testing::Types<LineString2d, LineString3d>;
201 
202 using BasicLineStrings = testing::Types<BasicLineString2d, BasicLineString3d>;
203 
204 #ifndef TYPED_TEST_SUITE
205 // backwards compability with old gtest versions
206 #define TYPED_TEST_SUITE TYPED_TEST_CASE
207 #endif
218 
220  this->ls1.setId(100);
221  EXPECT_EQ(100, this->ls1.id());
222 }
223 
224 TYPED_TEST(MutableLineStringsTest, readAttributes) { // NOLINT
225  EXPECT_TRUE(this->ls1.hasAttribute(AttributeName::Type));
226  EXPECT_TRUE(this->ls1.hasAttribute(AttributeNamesString::Type));
227  EXPECT_EQ(this->ls1.attribute(AttributeName::Type), AttributeValueString::Curbstone);
228  EXPECT_EQ(this->ls1.attribute(AttributeNamesString::Type), AttributeValueString::Curbstone);
229 }
230 
231 TYPED_TEST(PrimitiveLineStringsTest, constConversion) { // NOLINT
232  auto constLs = traits::toConst(this->ls1);
233  EXPECT_EQ(constLs, this->ls1);
234 }
235 
236 TYPED_TEST(AllLineStringsTest, iteration) { // NOLINT
237  auto xs = utils::transform(this->ls1, [](const auto& elem) { return elem.x(); });
238  EXPECT_EQ(3ul, xs.size());
239  for (auto x : xs) {
240  EXPECT_EQ(0, x);
241  }
242 }
243 
245  auto invertLs = this->ls1.invert();
246  auto ys = utils::transform(invertLs, [](const auto& elem) { return elem.y(); });
247  ASSERT_EQ(3ul, ys.size());
248  EXPECT_EQ(0, ys[2]);
249  EXPECT_EQ(2, ys[0]);
250 }
251 
252 TYPED_TEST(MutableLineStringsTest, invertAndPushBack) { // NOLINT
253  using PointT = typename TypeParam::PointType;
254  auto invertLs = this->ls1.invert();
255  EXPECT_NE(invertLs, this->ls1);
256  EXPECT_EQ(invertLs.invert(), this->ls1);
257  this->ls1[0] = PointT(this->p21);
258  EXPECT_EQ(PointT(this->p21), invertLs[2]);
259 
260  invertLs.push_back(this->p22);
261  EXPECT_EQ(this->p22.id(), this->ls1[0].id());
262 }
263 
264 TYPED_TEST(MutableLineStringsTest, invertAndInsertOne) { // NOLINT
265  using PointT = typename TypeParam::PointType;
266  auto invertLs = this->ls1.invert();
267  auto it = invertLs.insert(invertLs.begin() + 1, PointT(this->p21));
268  EXPECT_EQ(PointT(this->p21), *it);
269  EXPECT_EQ(PointT(this->p21), this->ls1[2]);
270 }
271 
272 TYPED_TEST(MutableLineStringsTest, invertAndErase) { // NOLINT
273  auto invertLs = this->ls1.invert();
274  auto it = invertLs.erase(invertLs.begin() + 1);
275  EXPECT_EQ(2ul, this->ls1.size());
276  EXPECT_EQ(this->ls1.front(), *it);
277 }
278 
279 TYPED_TEST(MutableLineStringsTest, invertAndInsertMultiple) { // NOLINT
280  auto invertLs = this->ls1.invert();
281  auto pts = std::vector<typename TypeParam::PointType>(this->ls2.begin(), this->ls2.end());
282  auto it = invertLs.insert(invertLs.end(), pts.begin(), pts.end());
283  EXPECT_EQ(it, invertLs.end() - 1);
284  EXPECT_LT(it, invertLs.end());
285  EXPECT_GT(it, invertLs.begin());
286  EXPECT_EQ(this->ls2.back(), invertLs.back());
287 }
288 
289 TYPED_TEST(MutableLineStringsTest, invertAndResize) { // NOLINT
290  auto invertLs = this->ls1.invert();
291  invertLs.resize(2);
292  ASSERT_EQ(2ul, invertLs.size());
293  EXPECT_EQ(invertLs.front(), this->p13);
294  EXPECT_EQ(invertLs.back(), this->p12);
295 }
296 
297 TYPED_TEST(TwoDLineStringsTest, bounds2d) { // NOLINT
299  EXPECT_EQ(bbox.min().x(), -1);
300  EXPECT_EQ(bbox.min().y(), 0);
301  EXPECT_EQ(bbox.max().x(), 2);
302  EXPECT_EQ(bbox.max().y(), 2);
303 }
304 
305 TYPED_TEST(ThreeDLineStringsTest, bounds3d) { // NOLINT
307  EXPECT_EQ(bbox.min().x(), 0);
308  EXPECT_EQ(bbox.min().y(), 0);
309  EXPECT_EQ(bbox.min().z(), 0);
310  EXPECT_EQ(bbox.max().x(), 0);
311  EXPECT_EQ(bbox.max().y(), 2);
312  EXPECT_EQ(bbox.max().z(), 1);
313 }
314 
316  EXPECT_NEAR(geometry::distance3d(this->ls1, this->ls2), 0.25, 0.05);
317  EXPECT_DOUBLE_EQ(geometry::distance3d(this->ls2, this->ls3), 2.);
318 }
319 
320 TYPED_TEST(ThreeDLineStringsTest, distance3dLongLinestring) { // NOLINT
321  auto ls2 = this->getLinestringAt(0, 100);
322  auto ls1 = this->getLinestringAt(5, 100);
323  EXPECT_DOUBLE_EQ(geometry::distance3d(ls1, ls2), 5.);
324 }
325 
326 TYPED_TEST(AllLineStringsTest, length) { // NOLINT
327  auto l = geometry::length(this->ls1);
328  auto lSeg1 = geometry::rangedLength(std::begin(this->ls1), std::prev(std::end(this->ls1)));
329  if (traits::is2D<TypeParam>()) {
330  EXPECT_DOUBLE_EQ(2, l);
331  } else {
332  EXPECT_DOUBLE_EQ(1 + std::sqrt(2), l);
333  }
334  EXPECT_DOUBLE_EQ(1, lSeg1);
335 }
336 
337 TYPED_TEST(MutableLineStringsTest, boostConvert) { // NOLINT
338  auto equal = [](auto& ls1, auto& ls2) {
339  return std::equal(ls1.begin(), ls1.end(), ls2.begin(), ls2.end(),
340  [](auto& p1, auto& p2) { return p1.basicPoint() == p2.basicPoint(); });
341  };
342  typename TypeParam::BasicLineString basicLineString;
343  TypeParam convertedLineString;
344  auto testLs = this->ls1.invert();
345  boost::geometry::convert(testLs, basicLineString);
346  boost::geometry::convert(basicLineString, convertedLineString);
347  EXPECT_PRED2(equal, testLs, convertedLineString);
348 }
349 
350 TYPED_TEST(MutableLineStringsTest, boostAppend) { // NOLINT
351  typename TypeParam::BasicPointType p = this->ls2.front();
352  auto testLs = this->ls1.invert();
353  boost::geometry::append(testLs, p);
354  EXPECT_EQ(testLs.back().basicPoint(), p);
355 }
356 
358  auto lRatios = geometry::lengthRatios(this->ls1);
359  ASSERT_EQ(2ul, lRatios.size());
360  if (traits::is2D<TypeParam>()) {
361  EXPECT_DOUBLE_EQ(0.5, lRatios[0]);
362  } else {
363  EXPECT_DOUBLE_EQ(1 / (1 + std::sqrt(2)), lRatios[0]);
364  }
365 }
366 
368  auto lRatios = geometry::accumulatedLengthRatios(this->ls2);
369  ASSERT_EQ(2ul, lRatios.size());
370  EXPECT_DOUBLE_EQ(1, lRatios[1]);
371 }
372 
373 TYPED_TEST(AllLineStringsTest, interpolatedPoint) { // NOLINT
374  const auto twoD = traits::is2D<TypeParam>();
375  const auto pos = twoD ? 1.5 : 1 + std::sqrt(0.5);
376  const auto l = geometry::length(this->ls1);
377  auto p = geometry::interpolatedPointAtDistance(this->ls1, pos);
378  auto pInv = geometry::interpolatedPointAtDistance(this->ls1, pos - l);
379  EXPECT_DOUBLE_EQ(p.x(), 0);
380  EXPECT_DOUBLE_EQ(pInv.x(), 0);
381  EXPECT_DOUBLE_EQ(p.y(), 1.5);
382  EXPECT_DOUBLE_EQ(pInv.y(), 1.5);
383  if (!twoD) {
384  EXPECT_DOUBLE_EQ(getZ(p), 0.5);
385  EXPECT_DOUBLE_EQ(getZ(pInv), 0.5);
386  }
387 }
388 
389 TYPED_TEST(AllLineStringsTest, nearestPoint) { // NOLINT
390  const auto twoD = traits::is2D<TypeParam>();
391  auto pos = twoD ? 1.4 : 1 + std::sqrt(0.4);
392  const auto l = geometry::length(this->ls1);
393  auto p = geometry::nearestPointAtDistance(this->ls1, pos);
394  auto pInv = geometry::nearestPointAtDistance(this->ls1, pos - l);
395  EXPECT_EQ(p, this->ls1[1]);
396  EXPECT_EQ(pInv, this->ls1[1]);
397 }
398 
399 TYPED_TEST(AllLineStringsTest, segments) { // NOLINT
400  auto segment = this->ls1.segment(0);
401  EXPECT_EQ(2ul, this->ls1.numSegments());
402  EXPECT_EQ(segment.first, this->ls1[0]);
403  EXPECT_EQ(segment.second, this->ls1[1]);
404 }
405 
406 TYPED_TEST(AllLineStringsTest, segmentsInverse) { // NOLINT
407  auto lsInv = this->ls1.invert();
408  auto segment = lsInv.segment(0);
409  EXPECT_EQ(segment.first, lsInv[0]);
410  EXPECT_EQ(segment.second, lsInv[1]);
411 }
412 
413 TYPED_TEST(TwoDPointsTest, checkCurvature) {
414  EXPECT_DOUBLE_EQ(1., geometry::curvature2d(this->p1, this->p2, this->p3));
415  EXPECT_DOUBLE_EQ(std::numeric_limits<double>::infinity(), geometry::curvature2d(this->p1, this->p2, this->p4));
416  EXPECT_DOUBLE_EQ(1., geometry::curvature2d(this->p3, this->p2, this->p1));
417  EXPECT_DOUBLE_EQ(std::numeric_limits<double>::infinity(), geometry::curvature2d(this->p3, this->p2, this->p4));
418  EXPECT_DOUBLE_EQ(1., geometry::signedCurvature2d(this->p1, this->p2, this->p3));
419  EXPECT_DOUBLE_EQ(std::numeric_limits<double>::infinity(), geometry::signedCurvature2d(this->p1, this->p2, this->p4));
420  EXPECT_DOUBLE_EQ(-1., geometry::signedCurvature2d(this->p3, this->p2, this->p1));
421  EXPECT_DOUBLE_EQ(std::numeric_limits<double>::infinity(), geometry::signedCurvature2d(this->p3, this->p2, this->p4));
422 }
423 
425  auto isLeft = [this](const BasicPoint2d& p) { return geometry::signedDistance(this->ls2, p) > 0; };
426  auto d = geometry::signedDistance(this->ls2, BasicPoint2d(2, -1));
427  EXPECT_DOUBLE_EQ(-1., d);
428  auto d2 = geometry::signedDistance(this->ls2, BasicPoint2d(3, 0.5));
429  EXPECT_DOUBLE_EQ(-std::sqrt(1.25), d2);
430 
431  EXPECT_FALSE(isLeft(BasicPoint2d(0, -1)));
432  EXPECT_FALSE(isLeft(BasicPoint2d(0, 2)));
433  EXPECT_FALSE(isLeft(BasicPoint2d(3, 0)));
434  EXPECT_TRUE(isLeft(BasicPoint2d(0, 1)));
435  EXPECT_TRUE(isLeft(BasicPoint2d(-5, 1)));
436  EXPECT_FALSE(isLeft(BasicPoint2d(-2, 5)));
437 }
438 
440  auto isLeft = [this](const BasicPoint3d& p) { return geometry::signedDistance(this->ls1, p) > 0; };
441  auto d = geometry::signedDistance(this->ls1, BasicPoint3d(2, 0, 0));
442  EXPECT_DOUBLE_EQ(-2., d);
443  auto d2 = geometry::signedDistance(this->ls1, BasicPoint3d(-1, 1, 0));
444  EXPECT_DOUBLE_EQ(1, d2);
445 
446  EXPECT_TRUE(isLeft(BasicPoint3d(-1, -1, 10)));
447  EXPECT_FALSE(isLeft(BasicPoint3d(5, 5, -10)));
448 }
449 
451  EXPECT_FALSE(geometry::intersects3d(this->ls1, this->ls3, 1.));
452  EXPECT_TRUE(geometry::intersects3d(this->ls3, this->ls1, 3.));
453  EXPECT_TRUE(geometry::intersects3d(this->ls2, this->ls1, 2.));
454 }
455 
456 TYPED_TEST(TwoDLineStringsTest, arcCoordinates) { // NOLINT
457  ArcCoordinates arcPoint = geometry::toArcCoordinates(this->ls1, BasicPoint2d(1, -1));
458  EXPECT_EQ(-std::sqrt(2), arcPoint.distance);
459  EXPECT_EQ(0, arcPoint.length);
460  ArcCoordinates arcPoint2 = geometry::toArcCoordinates(this->ls1, BasicPoint2d(-1, 1.5));
461  EXPECT_EQ(1, arcPoint2.distance);
462  EXPECT_EQ(1.5, arcPoint2.length);
463 }
464 
465 TYPED_TEST(TwoDLineStringsTest, projectedPoint) { // NOLINT
466  auto p = BasicPoint2d(0, 1.5);
467  auto projectedPoint = geometry::project(this->ls1, p);
468  EXPECT_DOUBLE_EQ(0, projectedPoint.x());
469  EXPECT_DOUBLE_EQ(1.5, projectedPoint.y());
470 }
471 
472 TYPED_TEST(ThreeDLineStringsTest, projectedPoint) { // NOLINT
473  auto p = BasicPoint3d(0, 1.5, 0.5);
474  auto projectedPoint = geometry::project(this->ls1, p);
475  EXPECT_DOUBLE_EQ(0, projectedPoint.x());
476  EXPECT_DOUBLE_EQ(1.5, projectedPoint.y());
477  EXPECT_DOUBLE_EQ(0.5, projectedPoint.z());
478 }
479 
480 TYPED_TEST(TwoDLineStringsTest, projectedPointLongLinestring) { // NOLINT
481  auto p = BasicPoint2d(0, 0);
482  auto ls = this->getLinestringAt(5, 100);
483  auto projectedPoint = geometry::project(ls, p);
484  EXPECT_DOUBLE_EQ(0, projectedPoint.x());
485  EXPECT_DOUBLE_EQ(5, projectedPoint.y());
486 }
487 
488 TYPED_TEST(ThreeDLineStringsTest, projectedPointLongLinestring) { // NOLINT
489  auto p = BasicPoint3d(0, 0, -1);
490  auto ls = this->getLinestringAt(5, 100);
491  auto projectedPoint = geometry::project(ls, p);
492  EXPECT_DOUBLE_EQ(0, projectedPoint.x());
493  EXPECT_DOUBLE_EQ(5, projectedPoint.y());
494  EXPECT_DOUBLE_EQ(0, projectedPoint.z());
495 }
496 
498  auto p = BasicPoint2d(0, 0);
499  auto segm = geometry::closestSegment(this->ls1, p);
500  EXPECT_DOUBLE_EQ(boost::geometry::distance(utils::toBasicPoint(segm.first), this->ls1), 0.);
501  EXPECT_DOUBLE_EQ(boost::geometry::distance(utils::toBasicPoint(segm.second), this->ls1), 0.);
503 }
504 
506  auto p = BasicPoint3d(0, 1, 2);
507  auto segm = geometry::closestSegment(this->ls1, p);
508  EXPECT_DOUBLE_EQ(boost::geometry::distance(utils::toBasicPoint(segm.first), this->ls1), 0.);
509  EXPECT_DOUBLE_EQ(boost::geometry::distance(utils::toBasicPoint(segm.second), this->ls1), 0.);
511 }
512 
513 TYPED_TEST(TwoDLineStringsTest, closestSegmentLongLinestring) { // NOLINT
514  auto p = BasicPoint2d(0, 0);
515  auto ls = this->getLinestringAt(5, 100);
516  auto segm = geometry::closestSegment(ls, p);
518 }
519 
520 TYPED_TEST(ThreeDLineStringsTest, closestSegmentLongLinestring) { // NOLINT
521  auto p = BasicPoint3d(0, 1, 2);
522  auto ls = this->getLinestringAt(5, 100);
523  auto segm = geometry::closestSegment(ls, p);
525 }
526 
527 TYPED_TEST(TwoDLineStringsTest, projectedPointL2L) { // NOLINT
528  auto points = geometry::projectedPoint2d(this->ls1, this->ls2);
529  EXPECT_DOUBLE_EQ((points.first - points.second).norm(), geometry::distance2d(this->ls1, this->ls2));
530  EXPECT_NEAR(geometry::distance2d(points.first, this->ls1), 0., 1e-10);
531  EXPECT_NEAR(geometry::distance2d(points.second, this->ls2), 0., 1e-10);
532 }
533 
534 TYPED_TEST(ThreeDLineStringsTest, projectedPointL2L) { // NOLINT
535  auto points = geometry::projectedPoint3d(this->ls1, this->ls2);
536  EXPECT_DOUBLE_EQ((points.first - points.second).norm(), geometry::distance3d(this->ls1, this->ls2));
537  EXPECT_NEAR(geometry::distance3d(points.first, this->ls1), 0., 1e-10);
538  EXPECT_NEAR(geometry::distance3d(points.second, this->ls2), 0., 1e-10);
539 }
540 
541 TYPED_TEST(TwoDLineStringsTest, projectedPointL2LLongLinestring) { // NOLINT
542  auto ls1 = this->getLinestringAt(0, 100);
543  auto ls2 = this->getLinestringAt(5, 100);
544  auto points = geometry::projectedPoint2d(ls1, ls2);
545  EXPECT_DOUBLE_EQ((points.first - points.second).norm(), 5);
546  EXPECT_DOUBLE_EQ(geometry::distance2d(points.first, ls1), 0.);
547  EXPECT_DOUBLE_EQ(geometry::distance2d(points.second, ls2), 0.);
548 }
549 
550 TYPED_TEST(ThreeDLineStringsTest, projectedPointL2LLongLinestring) { // NOLINT
551  auto ls1 = this->getLinestringAt(0, 100);
552  auto ls2 = this->getLinestringAt(5, 100);
553  auto points = geometry::projectedPoint3d(ls1, ls2);
554  EXPECT_DOUBLE_EQ((points.first - points.second).norm(), 5);
555  EXPECT_DOUBLE_EQ(geometry::distance3d(points.first, ls1), 0.);
556  EXPECT_DOUBLE_EQ(geometry::distance3d(points.second, ls2), 0.);
557 }
558 
560  TypeParam ls3(20, {Point3d(21, 2., 0., 0.), Point3d(22, 1.5, 0.5, 0.)});
561  auto aligned = geometry::align(this->ls1, ls3);
562  EXPECT_EQ(aligned.first, this->ls1);
563  EXPECT_EQ(aligned.second, ls3);
564 
565  aligned = geometry::align(ls3, this->ls1);
566  EXPECT_EQ(aligned.first.invert(), ls3);
567  EXPECT_EQ(aligned.second.invert(), this->ls1);
568 }
569 
570 TYPED_TEST(HybridLineStringsTest, segmentLength) { // NOLINT
571  auto segment = this->ls1.segment(0);
572  EXPECT_DOUBLE_EQ(geometry::length(segment), 1.);
573 }
574 
575 /*
576  * O
577  * |
578  * |
579  * |
580  * O--X
581  * |
582  * |
583  * |
584  * O
585  */
587  Id id = 0;
588  Point3d p1 = Point3d(++id, 0., 0.);
589  Point3d p2 = Point3d(++id, 0., 10.);
590  LineString3d ls(++id, Points3d{p1, p2});
592  EXPECT_TRUE(boost::geometry::equals(ap, BasicPoint2d{-2, 5}));
593 }
594 
596  Id id = 0;
597  Point3d p1 = Point3d(++id, 1., 0.);
598  Point3d p2 = Point3d(++id, 1., 1.);
599  Point3d p3 = Point3d(++id, 4., 1.);
600  Point3d p4 = Point3d(++id, 4., 3.);
601  LineString3d ls(++id, Points3d{p1, p2, p3, p4});
602  auto ap = geometry::offset(utils::to2D(ls), 1.);
603  BasicLineString2d comp({BasicPoint2d(0, 0), BasicPoint2d(0, 2), BasicPoint2d(3, 2), BasicPoint2d(3, 3)});
604  // required due to numeric approximation errors
605  for (size_t i = 0; i < ls.size(); ++i) {
606  EXPECT_NEAR(ap[i].x(), comp[i].x(), 1e-9);
607  EXPECT_NEAR(ap[i].y(), comp[i].y(), 1e-9);
608  }
609 
610  Point3d p11 = Point3d(++id, 1, 0);
611  Point3d p12 = Point3d(++id, 1, 1);
612  Point3d p13 = Point3d(++id, 0, 1);
613  Point3d p13a = Point3d(++id, 2, 1);
614  Point3d p14 = Point3d(++id, 0.5, 0);
615  Point3d p15 = Point3d(++id, 0.5, 1);
616  Point3d p16 = Point3d(++id, 1, 0.5);
617  Point3d p17 = Point3d(++id, 0, 0.5);
618  Point3d p18 = Point3d(++id, 0.5, 1.5);
619  Point3d p19 = Point3d(++id, 2, 1.5);
620 
625  auto lss = geometry::offset(l1, 0.5);
626  EXPECT_TRUE(boost::geometry::equals(
628  auto lss2 = geometry::offset(l2, 0.5);
629  EXPECT_TRUE(boost::geometry::equals(
632 }
633 
635  traits::PointType<typename TestFixture::LineStringT> p3d(100000000000, 0, 1.5, 1.5);
637  auto bp = utils::toBasicPoint(p3d);
638  auto refp = utils::toBasicPoint(ref3d);
639  auto cs = geometry::closestSegment(this->ls1, bp);
640  EXPECT_TRUE(boost::geometry::equals(cs.first, refp));
641 
642  auto b2dcs = geometry::closestSegment(utils::to2D(this->ls1).basicLineString(), utils::to2D(bp));
643  EXPECT_TRUE(boost::geometry::equals(b2dcs.first, utils::to2D(refp)));
644  auto b3dcs = geometry::closestSegment(this->ls1.basicLineString(), bp);
645  EXPECT_TRUE(boost::geometry::equals(b3dcs.first, refp));
646 }
647 
649  EXPECT_EQ(this->ls4.size(), 3ul);
650 
651  auto shifted = geometry::internal::shiftLateral(this->ls4, 1, 1., geometry::internal::makeVincinity(this->ls4, 1));
652  EXPECT_TRUE(boost::geometry::equals(shifted, BasicPoint2d(-1, 1. + sqrt(3) / 3)));
653 }
654 
655 /* O O
656  * /| |\
657  * O-X---X-O
658  * | |
659  * O O
660  */
662  auto p1 = BasicPoint2d(2, 0);
663  auto p2 = BasicPoint2d(2, 2);
664  auto p3 = BasicPoint2d(3, 1);
665  auto p4 = BasicPoint2d(0, 1);
666  auto p5 = BasicPoint2d(1, 2);
667  auto p6 = BasicPoint2d(1, 0);
668  auto p7 = BasicPoint2d(2, 1);
669  auto p8 = BasicPoint2d(1, 1);
670  BasicLineString2d l1{p1, p2, p3, p4, p5, p6};
671  BasicLineString2d l2{p1, p7, p8, p6};
673  EXPECT_TRUE(boost::geometry::equals(ret, l2));
674 }
675 
677  auto p1 = BasicPoint2d(1, 0);
678  auto p2 = BasicPoint2d(1, 1);
679  auto p3 = BasicPoint2d(0, 1);
680  auto p3a = BasicPoint2d(2, 1);
681  auto p3b = BasicPoint2d(0, 0);
682  auto p4 = BasicPoint2d(0.5, 0);
683  auto p5 = BasicPoint2d(0.5, 1);
684  auto p6 = BasicPoint2d(1, 0.5);
685  auto p7 = BasicPoint2d(0, 0.5);
686  auto p8 = BasicPoint2d(0.5, 1.5);
687  auto p9 = BasicPoint2d(2, 1.5);
688 
689  BasicLineString2d l1{p1, p2, p3};
690  BasicLineString2d l2{p1, p2, p3a};
691  BasicLineString2d l3{p1, p2, p3b};
692  auto lss = geometry::internal::extractConvex(l1, 0.5);
693  ASSERT_EQ(lss.size(), 2ul);
694  EXPECT_TRUE(boost::geometry::equals(lss.front(), BasicLineString2d{p4, p5}));
695  EXPECT_TRUE(boost::geometry::equals(lss.back(), BasicLineString2d{p6, p7}));
696  auto lss2 = geometry::internal::extractConvex(l2, 0.5);
697  ASSERT_EQ(lss2.size(), 1ul);
698  EXPECT_TRUE(boost::geometry::equals(lss2.front(), BasicLineString2d{p4, p8, p9}));
699  auto lss3 = geometry::internal::extractConvex(l3, -0.5);
700  ASSERT_EQ(lss3.size(), 1ul);
701  ASSERT_EQ(lss3.front().size(), 4ul);
702  EXPECT_TRUE(boost::geometry::equals(lss2.front(), BasicLineString2d{p4, p8, p9}));
703 }
704 
705 /*
706  * O----O
707  * | |
708  * | O
709  * |
710  * |
711  * O------O
712  *
713  */
714 
715 TEST(TwoDLineStringsTest, checkInversion) {
716  auto p1 = BasicPoint2d(3, 3);
717  auto p2 = BasicPoint2d(3, 5);
718  auto p3 = BasicPoint2d(0, 5);
719  auto p4 = BasicPoint2d(0, 0);
720  auto p5 = BasicPoint2d(4, 0);
721 
722  BasicLineString2d l1{p1, p2, p3, p4, p5};
723  EXPECT_THROW(geometry::offset(l1, 2), GeometryError); // NOLINT
724  EXPECT_NO_THROW(geometry::offset(l1, 1)); // NOLINT
725 }
lanelet::ArcCoordinates::length
double length
length along linestring
Definition: primitives/Point.h:99
LineStringPoints
Definition: test_linestring.cpp:11
lanelet::geometry::boundingBox3d
IfAr< AreaT, BoundingBox3d > boundingBox3d(const AreaT &area)
calculates 3d bounding box
Definition: geometry/impl/Area.h:30
MutableLineStringsTest
Definition: test_linestring.cpp:163
lanelet::ConstLineStringImpl::basicLineString
BasicLineString basicLineString() const noexcept
Create a basic linestring (ie a vector of Eigen Points)
Definition: primitives/LineString.h:345
lanelet::CompoundHybridLineString2d
A hybrid compound linestring in 2d (returns BasicPoint2d)
Definition: CompoundLineString.h:306
getZ
auto getZ(const T &p) -> std::enable_if_t<!traits::is2D< T >(), double >
Definition: test_linestring.cpp:131
TwoDLineStringsTest
Definition: test_linestring.cpp:178
lanelet::traits::toBasicSegment
auto toBasicSegment(const Segment< PointT > &s)
Definition: primitives/LineString.h:75
NonHybridLineStringsTest
Definition: test_linestring.cpp:169
lanelet::geometry::fromArcCoordinates
BasicPoint2d fromArcCoordinates(const LineString2dT &lineString, const ArcCoordinates &arcCoords)
create a point by moving laterally arcCoords.distance from the linestring point at arcCoords....
Definition: geometry/impl/LineString.h:832
lanelet::GeometryError
Thrown when a geometric operation is not valid.
Definition: Exceptions.h:63
LineStringPoints::SetUp
void SetUp() override
Definition: test_linestring.cpp:13
lanelet::geometry::interpolatedPointAtDistance
traits::BasicPointT< traits::PointType< LineStringT > > interpolatedPointAtDistance(LineStringT lineString, double dist)
Definition: geometry/impl/LineString.h:641
PrimitiveLineStringsTest
Definition: test_linestring.cpp:166
lanelet::traits::to2D
BoundingBox2d to2D(const BoundingBox3d &primitive)
Definition: primitives/BoundingBox.h:304
lanelet::geometry::align
std::pair< LineString1T, LineString2T > align(LineString1T left, LineString2T right)
inverts the two linestrings such that they are parallel
Definition: geometry/impl/LineString.h:809
lanelet
Definition: Attribute.h:13
LineStringPoints::p23
Point3d p23
Definition: test_linestring.cpp:29
TwoDPoints
testing::Types< BasicPoint2d, Point2d, ConstPoint2d > TwoDPoints
Definition: test_linestring.cpp:185
lanelet::BasicPoint3d
Eigen::Vector3d BasicPoint3d
a simple 3d-point
Definition: primitives/Point.h:19
BasicLineStringTypeTest::ls4
LineStringT ls4
Definition: test_linestring.cpp:101
lanelet::geometry::internal::fromArcCoords
BasicPoint2d fromArcCoords(const HybridLineStringT &hLineString, const BasicPoint2d &projStart, const size_t startIdx, const size_t endIdx, const double distance)
Definition: geometry/impl/LineString.h:140
AllLineStrings
testing::Types< LineString2d, LineString3d, ConstLineString2d, ConstLineString3d, ConstHybridLineString2d, ConstHybridLineString3d, CompoundLineString2d, CompoundLineString3d, CompoundHybridLineString2d, CompoundHybridLineString3d > AllLineStrings
Definition: test_linestring.cpp:188
lanelet::geometry::internal::makeVincinity
PointVincinity makeVincinity(const LineString2dT &lineString, const size_t idx)
makeVincinity create pair of preceding and following point on a line string
Definition: geometry/impl/LineString.h:169
CompoundLineStringTypeTest::SetUp
void SetUp() override
Definition: test_linestring.cpp:108
lanelet::geometry::lengthRatios
std::vector< double > lengthRatios(const LineStringT &lineString)
Definition: geometry/impl/LineString.h:617
NonHybridLineStrings
testing::Types< LineString2d, LineString3d, ConstLineString2d, ConstLineString3d, CompoundLineString2d, CompoundLineString3d > NonHybridLineStrings
Definition: test_linestring.cpp:198
LineStringTypeTest::LineStringT
T LineStringT
Definition: test_linestring.cpp:53
lanelet::geometry::project
BasicPoint3d project(const LineString3dT &lineString, const BasicPoint3d &pointToProject)
Projects the given point in 3d to the LineString.
Definition: geometry/impl/LineString.h:762
p2
BasicPoint p2
Definition: LineStringGeometry.cpp:167
p
BasicPoint p
Definition: LineStringGeometry.cpp:196
CompoundLineStringTypeTest::ls4
LineStringT ls4
Definition: test_linestring.cpp:127
lanelet::geometry::intersects3d
IfLL< Lanelet1T, bool > intersects3d(const Lanelet1T &lanelet, const Lanelet2T &otherLanelet, double heightTolerance)
test whether two lanelets intersect in 2d.
Definition: geometry/impl/Lanelet.h:111
lanelet::traits::toBasicPoint
auto toBasicPoint(const PointT &point) -> std::enable_if_t< PointTraits< PointT >::IsPrimitive, BasicPointT< PointT >>
Definition: Traits.h:165
lanelet::Point2d
A mutable 2d point.
Definition: primitives/Point.h:230
lanelet::geometry::internal::extractConvex
std::vector< BasicLineString2d > extractConvex(const LineString2dT &lineString, const double distance)
extractConvex get convex parts of line string offset by distance.
Definition: geometry/impl/LineString.h:514
lanelet::Id
int64_t Id
Definition: Forward.h:198
lanelet::utils::transform
auto transform(Iterator begin, Iterator end, const Func f)
Definition: Utilities.h:176
Point2dTypeTest::Point2dT
T Point2dT
Definition: test_linestring.cpp:37
Point2dTypeTest::SetUp
void SetUp() override
Definition: test_linestring.cpp:38
id
Id id
Definition: LaneletMap.cpp:63
MutableLineStrings
testing::Types< LineString2d, LineString3d > MutableLineStrings
Definition: test_linestring.cpp:194
lanelet::ArcCoordinates::distance
double distance
signed distance to linestring (left=positive)
Definition: primitives/Point.h:100
lanelet::AttributeNamesString::Type
static constexpr const char Type[]
Definition: Attribute.h:204
lanelet::ArcCoordinates
Describes a position in linestring coordinates.
Definition: primitives/Point.h:98
lanelet::ConstHybridLineString2d
A Linestring that returns BasicPoint2d instead of Point2d.
Definition: primitives/LineString.h:636
lanelet::CompoundLineString3d
A Compound linestring in 3d (returns Point3d)
Definition: CompoundLineString.h:285
BasicLineStrings
testing::Types< BasicLineString2d, BasicLineString3d > BasicLineStrings
Definition: test_linestring.cpp:202
LineStringPoints::p33
Point3d p33
Definition: test_linestring.cpp:30
lanelet::ConstLineString2d
A normal 2d linestring with immutable data.
Definition: primitives/LineString.h:552
LineStringTypeTest::SetUp
void SetUp() override
Definition: test_linestring.cpp:54
lanelet::BoundingBox2d
Axis-Aligned bounding box in 2d.
Definition: primitives/BoundingBox.h:23
lanelet::LineString2d
A normal 2d linestring with mutable data.
Definition: primitives/LineString.h:569
HybridLineStrings
testing::Types< ConstHybridLineString2d, ConstHybridLineString3d, CompoundHybridLineString2d, CompoundHybridLineString3d > HybridLineStrings
Definition: test_linestring.cpp:200
lanelet::geometry::internal::shiftLateral
BasicPoint2d shiftLateral(const LineString2dT &lineString, const size_t idx, const double offset, const PointVincinity &pv)
shiftLateral shift point along the bisectrix
Definition: geometry/impl/LineString.h:191
lanelet::traits::PointType
typename LineStringTraits< LineStringT >::PointType PointType
Definition: Traits.h:191
LineString.h
CompoundLineStringTypeTest::getLinestringAt
static LineStringT getLinestringAt(double y, size_t n=100)
Definition: test_linestring.cpp:123
lanelet::AttributeName::Type
@ Type
HybridLineStringsTest
Definition: test_linestring.cpp:172
lanelet::BoundingBox3d
Eigen::AlignedBox3d BoundingBox3d
Convenience type for an axis aligned bounding box in 3d.
Definition: primitives/BoundingBox.h:283
bbox
BoundingBox2d bbox
Definition: RegulatoryElementGeometry.cpp:30
lanelet::Points3d
std::vector< Point3d > Points3d
Definition: Forward.h:34
lanelet::CompoundHybridLineString3d
A hybrid compound linestring in 3d (returns BasicPoint3d)
Definition: CompoundLineString.h:327
lanelet::BasicLineString2d
BasicPoints2d BasicLineString2d
Definition: primitives/LineString.h:14
lanelet::geometry::nearestPointAtDistance
traits::PointType< LineStringT > nearestPointAtDistance(LineStringT lineString, double dist)
returns the cosest point to a position on the linestring
Definition: geometry/impl/LineString.h:667
ThreeDLineStringsTest
Definition: test_linestring.cpp:175
NormalLineStrings
testing::Types< LineString2d, LineString3d, ConstLineString2d, ConstLineString3d > NormalLineStrings
Definition: test_linestring.cpp:189
lanelet::geometry::projectedPoint2d
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.
Definition: geometry/impl/LineString.h:789
p1
BasicPoint p1
Definition: LineStringGeometry.cpp:166
PrimitiveLineStrings
testing::Types< LineString2d, LineString3d, ConstLineString2d, ConstLineString3d, ConstHybridLineString2d, ConstHybridLineString3d > PrimitiveLineStrings
Definition: test_linestring.cpp:196
lanelet::geometry::accumulatedLengthRatios
std::vector< double > accumulatedLengthRatios(const LineStringT &lineString)
Definition: geometry/impl/LineString.h:634
ThreeDLineStrings
testing::Types< LineString3d, ConstLineString3d, ConstHybridLineString3d, CompoundLineString3d, CompoundHybridLineString3d, BasicLineString3d > ThreeDLineStrings
Definition: test_linestring.cpp:191
NormalLineStringsTest
Definition: test_linestring.cpp:160
lanelet::AttributeValueString::Curbstone
static constexpr const char Curbstone[]
Definition: Attribute.h:283
lanelet::geometry::signedDistance
double signedDistance(const LineString3dT &lineString, const BasicPoint3d &p)
Definition: geometry/impl/LineString.h:693
TEST
TEST(TwoDLineStringsTest, removeSelfIntersections)
Definition: test_linestring.cpp:661
LineStringPoints::p43
Point3d p43
Definition: test_linestring.cpp:31
lanelet::traits::toConst
ConstPrimitiveType< PrimitiveT > toConst(const PrimitiveT &primitive)
Converts a primitive to its matching const type.
Definition: Traits.h:108
Point2dTypeTest
Definition: test_linestring.cpp:35
lanelet::geometry::curvature2d
double curvature2d(const Point2dT &p1, const Point2dT &p2, const Point2dT &p3)
Definition: geometry/impl/LineString.h:705
lanelet::BasicPoint2d
Eigen::Matrix< double, 2, 1, Eigen::DontAlign > BasicPoint2d
a simple 2d-point
Definition: primitives/Point.h:20
TwoDPointsTest
Definition: test_linestring.cpp:181
CompoundLineStringTypeTest
Definition: test_linestring.cpp:105
lanelet::BoundingBox2d::min
const VectorType &() min() const
Definition: primitives/BoundingBox.h:104
lanelet::Point3d
A mutable 3d point.
Definition: primitives/Point.h:271
lanelet::geometry::closestSegment
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:...
Definition: LineStringGeometry.cpp:442
LineStringTypeTest::getLinestringAt
static LineStringT getLinestringAt(double y, size_t n=100)
Definition: test_linestring.cpp:65
lanelet::HybridMap< Attribute, decltype(AttributeNamesString::Map)&, AttributeNamesString::Map >
TwoDLineStrings
testing::Types< LineString2d, ConstLineString2d, ConstHybridLineString2d, CompoundLineString2d, CompoundHybridLineString2d, BasicLineString2d > TwoDLineStrings
Definition: test_linestring.cpp:193
Traits.h
lanelet::geometry::boundingBox2d
IfAr< AreaT, BoundingBox2d > boundingBox2d(const AreaT &area)
calculates an up-right 2d bounding box
Definition: geometry/impl/Area.h:25
lanelet::geometry::internal::invert
LineStringT invert(const LineStringT &ls)
Definition: geometry/impl/LineString.h:57
lanelet::geometry::toArcCoordinates
ArcCoordinates toArcCoordinates(const LineString2dT &lineString, const BasicPoint2d &point)
Transform a point to the coordinates of the linestring.
Definition: geometry/impl/LineString.h:724
segm
Segm segm
Definition: LineStringGeometry.cpp:195
lanelet::CompoundLineString2d
A Compound linestring in 2d (returns Point2d)
Definition: CompoundLineString.h:263
lanelet::geometry::distance3d
IfLS2< LineString3d1T, LineString3d2T, double > distance3d(const LineString3d1T &l1, const LineString3d2T &l2)
Definition: geometry/impl/LineString.h:803
lanelet::BoundingBox2d::max
const VectorType &() max() const
Definition: primitives/BoundingBox.h:108
lanelet::ConstLineString3d
A normal 3d linestring with immutable data.
Definition: primitives/LineString.h:521
BasicLineStringTypeTest< LineString2d >::LineStringT
typename LineString2d ::BasicLineString LineStringT
Definition: test_linestring.cpp:80
BasicLineStringTypeTest::getLinestringAt
static LineStringT getLinestringAt(double y, size_t n=100)
Definition: test_linestring.cpp:93
LineString.h
distance
Optional< double > distance
Definition: LineStringGeometry.cpp:168
lanelet::ConstHybridLineString3d
A Linestring that returns BasicPoint3d instead of Point3d.
Definition: primitives/LineString.h:585
d
double d
Definition: RegulatoryElementGeometry.cpp:69
BasicLineStringTypeTest
Definition: test_linestring.cpp:77
lanelet::geometry::internal::removeSelfIntersections
BasicLineString2d removeSelfIntersections(const BasicLineString2d &lineString)
Definition: geometry/impl/LineString.h:394
BasicLineStringsTest
Definition: test_linestring.cpp:184
lanelet::geometry::signedCurvature2d
double signedCurvature2d(const Point2dT &p1, const Point2dT &p2, const Point2dT &p3)
Definition: geometry/impl/LineString.h:710
lanelet::geometry::distance2d
double distance2d(const RegulatoryElement &regElem, const BasicPoint2d &p)
Definition: RegulatoryElementGeometry.cpp:85
BasicLineStringTypeTest::SetUp
void SetUp() override
Definition: test_linestring.cpp:81
LineStringTypeTest::ls4
LineStringT ls4
Definition: test_linestring.cpp:73
LineStringPoints::p13
Point3d p13
Definition: test_linestring.cpp:28
lanelet::LineString3d
A normal 3d linestring with mutable data.
Definition: primitives/LineString.h:538
Point2dTypeTest::p4
Point2dT p4
Definition: test_linestring.cpp:47
AllLineStringsTest
Definition: test_linestring.cpp:157
TYPED_TEST_SUITE
#define TYPED_TEST_SUITE
Definition: test_linestring.cpp:206
LineStringTypeTest
Definition: test_linestring.cpp:51
lanelet::geometry::rangedLength
double rangedLength(LineStringIterator start, LineStringIterator end)
Definition: geometry/impl/LineString.h:610
TYPED_TEST
TYPED_TEST(MutableLineStringsTest, id)
Definition: test_linestring.cpp:219
lanelet::geometry::projectedPoint3d
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.
Definition: geometry/impl/LineString.h:796
lanelet::geometry::offset
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...
Definition: geometry/impl/LineString.h:865
lanelet::BasicLineString3d
BasicPoints3d BasicLineString3d
Definition: primitives/LineString.h:15


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