PolygonTest.cpp
Go to the documentation of this file.
00001 /*
00002  * PolygonTest.cpp
00003  *
00004  *  Created on: Mar 24, 2015
00005  *      Author: Martin Wermelinger, Péter Fankhauser
00006  *       Institute: ETH Zurich, Autonomous Systems Lab
00007  */
00008 
00009 #include "grid_map_core/Polygon.hpp"
00010 
00011 // gtest
00012 #include <gtest/gtest.h>
00013 
00014 // Eigen
00015 #include <Eigen/Core>
00016 #include <Eigen/Dense>
00017 
00018 using namespace std;
00019 using namespace Eigen;
00020 using namespace grid_map;
00021 
00022 TEST(Polygon, getCentroidTriangle)
00023 {
00024   Polygon triangle;
00025   triangle.addVertex(Vector2d(0.0, 0.0));
00026   triangle.addVertex(Vector2d(1.0, 0.0));
00027   triangle.addVertex(Vector2d(0.5, 1.0));
00028 
00029   Position expectedCentroid;
00030   expectedCentroid.x() = 1.0 / 3.0 * (1.0 + 0.5);
00031   expectedCentroid.y() = 1.0 / 3.0;
00032   Position centroid = triangle.getCentroid();
00033   EXPECT_DOUBLE_EQ(expectedCentroid.x(), centroid.x());
00034   EXPECT_DOUBLE_EQ(expectedCentroid.y(), centroid.y());
00035 }
00036 
00037 TEST(Polygon, getCentroidRectangle)
00038 {
00039   Polygon rectangle;
00040   rectangle.addVertex(Vector2d(-2.0, -1.0));
00041   rectangle.addVertex(Vector2d(-2.0, 2.0));
00042   rectangle.addVertex(Vector2d(1.0, 2.0));
00043   rectangle.addVertex(Vector2d(1.0, -1.0));
00044 
00045   Position expectedCentroid(-0.5, 0.5);
00046   Position centroid = rectangle.getCentroid();
00047   EXPECT_DOUBLE_EQ(expectedCentroid.x(), centroid.x());
00048   EXPECT_DOUBLE_EQ(expectedCentroid.y(), centroid.y());
00049 }
00050 
00051 TEST(Polygon, getBoundingBox)
00052 {
00053   Polygon triangle;
00054   triangle.addVertex(Vector2d(0.0, 0.0));
00055   triangle.addVertex(Vector2d(0.5, -1.2));
00056   triangle.addVertex(Vector2d(1.0, 0.0));
00057 
00058   Position expectedCenter(0.5, -0.6);
00059   Length expectedLength(1.0, 1.2);
00060   Position center;
00061   Length length;
00062   triangle.getBoundingBox(center, length);
00063 
00064   EXPECT_DOUBLE_EQ(expectedCenter.x(), center.x());
00065   EXPECT_DOUBLE_EQ(expectedCenter.y(), center.y());
00066   EXPECT_DOUBLE_EQ(expectedLength.x(), length.x());
00067   EXPECT_DOUBLE_EQ(expectedLength.y(), length.y());
00068 }
00069 
00070 TEST(Polygon, convexHullPolygon)
00071 {
00072   Polygon polygon1;
00073   polygon1.addVertex(Vector2d(0.0, 0.0));
00074   polygon1.addVertex(Vector2d(1.0, 1.0));
00075   polygon1.addVertex(Vector2d(0.0, 1.0));
00076   polygon1.addVertex(Vector2d(1.0, 0.0));
00077 
00078   Polygon polygon2;
00079   polygon2.addVertex(Vector2d(0.5, 0.5));
00080   polygon2.addVertex(Vector2d(0.5, 1.5));
00081   polygon2.addVertex(Vector2d(1.5, 0.5));
00082   polygon2.addVertex(Vector2d(1.5, 1.5));
00083 
00084   Polygon hull = Polygon::convexHull(polygon1, polygon2);
00085 
00086   EXPECT_EQ(6, hull.nVertices());
00087   EXPECT_TRUE(hull.isInside(Vector2d(0.5, 0.5)));
00088   EXPECT_FALSE(hull.isInside(Vector2d(0.01, 1.49)));
00089 }
00090 
00091 TEST(Polygon, convexHullCircles)
00092 {
00093   Position center1(0.0, 0.0);
00094   Position center2(1.0, 0.0);
00095   double radius = 0.5;
00096   const int nVertices = 15;
00097 
00098   Polygon hull = Polygon::convexHullOfTwoCircles(center1, center2, radius);
00099   EXPECT_EQ(20, hull.nVertices());
00100   EXPECT_TRUE(hull.isInside(Vector2d(-0.25, 0.0)));
00101   EXPECT_TRUE(hull.isInside(Vector2d(0.5, 0.0)));
00102   EXPECT_TRUE(hull.isInside(Vector2d(0.5, 0.4)));
00103   EXPECT_FALSE(hull.isInside(Vector2d(0.5, 0.6)));
00104   EXPECT_FALSE(hull.isInside(Vector2d(1.5, 0.2)));
00105 
00106   hull = Polygon::convexHullOfTwoCircles(center1, center2, radius, nVertices);
00107   EXPECT_EQ(nVertices + 1, hull.nVertices());
00108   EXPECT_TRUE(hull.isInside(Vector2d(-0.25, 0.0)));
00109   EXPECT_TRUE(hull.isInside(Vector2d(0.5, 0.0)));
00110   EXPECT_TRUE(hull.isInside(Vector2d(0.5, 0.4)));
00111   EXPECT_FALSE(hull.isInside(Vector2d(0.5, 0.6)));
00112   EXPECT_FALSE(hull.isInside(Vector2d(1.5, 0.2)));
00113 
00114   hull = Polygon::convexHullOfTwoCircles(center1, center1, radius);
00115   EXPECT_EQ(20, hull.nVertices());
00116   EXPECT_TRUE(hull.isInside(Vector2d(-0.25, 0.0)));
00117   EXPECT_TRUE(hull.isInside(Vector2d(0.25, 0.0)));
00118   EXPECT_TRUE(hull.isInside(Vector2d(0.0, 0.25)));
00119   EXPECT_TRUE(hull.isInside(Vector2d(0.0, -0.25)));
00120   EXPECT_FALSE(hull.isInside(Vector2d(0.5, 0.5)));
00121   EXPECT_FALSE(hull.isInside(Vector2d(0.6, 0.0)));
00122   EXPECT_FALSE(hull.isInside(Vector2d(-0.6, 0.0)));
00123   EXPECT_FALSE(hull.isInside(Vector2d(0.0, 0.6)));
00124   EXPECT_FALSE(hull.isInside(Vector2d(0.0, -0.6)));
00125 
00126   hull = Polygon::convexHullOfTwoCircles(center1, center1, radius, nVertices);
00127   EXPECT_EQ(nVertices, hull.nVertices());
00128   EXPECT_TRUE(hull.isInside(Vector2d(-0.25, 0.0)));
00129   EXPECT_TRUE(hull.isInside(Vector2d(0.25, 0.0)));
00130   EXPECT_TRUE(hull.isInside(Vector2d(0.0, 0.25)));
00131   EXPECT_TRUE(hull.isInside(Vector2d(0.0, -0.25)));
00132   EXPECT_FALSE(hull.isInside(Vector2d(0.5, 0.5)));
00133   EXPECT_FALSE(hull.isInside(Vector2d(0.6, 0.0)));
00134   EXPECT_FALSE(hull.isInside(Vector2d(-0.6, 0.0)));
00135   EXPECT_FALSE(hull.isInside(Vector2d(0.0, 0.6)));
00136   EXPECT_FALSE(hull.isInside(Vector2d(0.0, -0.6)));
00137 }
00138 
00139 TEST(Polygon, convexHullCircle)
00140 {
00141   Position center(0.0, 0.0);
00142   double radius = 0.5;
00143   const int nVertices = 15;
00144 
00145   Polygon hull = Polygon::fromCircle(center, radius);
00146 
00147   EXPECT_EQ(20, hull.nVertices());
00148   EXPECT_TRUE(hull.isInside(Vector2d(-0.25, 0.0)));
00149   EXPECT_TRUE(hull.isInside(Vector2d(0.49, 0.0)));
00150   EXPECT_FALSE(hull.isInside(Vector2d(0.5, 0.4)));
00151   EXPECT_FALSE(hull.isInside(Vector2d(1.0, 0.0)));
00152 
00153   hull = Polygon::fromCircle(center, radius, nVertices);
00154   EXPECT_EQ(nVertices, hull.nVertices());
00155   EXPECT_TRUE(hull.isInside(Vector2d(-0.25, 0.0)));
00156   EXPECT_TRUE(hull.isInside(Vector2d(0.49, 0.0)));
00157   EXPECT_FALSE(hull.isInside(Vector2d(0.5, 0.4)));
00158   EXPECT_FALSE(hull.isInside(Vector2d(1.0, 0.0)));
00159 }
00160 
00161 TEST(convertToInequalityConstraints, triangle1)
00162 {
00163   Polygon polygon({Position(1.0, 1.0), Position(0.0, 0.0), Position(1.1, -1.1)});
00164   MatrixXd A;
00165   VectorXd b;
00166   ASSERT_TRUE(polygon.convertToInequalityConstraints(A, b));
00167   EXPECT_NEAR(-1.3636, A(0, 0), 1e-4);
00168   EXPECT_NEAR( 1.3636, A(0, 1), 1e-4);
00169   EXPECT_NEAR(-1.5000, A(1, 0), 1e-4);
00170   EXPECT_NEAR(-1.5000, A(1, 1), 1e-4);
00171   EXPECT_NEAR( 2.8636, A(2, 0), 1e-4);
00172   EXPECT_NEAR( 0.1364, A(2, 1), 1e-4);
00173   EXPECT_NEAR( 0.0000, b(0), 1e-4);
00174   EXPECT_NEAR( 0.0000, b(1), 1e-4);
00175   EXPECT_NEAR( 3.0000, b(2), 1e-4);
00176 }
00177 
00178 TEST(convertToInequalityConstraints, triangle2)
00179 {
00180   Polygon polygon({Position(-1.0, 0.5), Position(-1.0, -0.5), Position(1.0, -0.5)});
00181   MatrixXd A;
00182   VectorXd b;
00183   ASSERT_TRUE(polygon.convertToInequalityConstraints(A, b));
00184   EXPECT_NEAR(-1.5000, A(0, 0), 1e-4);
00185   EXPECT_NEAR( 0.0000, A(0, 1), 1e-4);
00186   EXPECT_NEAR( 0.0000, A(1, 0), 1e-4);
00187   EXPECT_NEAR(-3.0000, A(1, 1), 1e-4);
00188   EXPECT_NEAR( 1.5000, A(2, 0), 1e-4);
00189   EXPECT_NEAR( 3.0000, A(2, 1), 1e-4);
00190   EXPECT_NEAR( 1.5000, b(0), 1e-4);
00191   EXPECT_NEAR( 1.5000, b(1), 1e-4);
00192   EXPECT_NEAR( 0.0000, b(2), 1e-4);
00193 }
00194 
00195 TEST(offsetInward, triangle)
00196 {
00197   Polygon polygon({Position(1.0, 1.0), Position(0.0, 0.0), Position(1.0, -1.0)});
00198   polygon.offsetInward(0.1);
00199   EXPECT_NEAR(0.9, polygon.getVertex(0)(0), 1e-4);
00200   EXPECT_NEAR(0.758579, polygon.getVertex(0)(1), 1e-4);
00201   EXPECT_NEAR(0.141421, polygon.getVertex(1)(0), 1e-4);
00202   EXPECT_NEAR(0.0, polygon.getVertex(1)(1), 1e-4);
00203   EXPECT_NEAR(0.9, polygon.getVertex(2)(0), 1e-4);
00204   EXPECT_NEAR(-0.758579, polygon.getVertex(2)(1), 1e-4);
00205 }
00206 
00207 TEST(triangulation, triangle)
00208 {
00209   Polygon polygon({Position(1.0, 1.0), Position(0.0, 0.0), Position(1.0, -1.0)});
00210   std::vector<Polygon> polygons;
00211   polygons = polygon.triangulate();
00212   ASSERT_EQ(1, polygons.size());
00213   EXPECT_EQ(polygon.getVertex(0).x(), polygons[0].getVertex(0).x());
00214   EXPECT_EQ(polygon.getVertex(0).y(), polygons[0].getVertex(0).y());
00215   EXPECT_EQ(polygon.getVertex(1).x(), polygons[0].getVertex(1).x());
00216   EXPECT_EQ(polygon.getVertex(1).y(), polygons[0].getVertex(1).y());
00217   EXPECT_EQ(polygon.getVertex(2).x(), polygons[0].getVertex(2).x());
00218   EXPECT_EQ(polygon.getVertex(2).y(), polygons[0].getVertex(2).y());
00219 }
00220 
00221 TEST(triangulation, rectangle)
00222 {
00223   Polygon rectangle;
00224   rectangle.addVertex(Vector2d(-2.0, -1.0));
00225   rectangle.addVertex(Vector2d(-2.0, 2.0));
00226   rectangle.addVertex(Vector2d(1.0, 2.0));
00227   rectangle.addVertex(Vector2d(1.0, -1.0));
00228   std::vector<Polygon> polygons;
00229   polygons = rectangle.triangulate();
00230   ASSERT_EQ(2, polygons.size());
00231   // TODO Extend.
00232 }


grid_map_core
Author(s): Péter Fankhauser
autogenerated on Mon Oct 9 2017 03:09:16