1 #include <gtest/gtest.h>
3 #include <boost/geometry/algorithms/equals.hpp>
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.);
42 p3 =
Point2d(++
id, -1., 0., 0.);
67 std::vector<Point3d> points;
68 for (
auto i = 0; i < n; i++) {
69 points.push_back(
Point3d(++
id, i, y, 0));
95 std::vector<Point3d> points;
96 for (
auto i = 0; i < n; i++) {
97 points.push_back(
Point3d(++
id, i, y, 0));
104 template <
typename T>
130 template <
typename T>
131 auto getZ(
const T&
p) -> std::enable_if_t<!traits::is2D<T>(),
double> {
134 template <
typename T>
135 auto getZ(
const T& ) -> std::enable_if_t<traits::is2D<T>(),
double> {
156 template <
typename T>
159 template <
typename T>
162 template <
typename T>
165 template <
typename T>
168 template <
typename T>
171 template <
typename T>
174 template <
typename T>
177 template <
typename T>
180 template <
typename T>
183 template <
typename T>
185 using TwoDPoints = testing::Types<BasicPoint2d, Point2d, ConstPoint2d>;
189 using NormalLineStrings = testing::Types<LineString2d, LineString3d, ConstLineString2d, ConstLineString3d>;
204 #ifndef TYPED_TEST_SUITE
206 #define TYPED_TEST_SUITE TYPED_TEST_CASE
220 this->ls1.setId(100);
221 EXPECT_EQ(100, this->ls1.id());
233 EXPECT_EQ(constLs, this->ls1);
237 auto xs =
utils::transform(this->ls1, [](
const auto& elem) {
return elem.x(); });
238 EXPECT_EQ(3ul, xs.size());
245 auto invertLs = this->ls1.invert();
246 auto ys =
utils::transform(invertLs, [](
const auto& elem) {
return elem.y(); });
247 ASSERT_EQ(3ul, ys.size());
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]);
260 invertLs.push_back(this->p22);
261 EXPECT_EQ(this->p22.id(), this->ls1[0].id());
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]);
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);
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());
290 auto invertLs = this->ls1.invert();
292 ASSERT_EQ(2ul, invertLs.size());
293 EXPECT_EQ(invertLs.front(), this->p13);
294 EXPECT_EQ(invertLs.back(), this->p12);
321 auto ls2 = this->getLinestringAt(0, 100);
322 auto ls1 = this->getLinestringAt(5, 100);
327 auto l = geometry::length(this->ls1);
329 if (traits::is2D<TypeParam>()) {
330 EXPECT_DOUBLE_EQ(2, l);
332 EXPECT_DOUBLE_EQ(1 + std::sqrt(2), l);
334 EXPECT_DOUBLE_EQ(1, lSeg1);
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(); });
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);
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);
359 ASSERT_EQ(2ul, lRatios.size());
360 if (traits::is2D<TypeParam>()) {
361 EXPECT_DOUBLE_EQ(0.5, lRatios[0]);
363 EXPECT_DOUBLE_EQ(1 / (1 + std::sqrt(2)), lRatios[0]);
369 ASSERT_EQ(2ul, lRatios.size());
370 EXPECT_DOUBLE_EQ(1, lRatios[1]);
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);
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);
384 EXPECT_DOUBLE_EQ(
getZ(
p), 0.5);
385 EXPECT_DOUBLE_EQ(
getZ(pInv), 0.5);
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);
395 EXPECT_EQ(
p, this->ls1[1]);
396 EXPECT_EQ(pInv, this->ls1[1]);
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]);
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]);
417 EXPECT_DOUBLE_EQ(std::numeric_limits<double>::infinity(),
geometry::curvature2d(this->p3, this->
p2, this->p4));
427 EXPECT_DOUBLE_EQ(-1.,
d);
429 EXPECT_DOUBLE_EQ(-std::sqrt(1.25), d2);
442 EXPECT_DOUBLE_EQ(-2.,
d);
444 EXPECT_DOUBLE_EQ(1, d2);
458 EXPECT_EQ(-std::sqrt(2), arcPoint.
distance);
459 EXPECT_EQ(0, arcPoint.
length);
462 EXPECT_EQ(1.5, arcPoint2.
length);
468 EXPECT_DOUBLE_EQ(0, projectedPoint.x());
469 EXPECT_DOUBLE_EQ(1.5, projectedPoint.y());
475 EXPECT_DOUBLE_EQ(0, projectedPoint.x());
476 EXPECT_DOUBLE_EQ(1.5, projectedPoint.y());
477 EXPECT_DOUBLE_EQ(0.5, projectedPoint.z());
482 auto ls = this->getLinestringAt(5, 100);
484 EXPECT_DOUBLE_EQ(0, projectedPoint.x());
485 EXPECT_DOUBLE_EQ(5, projectedPoint.y());
490 auto ls = this->getLinestringAt(5, 100);
492 EXPECT_DOUBLE_EQ(0, projectedPoint.x());
493 EXPECT_DOUBLE_EQ(5, projectedPoint.y());
494 EXPECT_DOUBLE_EQ(0, projectedPoint.z());
515 auto ls = this->getLinestringAt(5, 100);
522 auto ls = this->getLinestringAt(5, 100);
529 EXPECT_DOUBLE_EQ((points.first - points.second).norm(),
geometry::distance2d(this->ls1, this->ls2));
536 EXPECT_DOUBLE_EQ((points.first - points.second).norm(),
geometry::distance3d(this->ls1, this->ls2));
542 auto ls1 = this->getLinestringAt(0, 100);
543 auto ls2 = this->getLinestringAt(5, 100);
545 EXPECT_DOUBLE_EQ((points.first - points.second).norm(), 5);
551 auto ls1 = this->getLinestringAt(0, 100);
552 auto ls2 = this->getLinestringAt(5, 100);
554 EXPECT_DOUBLE_EQ((points.first - points.second).norm(), 5);
560 TypeParam ls3(20, {
Point3d(21, 2., 0., 0.),
Point3d(22, 1.5, 0.5, 0.)});
562 EXPECT_EQ(aligned.first, this->ls1);
563 EXPECT_EQ(aligned.second, ls3);
566 EXPECT_EQ(aligned.first.invert(), ls3);
567 EXPECT_EQ(aligned.second.invert(), this->ls1);
571 auto segment = this->ls1.segment(0);
572 EXPECT_DOUBLE_EQ(geometry::length(segment), 1.);
592 EXPECT_TRUE(boost::geometry::equals(ap,
BasicPoint2d{-2, 5}));
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);
626 EXPECT_TRUE(boost::geometry::equals(
629 EXPECT_TRUE(boost::geometry::equals(
640 EXPECT_TRUE(boost::geometry::equals(cs.first, refp));
643 EXPECT_TRUE(boost::geometry::equals(b2dcs.first,
utils::to2D(refp)));
645 EXPECT_TRUE(boost::geometry::equals(b3dcs.first, refp));
649 EXPECT_EQ(this->ls4.size(), 3ul);
652 EXPECT_TRUE(boost::geometry::equals(shifted,
BasicPoint2d(-1, 1. + sqrt(3) / 3)));
673 EXPECT_TRUE(boost::geometry::equals(ret, l2));
693 ASSERT_EQ(lss.size(), 2ul);
697 ASSERT_EQ(lss2.size(), 1ul);
698 EXPECT_TRUE(boost::geometry::equals(lss2.front(),
BasicLineString2d{p4, p8, p9}));
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}));