param_tests.cpp
Go to the documentation of this file.
00001 /*********************************************************************
00002 *
00003 * Software License Agreement (BSD License)
00004 *
00005 *  Copyright (c) 2009, Willow Garage, Inc.
00006 *                2018, Locus Robotics
00007 *  All rights reserved.
00008 *
00009 *  Redistribution and use in source and binary forms, with or without
00010 *  modification, are permitted provided that the following conditions
00011 *  are met:
00012 *
00013 *   * Redistributions of source code must retain the above copyright
00014 *     notice, this list of conditions and the following disclaimer.
00015 *   * Redistributions in binary form must reproduce the above
00016 *     copyright notice, this list of conditions and the following
00017 *     disclaimer in the documentation and/or other materials provided
00018 *     with the distribution.
00019 *   * Neither the name of Willow Garage, Inc. nor the names of its
00020 *     contributors may be used to endorse or promote products derived
00021 *     from this software without specific prior written permission.
00022 *
00023 *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00024 *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00025 *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00026 *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00027 *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00028 *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00029 *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00030 *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00031 *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00032 *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00033 *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00034 *  POSSIBILITY OF SUCH DAMAGE.
00035 *
00036 * Author: Dave Hershberger
00037 *         David V. Lu!! (nav_2d_utils version)
00038 *********************************************************************/
00039 #include <gtest/gtest.h>
00040 #include <ros/ros.h>
00041 #include <nav_2d_utils/polygons.h>
00042 
00043 using nav_2d_utils::polygonFromParams;
00044 using nav_2d_msgs::Polygon2D;
00045 
00046 TEST(Polygon2D, unpadded_footprint_from_string_param)
00047 {
00048   ros::NodeHandle nh("~unpadded");
00049   Polygon2D footprint = polygonFromParams(nh, "footprint");
00050   ASSERT_EQ(3U, footprint.points.size());
00051 
00052   EXPECT_EQ(1.0f, footprint.points[ 0 ].x);
00053   EXPECT_EQ(1.0f, footprint.points[ 0 ].y);
00054 
00055   EXPECT_EQ(-1.0f, footprint.points[ 1 ].x);
00056   EXPECT_EQ(1.0f, footprint.points[ 1 ].y);
00057 
00058   EXPECT_EQ(-1.0f, footprint.points[ 2 ].x);
00059   EXPECT_EQ(-1.0f, footprint.points[ 2 ].y);
00060 }
00061 
00062 TEST(Polygon2D, check_search_capabilities)
00063 {
00064   ros::NodeHandle nh("~unpadded/unneccessarily/long_namespace");
00065   Polygon2D footprint = polygonFromParams(nh, "footprint");
00066   ASSERT_EQ(3U, footprint.points.size());
00067   EXPECT_THROW(polygonFromParams(nh, "footprint", false), nav_2d_utils::PolygonParseException);
00068 }
00069 
00070 TEST(Polygon2D, footprint_from_xmlrpc_param)
00071 {
00072   ros::NodeHandle nh("~xmlrpc");
00073   Polygon2D footprint = polygonFromParams(nh, "footprint");
00074   ASSERT_EQ(4U, footprint.points.size());
00075 
00076   EXPECT_FLOAT_EQ(0.1f, footprint.points[ 0 ].x);
00077   EXPECT_FLOAT_EQ(0.1f, footprint.points[ 0 ].y);
00078 
00079   EXPECT_FLOAT_EQ(-0.1f, footprint.points[ 1 ].x);
00080   EXPECT_FLOAT_EQ(0.1f, footprint.points[ 1 ].y);
00081 
00082   EXPECT_FLOAT_EQ(-0.1f, footprint.points[ 2 ].x);
00083   EXPECT_FLOAT_EQ(-0.1f, footprint.points[ 2 ].y);
00084 
00085   EXPECT_FLOAT_EQ(0.1f, footprint.points[ 3 ].x);
00086   EXPECT_FLOAT_EQ(-0.1f, footprint.points[ 3 ].y);
00087 
00088   Polygon2D footprint2 = polygonFromParams(nh, "footprint2");
00089   ASSERT_TRUE(nav_2d_utils::equals(footprint, footprint2));
00090 }
00091 
00092 TEST(Polygon2D, footprint_from_same_level_param)
00093 {
00094   ros::NodeHandle nh("~same_level");
00095   Polygon2D footprint = polygonFromParams(nh, "footprint");
00096   ASSERT_EQ(3U, footprint.points.size());
00097 
00098   EXPECT_EQ(1.0f, footprint.points[ 0 ].x);
00099   EXPECT_EQ(2.0f, footprint.points[ 0 ].y);
00100 
00101   EXPECT_EQ(3.0f, footprint.points[ 1 ].x);
00102   EXPECT_EQ(4.0f, footprint.points[ 1 ].y);
00103 
00104   EXPECT_EQ(5.0f, footprint.points[ 2 ].x);
00105   EXPECT_EQ(6.0f, footprint.points[ 2 ].y);
00106 }
00107 
00108 TEST(Polygon2D, footprint_from_xmlrpc_param_failure)
00109 {
00110   ros::NodeHandle nh("~xmlrpc_fail");
00111   EXPECT_THROW(polygonFromParams(nh, "footprint"), nav_2d_utils::PolygonParseException);
00112   EXPECT_THROW(polygonFromParams(nh, "footprint2"), nav_2d_utils::PolygonParseException);
00113   EXPECT_THROW(polygonFromParams(nh, "footprint3"), nav_2d_utils::PolygonParseException);
00114   EXPECT_THROW(polygonFromParams(nh, "footprint4"), nav_2d_utils::PolygonParseException);
00115   EXPECT_THROW(polygonFromParams(nh, "footprint5"), nav_2d_utils::PolygonParseException);
00116   EXPECT_THROW(polygonFromParams(nh, "footprint6"), nav_2d_utils::PolygonParseException);
00117   EXPECT_THROW(polygonFromParams(nh, "footprint7"), nav_2d_utils::PolygonParseException);
00118   EXPECT_THROW(polygonFromParams(nh, "footprint8"), nav_2d_utils::PolygonParseException);
00119   EXPECT_THROW(polygonFromParams(nh, "footprint9"), nav_2d_utils::PolygonParseException);
00120 }
00121 
00122 TEST(Polygon2D, footprint_empty)
00123 {
00124   ros::NodeHandle nh("~empty");
00125   EXPECT_THROW(polygonFromParams(nh, "footprint"), nav_2d_utils::PolygonParseException);
00126 }
00127 
00128 TEST(Polygon2D, test_write)
00129 {
00130   ros::NodeHandle nh("~unpadded");
00131   Polygon2D footprint = polygonFromParams(nh, "footprint");
00132   nh.setParam("another_footprint", nav_2d_utils::polygonToXMLRPC(footprint));
00133   Polygon2D another_footprint = polygonFromParams(nh, "another_footprint");
00134   EXPECT_TRUE(nav_2d_utils::equals(footprint, another_footprint));
00135 
00136   nh.setParam("third_footprint", nav_2d_utils::polygonToXMLRPC(footprint, false));
00137   another_footprint = polygonFromParams(nh, "third_footprint");
00138   EXPECT_TRUE(nav_2d_utils::equals(footprint, another_footprint));
00139 }
00140 
00141 int main(int argc, char** argv)
00142 {
00143   ros::init(argc, argv, "param_tests");
00144   testing::InitGoogleTest(&argc, argv);
00145   return RUN_ALL_TESTS();
00146 }


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