00001
00002
00003
00004
00005
00006
00007
00008
00009 #include "grid_map_core/Polygon.hpp"
00010
00011
00012 #include <gtest/gtest.h>
00013
00014
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, convexHullPoints)
00071 {
00072
00073 std::vector<Position> points1;
00074 points1.push_back(Vector2d(0.0, 0.0));
00075 points1.push_back(Vector2d(1.0, 0.0));
00076 points1.push_back(Vector2d(1.0, 1.0));
00077 points1.push_back(Vector2d(0.0, 1.0));
00078 Polygon polygon1 = Polygon::monotoneChainConvexHullOfPoints(points1);
00079 EXPECT_EQ(4, polygon1.nVertices());
00080 EXPECT_TRUE(polygon1.isInside(Vector2d(0.5, 0.5)));
00081 EXPECT_FALSE(polygon1.isInside(Vector2d(-0.01, 0.5)));
00082
00083
00084 std::vector<Position> points2;
00085 points2.push_back(Vector2d(0.0, 0.0));
00086 points2.push_back(Vector2d(1.0, 0.0));
00087 points2.push_back(Vector2d(2.0, 1.0));
00088 points2.push_back(Vector2d(1.0, 2.0));
00089 points2.push_back(Vector2d(-1.0, 2.0));
00090 points2.push_back(Vector2d(-1.0, -2.0));
00091 points2.push_back(Vector2d(0.0, 1.0));
00092 points2.push_back(Vector2d(1.0, 1.0));
00093 Polygon polygon2 = Polygon::monotoneChainConvexHullOfPoints(points2);
00094 EXPECT_EQ(4, polygon2.nVertices());
00095 EXPECT_TRUE(polygon2.isInside(Vector2d(0.5, 0.5)));
00096 EXPECT_TRUE(polygon2.isInside(Vector2d(0.0, 1.0)));
00097 EXPECT_TRUE(polygon2.isInside(Vector2d(-0.5, -0.5)));
00098 EXPECT_FALSE(polygon2.isInside(Vector2d(2.0, 0.0)));
00099 EXPECT_FALSE(polygon2.isInside(Vector2d(-0.5, -2)));
00100 EXPECT_FALSE(polygon2.isInside(Vector2d(1.75, 1.75)));
00101 }
00102
00103 TEST(Polygon, convexHullPolygon)
00104 {
00105 Polygon polygon1;
00106 polygon1.addVertex(Vector2d(0.0, 0.0));
00107 polygon1.addVertex(Vector2d(1.0, 1.0));
00108 polygon1.addVertex(Vector2d(0.0, 1.0));
00109 polygon1.addVertex(Vector2d(1.0, 0.0));
00110
00111 Polygon polygon2;
00112 polygon2.addVertex(Vector2d(0.5, 0.5));
00113 polygon2.addVertex(Vector2d(0.5, 1.5));
00114 polygon2.addVertex(Vector2d(1.5, 0.5));
00115 polygon2.addVertex(Vector2d(1.5, 1.5));
00116
00117 Polygon hull = Polygon::convexHull(polygon1, polygon2);
00118
00119 EXPECT_EQ(6, hull.nVertices());
00120 EXPECT_TRUE(hull.isInside(Vector2d(0.5, 0.5)));
00121 EXPECT_FALSE(hull.isInside(Vector2d(0.01, 1.49)));
00122 }
00123
00124 TEST(Polygon, convexHullCircles)
00125 {
00126 Position center1(0.0, 0.0);
00127 Position center2(1.0, 0.0);
00128 double radius = 0.5;
00129 const int nVertices = 15;
00130
00131 Polygon hull = Polygon::convexHullOfTwoCircles(center1, center2, radius);
00132 EXPECT_EQ(20, hull.nVertices());
00133 EXPECT_TRUE(hull.isInside(Vector2d(-0.25, 0.0)));
00134 EXPECT_TRUE(hull.isInside(Vector2d(0.5, 0.0)));
00135 EXPECT_TRUE(hull.isInside(Vector2d(0.5, 0.4)));
00136 EXPECT_FALSE(hull.isInside(Vector2d(0.5, 0.6)));
00137 EXPECT_FALSE(hull.isInside(Vector2d(1.5, 0.2)));
00138
00139 hull = Polygon::convexHullOfTwoCircles(center1, center2, radius, nVertices);
00140 EXPECT_EQ(nVertices + 1, hull.nVertices());
00141 EXPECT_TRUE(hull.isInside(Vector2d(-0.25, 0.0)));
00142 EXPECT_TRUE(hull.isInside(Vector2d(0.5, 0.0)));
00143 EXPECT_TRUE(hull.isInside(Vector2d(0.5, 0.4)));
00144 EXPECT_FALSE(hull.isInside(Vector2d(0.5, 0.6)));
00145 EXPECT_FALSE(hull.isInside(Vector2d(1.5, 0.2)));
00146
00147 hull = Polygon::convexHullOfTwoCircles(center1, center1, radius);
00148 EXPECT_EQ(20, hull.nVertices());
00149 EXPECT_TRUE(hull.isInside(Vector2d(-0.25, 0.0)));
00150 EXPECT_TRUE(hull.isInside(Vector2d(0.25, 0.0)));
00151 EXPECT_TRUE(hull.isInside(Vector2d(0.0, 0.25)));
00152 EXPECT_TRUE(hull.isInside(Vector2d(0.0, -0.25)));
00153 EXPECT_FALSE(hull.isInside(Vector2d(0.5, 0.5)));
00154 EXPECT_FALSE(hull.isInside(Vector2d(0.6, 0.0)));
00155 EXPECT_FALSE(hull.isInside(Vector2d(-0.6, 0.0)));
00156 EXPECT_FALSE(hull.isInside(Vector2d(0.0, 0.6)));
00157 EXPECT_FALSE(hull.isInside(Vector2d(0.0, -0.6)));
00158
00159 hull = Polygon::convexHullOfTwoCircles(center1, center1, radius, nVertices);
00160 EXPECT_EQ(nVertices, hull.nVertices());
00161 EXPECT_TRUE(hull.isInside(Vector2d(-0.25, 0.0)));
00162 EXPECT_TRUE(hull.isInside(Vector2d(0.25, 0.0)));
00163 EXPECT_TRUE(hull.isInside(Vector2d(0.0, 0.25)));
00164 EXPECT_TRUE(hull.isInside(Vector2d(0.0, -0.25)));
00165 EXPECT_FALSE(hull.isInside(Vector2d(0.5, 0.5)));
00166 EXPECT_FALSE(hull.isInside(Vector2d(0.6, 0.0)));
00167 EXPECT_FALSE(hull.isInside(Vector2d(-0.6, 0.0)));
00168 EXPECT_FALSE(hull.isInside(Vector2d(0.0, 0.6)));
00169 EXPECT_FALSE(hull.isInside(Vector2d(0.0, -0.6)));
00170 }
00171
00172 TEST(Polygon, convexHullCircle)
00173 {
00174 Position center(0.0, 0.0);
00175 double radius = 0.5;
00176 const int nVertices = 15;
00177
00178 Polygon hull = Polygon::fromCircle(center, radius);
00179
00180 EXPECT_EQ(20, hull.nVertices());
00181 EXPECT_TRUE(hull.isInside(Vector2d(-0.25, 0.0)));
00182 EXPECT_TRUE(hull.isInside(Vector2d(0.49, 0.0)));
00183 EXPECT_FALSE(hull.isInside(Vector2d(0.5, 0.4)));
00184 EXPECT_FALSE(hull.isInside(Vector2d(1.0, 0.0)));
00185
00186 hull = Polygon::fromCircle(center, radius, nVertices);
00187 EXPECT_EQ(nVertices, hull.nVertices());
00188 EXPECT_TRUE(hull.isInside(Vector2d(-0.25, 0.0)));
00189 EXPECT_TRUE(hull.isInside(Vector2d(0.49, 0.0)));
00190 EXPECT_FALSE(hull.isInside(Vector2d(0.5, 0.4)));
00191 EXPECT_FALSE(hull.isInside(Vector2d(1.0, 0.0)));
00192 }
00193
00194 TEST(convertToInequalityConstraints, triangle1)
00195 {
00196 Polygon polygon({Position(1.0, 1.0), Position(0.0, 0.0), Position(1.1, -1.1)});
00197 MatrixXd A;
00198 VectorXd b;
00199 ASSERT_TRUE(polygon.convertToInequalityConstraints(A, b));
00200 EXPECT_NEAR(-1.3636, A(0, 0), 1e-4);
00201 EXPECT_NEAR( 1.3636, A(0, 1), 1e-4);
00202 EXPECT_NEAR(-1.5000, A(1, 0), 1e-4);
00203 EXPECT_NEAR(-1.5000, A(1, 1), 1e-4);
00204 EXPECT_NEAR( 2.8636, A(2, 0), 1e-4);
00205 EXPECT_NEAR( 0.1364, A(2, 1), 1e-4);
00206 EXPECT_NEAR( 0.0000, b(0), 1e-4);
00207 EXPECT_NEAR( 0.0000, b(1), 1e-4);
00208 EXPECT_NEAR( 3.0000, b(2), 1e-4);
00209 }
00210
00211 TEST(convertToInequalityConstraints, triangle2)
00212 {
00213 Polygon polygon({Position(-1.0, 0.5), Position(-1.0, -0.5), Position(1.0, -0.5)});
00214 MatrixXd A;
00215 VectorXd b;
00216 ASSERT_TRUE(polygon.convertToInequalityConstraints(A, b));
00217 EXPECT_NEAR(-1.5000, A(0, 0), 1e-4);
00218 EXPECT_NEAR( 0.0000, A(0, 1), 1e-4);
00219 EXPECT_NEAR( 0.0000, A(1, 0), 1e-4);
00220 EXPECT_NEAR(-3.0000, A(1, 1), 1e-4);
00221 EXPECT_NEAR( 1.5000, A(2, 0), 1e-4);
00222 EXPECT_NEAR( 3.0000, A(2, 1), 1e-4);
00223 EXPECT_NEAR( 1.5000, b(0), 1e-4);
00224 EXPECT_NEAR( 1.5000, b(1), 1e-4);
00225 EXPECT_NEAR( 0.0000, b(2), 1e-4);
00226 }
00227
00228 TEST(offsetInward, triangle)
00229 {
00230 Polygon polygon({Position(1.0, 1.0), Position(0.0, 0.0), Position(1.0, -1.0)});
00231 polygon.offsetInward(0.1);
00232 EXPECT_NEAR(0.9, polygon.getVertex(0)(0), 1e-4);
00233 EXPECT_NEAR(0.758579, polygon.getVertex(0)(1), 1e-4);
00234 EXPECT_NEAR(0.141421, polygon.getVertex(1)(0), 1e-4);
00235 EXPECT_NEAR(0.0, polygon.getVertex(1)(1), 1e-4);
00236 EXPECT_NEAR(0.9, polygon.getVertex(2)(0), 1e-4);
00237 EXPECT_NEAR(-0.758579, polygon.getVertex(2)(1), 1e-4);
00238 }
00239
00240 TEST(triangulation, triangle)
00241 {
00242 Polygon polygon({Position(1.0, 1.0), Position(0.0, 0.0), Position(1.0, -1.0)});
00243 std::vector<Polygon> polygons;
00244 polygons = polygon.triangulate();
00245 ASSERT_EQ(1, polygons.size());
00246 EXPECT_EQ(polygon.getVertex(0).x(), polygons[0].getVertex(0).x());
00247 EXPECT_EQ(polygon.getVertex(0).y(), polygons[0].getVertex(0).y());
00248 EXPECT_EQ(polygon.getVertex(1).x(), polygons[0].getVertex(1).x());
00249 EXPECT_EQ(polygon.getVertex(1).y(), polygons[0].getVertex(1).y());
00250 EXPECT_EQ(polygon.getVertex(2).x(), polygons[0].getVertex(2).x());
00251 EXPECT_EQ(polygon.getVertex(2).y(), polygons[0].getVertex(2).y());
00252 }
00253
00254 TEST(triangulation, rectangle)
00255 {
00256 Polygon rectangle;
00257 rectangle.addVertex(Vector2d(-2.0, -1.0));
00258 rectangle.addVertex(Vector2d(-2.0, 2.0));
00259 rectangle.addVertex(Vector2d(1.0, 2.0));
00260 rectangle.addVertex(Vector2d(1.0, -1.0));
00261 std::vector<Polygon> polygons;
00262 polygons = rectangle.triangulate();
00263 ASSERT_EQ(2, polygons.size());
00264
00265 }