polygon_tests.cpp
Go to the documentation of this file.
00001 /*
00002  * Software License Agreement (BSD License)
00003  *
00004  *  Copyright (c) 2018, Locus Robotics
00005  *  All rights reserved.
00006  *
00007  *  Redistribution and use in source and binary forms, with or without
00008  *  modification, are permitted provided that the following conditions
00009  *  are met:
00010  *
00011  *   * Redistributions of source code must retain the above copyright
00012  *     notice, this list of conditions and the following disclaimer.
00013  *   * Redistributions in binary form must reproduce the above
00014  *     copyright notice, this list of conditions and the following
00015  *     disclaimer in the documentation and/or other materials provided
00016  *     with the distribution.
00017  *   * Neither the name of the copyright holder nor the names of its
00018  *     contributors may be used to endorse or promote products derived
00019  *     from this software without specific prior written permission.
00020  *
00021  *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00022  *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00023  *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00024  *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00025  *  COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00026  *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00027  *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00028  *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00029  *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00030  *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00031  *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00032  *  POSSIBILITY OF SUCH DAMAGE.
00033  */
00034 #include <gtest/gtest.h>
00035 #include <nav_2d_utils/polygons.h>
00036 #include <vector>
00037 
00038 using nav_2d_utils::parseVVD;
00039 using nav_2d_msgs::Polygon2D;
00040 using nav_2d_utils::polygonFromString;
00041 using nav_2d_utils::polygonFromParallelArrays;
00042 
00043 TEST(array_parser, basic_operation)
00044 {
00045   std::vector<std::vector<double> > vvd;
00046   vvd = parseVVD("[[1, 2.2], [.3, -4e4]]");
00047   EXPECT_DOUBLE_EQ(2U, vvd.size());
00048   EXPECT_DOUBLE_EQ(2U, vvd[0].size());
00049   EXPECT_DOUBLE_EQ(2U, vvd[1].size());
00050   EXPECT_DOUBLE_EQ(1.0, vvd[0][0]);
00051   EXPECT_DOUBLE_EQ(2.2, vvd[0][1]);
00052   EXPECT_DOUBLE_EQ(0.3, vvd[1][0]);
00053   EXPECT_DOUBLE_EQ(-40000.0, vvd[1][1]);
00054 }
00055 
00056 TEST(array_parser, missing_open)
00057 {
00058   EXPECT_THROW(parseVVD("[1, 2.2], [.3, -4e4]]"), nav_2d_utils::PolygonParseException);
00059 }
00060 
00061 TEST(array_parser, missing_close)
00062 {
00063   EXPECT_THROW(parseVVD("[[1, 2.2], [.3, -4e4]"), nav_2d_utils::PolygonParseException);
00064 }
00065 
00066 TEST(array_parser, wrong_depth)
00067 {
00068   EXPECT_THROW(parseVVD("[1, 2.2], [.3, -4e4]"), nav_2d_utils::PolygonParseException);
00069 }
00070 
00071 TEST(Polygon2D, radius_param)
00072 {
00073   Polygon2D footprint = nav_2d_utils::polygonFromRadius(10.0);
00074   // Circular robot has 16-point footprint auto-generated.
00075   ASSERT_EQ(16U, footprint.points.size());
00076 
00077   // Check the first point
00078   EXPECT_EQ(10.0, footprint.points[0].x);
00079   EXPECT_EQ(0.0, footprint.points[0].y);
00080 
00081   // Check the 4th point, which should be 90 degrees around the circle from the first.
00082   EXPECT_NEAR(0.0, footprint.points[4].x, 0.0001);
00083   EXPECT_NEAR(10.0, footprint.points[4].y, 0.0001);
00084 }
00085 
00086 TEST(Polygon2D, string_param)
00087 {
00088   Polygon2D footprint = polygonFromString("[[1, 1], [-1, 1], [-1, -1]]");
00089   ASSERT_EQ(3U, footprint.points.size());
00090 
00091   EXPECT_EQ(1.0, footprint.points[ 0 ].x);
00092   EXPECT_EQ(1.0, footprint.points[ 0 ].y);
00093 
00094   EXPECT_EQ(-1.0, footprint.points[ 1 ].x);
00095   EXPECT_EQ(1.0, footprint.points[ 1 ].y);
00096 
00097   EXPECT_EQ(-1.0, footprint.points[ 2 ].x);
00098   EXPECT_EQ(-1.0, footprint.points[ 2 ].y);
00099 }
00100 
00101 TEST(Polygon2D, broken_string_param)
00102 {
00103   // Not enough points
00104   EXPECT_THROW(polygonFromString("[[1, 1], [-1, 1]]"), nav_2d_utils::PolygonParseException);
00105 
00106   // Too many numbers in point
00107   EXPECT_THROW(polygonFromString("[[1, 1, 1], [-1, 1], [-1, -1]]"), nav_2d_utils::PolygonParseException);
00108 
00109   // Unexpected character
00110   EXPECT_THROW(polygonFromString("[[x, 1], [-1, 1], [-1, -1]]"), nav_2d_utils::PolygonParseException);
00111 
00112   // Empty String
00113   EXPECT_THROW(polygonFromString(""), nav_2d_utils::PolygonParseException);
00114 
00115   // Empty List
00116   EXPECT_THROW(polygonFromString("[]"), nav_2d_utils::PolygonParseException);
00117 
00118   // Empty Point
00119   EXPECT_THROW(polygonFromString("[[]]"), nav_2d_utils::PolygonParseException);
00120 }
00121 
00122 TEST(Polygon2D, arrays)
00123 {
00124   std::vector<double> xs = {1, -1, -1};
00125   std::vector<double> ys = {1, 1, -1};
00126   Polygon2D footprint = polygonFromParallelArrays(xs, ys);
00127   ASSERT_EQ(3U, footprint.points.size());
00128 
00129   EXPECT_EQ(1.0, footprint.points[ 0 ].x);
00130   EXPECT_EQ(1.0, footprint.points[ 0 ].y);
00131 
00132   EXPECT_EQ(-1.0, footprint.points[ 1 ].x);
00133   EXPECT_EQ(1.0, footprint.points[ 1 ].y);
00134 
00135   EXPECT_EQ(-1.0, footprint.points[ 2 ].x);
00136   EXPECT_EQ(-1.0, footprint.points[ 2 ].y);
00137 }
00138 
00139 TEST(Polygon2D, broken_arrays)
00140 {
00141   std::vector<double> shorty = {1, -1};
00142   std::vector<double> three = {1, 1, -1};
00143   std::vector<double> four = {1, 1, -1, -1};
00144   EXPECT_THROW(polygonFromParallelArrays(shorty, shorty), nav_2d_utils::PolygonParseException);
00145   EXPECT_THROW(polygonFromParallelArrays(three, four), nav_2d_utils::PolygonParseException);
00146 }
00147 
00148 TEST(Polygon2D, test_move)
00149 {
00150   Polygon2D square = polygonFromString("[[0.5, 0.5], [0.5, -0.5], [-0.5, -0.5], [-0.5, 0.5]]");
00151   geometry_msgs::Pose2D pose;
00152   Polygon2D square2 = nav_2d_utils::movePolygonToPose(square, pose);
00153   EXPECT_TRUE(nav_2d_utils::equals(square, square2));
00154   pose.x = 15;
00155   pose.y = -10;
00156   pose.theta = M_PI / 4;
00157   Polygon2D diamond = nav_2d_utils::movePolygonToPose(square, pose);
00158   ASSERT_EQ(4U, diamond.points.size());
00159   double side = 1.0 / sqrt(2);
00160 
00161   EXPECT_DOUBLE_EQ(pose.x,        diamond.points[ 0 ].x);
00162   EXPECT_DOUBLE_EQ(pose.y + side, diamond.points[ 0 ].y);
00163   EXPECT_DOUBLE_EQ(pose.x + side, diamond.points[ 1 ].x);
00164   EXPECT_DOUBLE_EQ(pose.y,        diamond.points[ 1 ].y);
00165   EXPECT_DOUBLE_EQ(pose.x,        diamond.points[ 2 ].x);
00166   EXPECT_DOUBLE_EQ(pose.y - side, diamond.points[ 2 ].y);
00167   EXPECT_DOUBLE_EQ(pose.x - side, diamond.points[ 3 ].x);
00168   EXPECT_DOUBLE_EQ(pose.y,        diamond.points[ 3 ].y);
00169 }
00170 
00171 TEST(Polygon2D, inside)
00172 {
00173   Polygon2D square = polygonFromString("[[0.5, 0.5], [0.5, -0.5], [-0.5, -0.5], [-0.5, 0.5]]");
00174   EXPECT_TRUE(nav_2d_utils::isInside(square, 0.00, 0.00));
00175   EXPECT_TRUE(nav_2d_utils::isInside(square, 0.45, 0.45));
00176   EXPECT_FALSE(nav_2d_utils::isInside(square, 0.50, 0.50));
00177   EXPECT_FALSE(nav_2d_utils::isInside(square, 0.00, 0.50));
00178   EXPECT_FALSE(nav_2d_utils::isInside(square, 0.55, 0.55));
00179 }
00180 
00181 int main(int argc, char** argv)
00182 {
00183   testing::InitGoogleTest(&argc, argv);
00184   return RUN_ALL_TESTS();
00185 }


nav_2d_utils
Author(s):
autogenerated on Wed Jun 26 2019 20:09:36