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>;
187  ConstHybridLineString2d, ConstHybridLineString3d, CompoundLineString2d,
188  CompoundLineString3d, CompoundHybridLineString2d, CompoundHybridLineString3d>;
189 using NormalLineStrings = testing::Types<LineString2d, LineString3d, ConstLineString2d, ConstLineString3d>;
190 using ThreeDLineStrings = testing::Types<LineString3d, ConstLineString3d, ConstHybridLineString3d, CompoundLineString3d,
191  CompoundHybridLineString3d, BasicLineString3d>;
192 using TwoDLineStrings = testing::Types<LineString2d, ConstLineString2d, ConstHybridLineString2d, CompoundLineString2d,
193  CompoundHybridLineString2d, BasicLineString2d>;
194 using MutableLineStrings = testing::Types<LineString2d, LineString3d>;
198  CompoundLineString2d, CompoundLineString3d>;
199 using HybridLineStrings = testing::Types<ConstHybridLineString2d, ConstHybridLineString3d, CompoundHybridLineString2d,
200  CompoundHybridLineString3d>;
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 }
417 
419  auto isLeft = [this](const BasicPoint2d& p) { return geometry::signedDistance(this->ls2, p) > 0; };
420  auto d = geometry::signedDistance(this->ls2, BasicPoint2d(2, -1));
421  EXPECT_DOUBLE_EQ(-1., d);
422  auto d2 = geometry::signedDistance(this->ls2, BasicPoint2d(3, 0.5));
423  EXPECT_DOUBLE_EQ(-std::sqrt(1.25), d2);
424 
425  EXPECT_FALSE(isLeft(BasicPoint2d(0, -1)));
426  EXPECT_FALSE(isLeft(BasicPoint2d(0, 2)));
427  EXPECT_FALSE(isLeft(BasicPoint2d(3, 0)));
428  EXPECT_TRUE(isLeft(BasicPoint2d(0, 1)));
429  EXPECT_TRUE(isLeft(BasicPoint2d(-5, 1)));
430  EXPECT_FALSE(isLeft(BasicPoint2d(-2, 5)));
431 }
432 
434  auto isLeft = [this](const BasicPoint3d& p) { return geometry::signedDistance(this->ls1, p) > 0; };
435  auto d = geometry::signedDistance(this->ls1, BasicPoint3d(2, 0, 0));
436  EXPECT_DOUBLE_EQ(-2., d);
437  auto d2 = geometry::signedDistance(this->ls1, BasicPoint3d(-1, 1, 0));
438  EXPECT_DOUBLE_EQ(1, d2);
439 
440  EXPECT_TRUE(isLeft(BasicPoint3d(-1, -1, 10)));
441  EXPECT_FALSE(isLeft(BasicPoint3d(5, 5, -10)));
442 }
443 
445  EXPECT_FALSE(geometry::intersects3d(this->ls1, this->ls3, 1.));
446  EXPECT_TRUE(geometry::intersects3d(this->ls3, this->ls1, 3.));
447  EXPECT_TRUE(geometry::intersects3d(this->ls2, this->ls1, 2.));
448 }
449 
450 TYPED_TEST(TwoDLineStringsTest, arcCoordinates) { // NOLINT
451  ArcCoordinates arcPoint = geometry::toArcCoordinates(this->ls1, BasicPoint2d(1, -1));
452  EXPECT_EQ(-std::sqrt(2), arcPoint.distance);
453  EXPECT_EQ(0, arcPoint.length);
454  ArcCoordinates arcPoint2 = geometry::toArcCoordinates(this->ls1, BasicPoint2d(-1, 1.5));
455  EXPECT_EQ(1, arcPoint2.distance);
456  EXPECT_EQ(1.5, arcPoint2.length);
457 }
458 
459 TYPED_TEST(TwoDLineStringsTest, projectedPoint) { // NOLINT
460  auto p = BasicPoint2d(0, 1.5);
461  auto projectedPoint = geometry::project(this->ls1, p);
462  EXPECT_DOUBLE_EQ(0, projectedPoint.x());
463  EXPECT_DOUBLE_EQ(1.5, projectedPoint.y());
464 }
465 
466 TYPED_TEST(ThreeDLineStringsTest, projectedPoint) { // NOLINT
467  auto p = BasicPoint3d(0, 1.5, 0.5);
468  auto projectedPoint = geometry::project(this->ls1, p);
469  EXPECT_DOUBLE_EQ(0, projectedPoint.x());
470  EXPECT_DOUBLE_EQ(1.5, projectedPoint.y());
471  EXPECT_DOUBLE_EQ(0.5, projectedPoint.z());
472 }
473 
474 TYPED_TEST(TwoDLineStringsTest, projectedPointLongLinestring) { // NOLINT
475  auto p = BasicPoint2d(0, 0);
476  auto ls = this->getLinestringAt(5, 100);
477  auto projectedPoint = geometry::project(ls, p);
478  EXPECT_DOUBLE_EQ(0, projectedPoint.x());
479  EXPECT_DOUBLE_EQ(5, projectedPoint.y());
480 }
481 
482 TYPED_TEST(ThreeDLineStringsTest, projectedPointLongLinestring) { // NOLINT
483  auto p = BasicPoint3d(0, 0, -1);
484  auto ls = this->getLinestringAt(5, 100);
485  auto projectedPoint = geometry::project(ls, p);
486  EXPECT_DOUBLE_EQ(0, projectedPoint.x());
487  EXPECT_DOUBLE_EQ(5, projectedPoint.y());
488  EXPECT_DOUBLE_EQ(0, projectedPoint.z());
489 }
490 
492  auto p = BasicPoint2d(0, 0);
493  auto segm = geometry::closestSegment(this->ls1, p);
494  EXPECT_DOUBLE_EQ(boost::geometry::distance(utils::toBasicPoint(segm.first), this->ls1), 0.);
495  EXPECT_DOUBLE_EQ(boost::geometry::distance(utils::toBasicPoint(segm.second), this->ls1), 0.);
497 }
498 
500  auto p = BasicPoint3d(0, 1, 2);
501  auto segm = geometry::closestSegment(this->ls1, p);
502  EXPECT_DOUBLE_EQ(boost::geometry::distance(utils::toBasicPoint(segm.first), this->ls1), 0.);
503  EXPECT_DOUBLE_EQ(boost::geometry::distance(utils::toBasicPoint(segm.second), this->ls1), 0.);
505 }
506 
507 TYPED_TEST(TwoDLineStringsTest, closestSegmentLongLinestring) { // NOLINT
508  auto p = BasicPoint2d(0, 0);
509  auto ls = this->getLinestringAt(5, 100);
510  auto segm = geometry::closestSegment(ls, p);
512 }
513 
514 TYPED_TEST(ThreeDLineStringsTest, closestSegmentLongLinestring) { // NOLINT
515  auto p = BasicPoint3d(0, 1, 2);
516  auto ls = this->getLinestringAt(5, 100);
517  auto segm = geometry::closestSegment(ls, p);
519 }
520 
521 TYPED_TEST(TwoDLineStringsTest, projectedPointL2L) { // NOLINT
522  auto points = geometry::projectedPoint2d(this->ls1, this->ls2);
523  EXPECT_DOUBLE_EQ((points.first - points.second).norm(), geometry::distance2d(this->ls1, this->ls2));
524  EXPECT_NEAR(geometry::distance2d(points.first, this->ls1), 0., 1e-10);
525  EXPECT_NEAR(geometry::distance2d(points.second, this->ls2), 0., 1e-10);
526 }
527 
528 TYPED_TEST(ThreeDLineStringsTest, projectedPointL2L) { // NOLINT
529  auto points = geometry::projectedPoint3d(this->ls1, this->ls2);
530  EXPECT_DOUBLE_EQ((points.first - points.second).norm(), geometry::distance3d(this->ls1, this->ls2));
531  EXPECT_NEAR(geometry::distance3d(points.first, this->ls1), 0., 1e-10);
532  EXPECT_NEAR(geometry::distance3d(points.second, this->ls2), 0., 1e-10);
533 }
534 
535 TYPED_TEST(TwoDLineStringsTest, projectedPointL2LLongLinestring) { // NOLINT
536  auto ls1 = this->getLinestringAt(0, 100);
537  auto ls2 = this->getLinestringAt(5, 100);
538  auto points = geometry::projectedPoint2d(ls1, ls2);
539  EXPECT_DOUBLE_EQ((points.first - points.second).norm(), 5);
540  EXPECT_DOUBLE_EQ(geometry::distance2d(points.first, ls1), 0.);
541  EXPECT_DOUBLE_EQ(geometry::distance2d(points.second, ls2), 0.);
542 }
543 
544 TYPED_TEST(ThreeDLineStringsTest, projectedPointL2LLongLinestring) { // NOLINT
545  auto ls1 = this->getLinestringAt(0, 100);
546  auto ls2 = this->getLinestringAt(5, 100);
547  auto points = geometry::projectedPoint3d(ls1, ls2);
548  EXPECT_DOUBLE_EQ((points.first - points.second).norm(), 5);
549  EXPECT_DOUBLE_EQ(geometry::distance3d(points.first, ls1), 0.);
550  EXPECT_DOUBLE_EQ(geometry::distance3d(points.second, ls2), 0.);
551 }
552 
554  TypeParam ls3(20, {Point3d(21, 2., 0., 0.), Point3d(22, 1.5, 0.5, 0.)});
555  auto aligned = geometry::align(this->ls1, ls3);
556  EXPECT_EQ(aligned.first, this->ls1);
557  EXPECT_EQ(aligned.second, ls3);
558 
559  aligned = geometry::align(ls3, this->ls1);
560  EXPECT_EQ(aligned.first.invert(), ls3);
561  EXPECT_EQ(aligned.second.invert(), this->ls1);
562 }
563 
564 TYPED_TEST(HybridLineStringsTest, segmentLength) { // NOLINT
565  auto segment = this->ls1.segment(0);
566  EXPECT_DOUBLE_EQ(geometry::length(segment), 1.);
567 }
568 
569 /*
570  * O
571  * |
572  * |
573  * |
574  * O--X
575  * |
576  * |
577  * |
578  * O
579  */
581  Id id = 0;
582  Point3d p1 = Point3d(++id, 0., 0.);
583  Point3d p2 = Point3d(++id, 0., 10.);
584  LineString3d ls(++id, Points3d{p1, p2});
586  EXPECT_TRUE(boost::geometry::equals(ap, BasicPoint2d{-2, 5}));
587 }
588 
590  Id id = 0;
591  Point3d p1 = Point3d(++id, 1., 0.);
592  Point3d p2 = Point3d(++id, 1., 1.);
593  Point3d p3 = Point3d(++id, 4., 1.);
594  Point3d p4 = Point3d(++id, 4., 3.);
595  LineString3d ls(++id, Points3d{p1, p2, p3, p4});
596  auto ap = geometry::offset(utils::to2D(ls), 1.);
597  BasicLineString2d comp({BasicPoint2d(0, 0), BasicPoint2d(0, 2), BasicPoint2d(3, 2), BasicPoint2d(3, 3)});
598  // required due to numeric approximation errors
599  for (size_t i = 0; i < ls.size(); ++i) {
600  EXPECT_NEAR(ap[i].x(), comp[i].x(), 1e-9);
601  EXPECT_NEAR(ap[i].y(), comp[i].y(), 1e-9);
602  }
603 
604  Point3d p11 = Point3d(++id, 1, 0);
605  Point3d p12 = Point3d(++id, 1, 1);
606  Point3d p13 = Point3d(++id, 0, 1);
607  Point3d p13a = Point3d(++id, 2, 1);
608  Point3d p14 = Point3d(++id, 0.5, 0);
609  Point3d p15 = Point3d(++id, 0.5, 1);
610  Point3d p16 = Point3d(++id, 1, 0.5);
611  Point3d p17 = Point3d(++id, 0, 0.5);
612  Point3d p18 = Point3d(++id, 0.5, 1.5);
613  Point3d p19 = Point3d(++id, 2, 1.5);
614 
615  BasicLineString2d l1{utils::toBasicPoint(utils::to2D(p11)), utils::toBasicPoint(utils::to2D(p12)),
617  BasicLineString2d l2{utils::toBasicPoint(utils::to2D(p11)), utils::toBasicPoint(utils::to2D(p12)),
619  auto lss = geometry::offset(l1, 0.5);
620  EXPECT_TRUE(boost::geometry::equals(
621  lss, BasicLineString2d{utils::toBasicPoint(utils::to2D(p14)), BasicPoint2d{0.5, 0.5}, BasicPoint2d{0, 0.5}}));
622  auto lss2 = geometry::offset(l2, 0.5);
623  EXPECT_TRUE(boost::geometry::equals(
624  lss2, BasicLineString2d{utils::toBasicPoint(utils::to2D(p14)), utils::toBasicPoint(utils::to2D(p18)),
626 }
627 
629  traits::PointType<typename TestFixture::LineStringT> p3d(100000000000, 0, 1.5, 1.5);
631  auto bp = utils::toBasicPoint(p3d);
632  auto refp = utils::toBasicPoint(ref3d);
633  auto cs = geometry::closestSegment(this->ls1, bp);
634  EXPECT_TRUE(boost::geometry::equals(cs.first, refp));
635 
636  auto b2dcs = geometry::closestSegment(utils::to2D(this->ls1).basicLineString(), utils::to2D(bp));
637  EXPECT_TRUE(boost::geometry::equals(b2dcs.first, utils::to2D(refp)));
638  auto b3dcs = geometry::closestSegment(this->ls1.basicLineString(), bp);
639  EXPECT_TRUE(boost::geometry::equals(b3dcs.first, refp));
640 }
641 
643  EXPECT_EQ(this->ls4.size(), 3ul);
644 
645  auto shifted = geometry::internal::shiftLateral(this->ls4, 1, 1., geometry::internal::makeVincinity(this->ls4, 1));
646  EXPECT_TRUE(boost::geometry::equals(shifted, BasicPoint2d(-1, 1. + sqrt(3) / 3)));
647 }
648 
649 /* O O
650  * /| |\
651  * O-X---X-O
652  * | |
653  * O O
654  */
656  auto p1 = BasicPoint2d(2, 0);
657  auto p2 = BasicPoint2d(2, 2);
658  auto p3 = BasicPoint2d(3, 1);
659  auto p4 = BasicPoint2d(0, 1);
660  auto p5 = BasicPoint2d(1, 2);
661  auto p6 = BasicPoint2d(1, 0);
662  auto p7 = BasicPoint2d(2, 1);
663  auto p8 = BasicPoint2d(1, 1);
664  BasicLineString2d l1{p1, p2, p3, p4, p5, p6};
665  BasicLineString2d l2{p1, p7, p8, p6};
667  EXPECT_TRUE(boost::geometry::equals(ret, l2));
668 }
669 
671  auto p1 = BasicPoint2d(1, 0);
672  auto p2 = BasicPoint2d(1, 1);
673  auto p3 = BasicPoint2d(0, 1);
674  auto p3a = BasicPoint2d(2, 1);
675  auto p3b = BasicPoint2d(0, 0);
676  auto p4 = BasicPoint2d(0.5, 0);
677  auto p5 = BasicPoint2d(0.5, 1);
678  auto p6 = BasicPoint2d(1, 0.5);
679  auto p7 = BasicPoint2d(0, 0.5);
680  auto p8 = BasicPoint2d(0.5, 1.5);
681  auto p9 = BasicPoint2d(2, 1.5);
682 
683  BasicLineString2d l1{p1, p2, p3};
684  BasicLineString2d l2{p1, p2, p3a};
685  BasicLineString2d l3{p1, p2, p3b};
686  auto lss = geometry::internal::extractConvex(l1, 0.5);
687  ASSERT_EQ(lss.size(), 2ul);
688  EXPECT_TRUE(boost::geometry::equals(lss.front(), BasicLineString2d{p4, p5}));
689  EXPECT_TRUE(boost::geometry::equals(lss.back(), BasicLineString2d{p6, p7}));
690  auto lss2 = geometry::internal::extractConvex(l2, 0.5);
691  ASSERT_EQ(lss2.size(), 1ul);
692  EXPECT_TRUE(boost::geometry::equals(lss2.front(), BasicLineString2d{p4, p8, p9}));
693  auto lss3 = geometry::internal::extractConvex(l3, -0.5);
694  ASSERT_EQ(lss3.size(), 1ul);
695  ASSERT_EQ(lss3.front().size(), 4ul);
696  EXPECT_TRUE(boost::geometry::equals(lss2.front(), BasicLineString2d{p4, p8, p9}));
697 }
698 
699 /*
700  * O----O
701  * | |
702  * | O
703  * |
704  * |
705  * O------O
706  *
707  */
708 
709 TEST(TwoDLineStringsTest, checkInversion) {
710  auto p1 = BasicPoint2d(3, 3);
711  auto p2 = BasicPoint2d(3, 5);
712  auto p3 = BasicPoint2d(0, 5);
713  auto p4 = BasicPoint2d(0, 0);
714  auto p5 = BasicPoint2d(4, 0);
715 
716  BasicLineString2d l1{p1, p2, p3, p4, p5};
717  EXPECT_THROW(geometry::offset(l1, 2), GeometryError); // NOLINT
718  EXPECT_NO_THROW(geometry::offset(l1, 1)); // NOLINT
719 }
testing::Types< LineString2d, LineString3d, ConstLineString2d, ConstLineString3d, ConstHybridLineString2d, ConstHybridLineString3d, CompoundLineString2d, CompoundLineString3d, CompoundHybridLineString2d, CompoundHybridLineString3d > AllLineStrings
BasicPoint p
testing::Types< LineString2d, LineString3d, ConstLineString2d, ConstLineString3d, CompoundLineString2d, CompoundLineString3d > NonHybridLineStrings
Segm segm
IfLL< Lanelet1T, bool > intersects3d(const Lanelet1T &lanelet, const Lanelet2T &otherLanelet, double heightTolerance)
test whether two lanelets intersect in 2d.
static LineStringT getLinestringAt(double y, size_t n=100)
BasicPoints3d BasicLineString3d
double rangedLength(LineStringIterator start, LineStringIterator end)
A Linestring that returns BasicPoint2d instead of Point2d.
A Compound linestring in 3d (returns Point3d)
static constexpr const char Curbstone[]
Definition: Attribute.h:283
Thrown when a geometric operation is not valid.
Definition: Exceptions.h:63
testing::Types< LineString2d, LineString3d > MutableLineStrings
ConstPrimitiveType< PrimitiveT > toConst(const PrimitiveT &primitive)
Converts a primitive to its matching const type.
Definition: Traits.h:108
int64_t Id
Definition: Forward.h:198
BasicPoint2d fromArcCoords(const HybridLineStringT &hLineString, const BasicPoint2d &projStart, const size_t startIdx, const size_t endIdx, const double distance)
auto transform(Iterator begin, Iterator end, const Func f)
Definition: Utilities.h:176
Eigen::Vector3d BasicPoint3d
a simple 3d-point
testing::Types< LineString2d, LineString3d, ConstLineString2d, ConstLineString3d, ConstHybridLineString2d, ConstHybridLineString3d > PrimitiveLineStrings
traits::BasicPointT< traits::PointType< LineStringT > > interpolatedPointAtDistance(LineStringT lineString, double dist)
typename LineStringTraits< LineStringT >::PointType PointType
Definition: Traits.h:191
BasicPoint2d fromArcCoordinates(const LineString2dT &lineString, const ArcCoordinates &arcCoords)
create a point by moving laterally arcCoords.distance from the linestring point at arcCoords...
BasicPoint2d shiftLateral(const LineString2dT &lineString, const size_t idx, const double offset, const PointVincinity &pv)
shiftLateral shift point along the bisectrix
A hybrid compound linestring in 2d (returns BasicPoint2d)
std::vector< BasicLineString2d > extractConvex(const LineString2dT &lineString, const double distance)
extractConvex get convex parts of line string offset by distance.
testing::Types< BasicLineString2d, BasicLineString3d > BasicLineStrings
void SetUp() override
auto getZ(const T &p) -> std::enable_if_t<!traits::is2D< T >(), double >
std::vector< double > lengthRatios(const LineStringT &lineString)
BasicPoint3d project(const LineString3dT &lineString, const BasicPoint3d &pointToProject)
Projects the given point in 3d to the LineString.
Describes a position in linestring coordinates.
A normal 3d linestring with immutable data.
BoundingBox2d bbox
traits::PointType< LineStringT > nearestPointAtDistance(LineStringT lineString, double dist)
returns the cosest point to a position on the linestring
const VectorType &() min() const
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.
std::vector< Point3d > Points3d
Definition: Forward.h:34
BasicPoint p2
Eigen::AlignedBox3d BoundingBox3d
Convenience type for an axis aligned bounding box in 3d.
static constexpr const char Type[]
Definition: Attribute.h:204
A normal 3d linestring with mutable data.
A mutable 3d point.
double curvature2d(const Point2dT &p1, const Point2dT &p2, const Point2dT &p3)
const VectorType &() max() const
std::vector< double > accumulatedLengthRatios(const LineStringT &lineString)
A Compound linestring in 2d (returns Point2d)
BasicLineString basicLineString() const noexcept
Create a basic linestring (ie a vector of Eigen Points)
BasicPoints2d BasicLineString2d
#define TYPED_TEST_SUITE
IfAr< AreaT, BoundingBox2d > boundingBox2d(const AreaT &area)
calculates an up-right 2d bounding box
Optional< double > distance
LineStringT invert(const LineStringT &ls)
static LineStringT getLinestringAt(double y, size_t n=100)
testing::Types< LineString3d, ConstLineString3d, ConstHybridLineString3d, CompoundLineString3d, CompoundHybridLineString3d, BasicLineString3d > ThreeDLineStrings
void SetUp() override
A Linestring that returns BasicPoint3d instead of Point3d.
double distance
signed distance to linestring (left=positive)
testing::Types< ConstHybridLineString2d, ConstHybridLineString3d, CompoundHybridLineString2d, CompoundHybridLineString3d > HybridLineStrings
IfLS2< LineString3d1T, LineString3d2T, double > distance3d(const LineString3d1T &l1, const LineString3d2T &l2)
Axis-Aligned bounding box in 2d.
Eigen::Matrix< double, 2, 1, Eigen::DontAlign > BasicPoint2d
a simple 2d-point
auto toBasicSegment(const Segment< PointT > &s)
BasicPoint p1
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:...
testing::Types< LineString2d, LineString3d, ConstLineString2d, ConstLineString3d > NormalLineStrings
A hybrid compound linestring in 3d (returns BasicPoint3d)
TEST(TwoDLineStringsTest, removeSelfIntersections)
testing::Types< LineString2d, ConstLineString2d, ConstHybridLineString2d, CompoundLineString2d, CompoundHybridLineString2d, BasicLineString2d > TwoDLineStrings
BasicLineString2d removeSelfIntersections(const BasicLineString2d &lineString)
Id id
Definition: LaneletMap.cpp:63
auto toBasicPoint(const PointT &point) -> std::enable_if_t< PointTraits< PointT >::IsPrimitive, BasicPointT< PointT >>
Definition: Traits.h:165
typename LineString2d ::BasicLineString LineStringT
double signedDistance(const LineString3dT &lineString, const BasicPoint3d &p)
TYPED_TEST(MutableLineStringsTest, id)
void SetUp() override
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...
BoundingBox2d to2D(const BoundingBox3d &primitive)
double length
length along linestring
static LineStringT getLinestringAt(double y, size_t n=100)
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.
A mutable 2d point.
std::pair< LineString1T, LineString2T > align(LineString1T left, LineString2T right)
inverts the two linestrings such that they are parallel
double distance2d(const RegulatoryElement &regElem, const BasicPoint2d &p)
testing::Types< BasicPoint2d, Point2d, ConstPoint2d > TwoDPoints
PointVincinity makeVincinity(const LineString2dT &lineString, const size_t idx)
makeVincinity create pair of preceding and following point on a line string
IfAr< AreaT, BoundingBox3d > boundingBox3d(const AreaT &area)
calculates 3d bounding box


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