param_tests.cpp
Go to the documentation of this file.
1 /*********************************************************************
2 *
3 * Software License Agreement (BSD License)
4 *
5 * Copyright (c) 2009, Willow Garage, Inc.
6 * 2018, Locus Robotics
7 * All rights reserved.
8 *
9 * Redistribution and use in source and binary forms, with or without
10 * modification, are permitted provided that the following conditions
11 * are met:
12 *
13 * * Redistributions of source code must retain the above copyright
14 * notice, this list of conditions and the following disclaimer.
15 * * Redistributions in binary form must reproduce the above
16 * copyright notice, this list of conditions and the following
17 * disclaimer in the documentation and/or other materials provided
18 * with the distribution.
19 * * Neither the name of Willow Garage, Inc. nor the names of its
20 * contributors may be used to endorse or promote products derived
21 * from this software without specific prior written permission.
22 *
23 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
24 * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
25 * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
26 * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
27 * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
28 * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
29 * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
30 * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
31 * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
32 * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
33 * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
34 * POSSIBILITY OF SUCH DAMAGE.
35 *
36 * Author: Dave Hershberger
37 * David V. Lu!! (nav_2d_utils version)
38 *********************************************************************/
39 #include <gtest/gtest.h>
40 #include <ros/ros.h>
41 #include <nav_2d_utils/polygons.h>
42 
44 using nav_2d_msgs::Polygon2D;
45 
46 TEST(Polygon2D, unpadded_footprint_from_string_param)
47 {
48  ros::NodeHandle nh("~unpadded");
49  Polygon2D footprint = polygonFromParams(nh, "footprint");
50  ASSERT_EQ(3U, footprint.points.size());
51 
52  EXPECT_EQ(1.0f, footprint.points[ 0 ].x);
53  EXPECT_EQ(1.0f, footprint.points[ 0 ].y);
54 
55  EXPECT_EQ(-1.0f, footprint.points[ 1 ].x);
56  EXPECT_EQ(1.0f, footprint.points[ 1 ].y);
57 
58  EXPECT_EQ(-1.0f, footprint.points[ 2 ].x);
59  EXPECT_EQ(-1.0f, footprint.points[ 2 ].y);
60 }
61 
62 TEST(Polygon2D, check_search_capabilities)
63 {
64  ros::NodeHandle nh("~unpadded/unneccessarily/long_namespace");
65  Polygon2D footprint = polygonFromParams(nh, "footprint");
66  ASSERT_EQ(3U, footprint.points.size());
67  EXPECT_THROW(polygonFromParams(nh, "footprint", false), nav_2d_utils::PolygonParseException);
68 }
69 
70 TEST(Polygon2D, footprint_from_xmlrpc_param)
71 {
72  ros::NodeHandle nh("~xmlrpc");
73  Polygon2D footprint = polygonFromParams(nh, "footprint");
74  ASSERT_EQ(4U, footprint.points.size());
75 
76  EXPECT_FLOAT_EQ(0.1f, footprint.points[ 0 ].x);
77  EXPECT_FLOAT_EQ(0.1f, footprint.points[ 0 ].y);
78 
79  EXPECT_FLOAT_EQ(-0.1f, footprint.points[ 1 ].x);
80  EXPECT_FLOAT_EQ(0.1f, footprint.points[ 1 ].y);
81 
82  EXPECT_FLOAT_EQ(-0.1f, footprint.points[ 2 ].x);
83  EXPECT_FLOAT_EQ(-0.1f, footprint.points[ 2 ].y);
84 
85  EXPECT_FLOAT_EQ(0.1f, footprint.points[ 3 ].x);
86  EXPECT_FLOAT_EQ(-0.1f, footprint.points[ 3 ].y);
87 
88  Polygon2D footprint2 = polygonFromParams(nh, "footprint2");
89  ASSERT_TRUE(nav_2d_utils::equals(footprint, footprint2));
90 }
91 
92 TEST(Polygon2D, footprint_from_same_level_param)
93 {
94  ros::NodeHandle nh("~same_level");
95  Polygon2D footprint = polygonFromParams(nh, "footprint");
96  ASSERT_EQ(3U, footprint.points.size());
97 
98  EXPECT_EQ(1.0f, footprint.points[ 0 ].x);
99  EXPECT_EQ(2.0f, footprint.points[ 0 ].y);
100 
101  EXPECT_EQ(3.0f, footprint.points[ 1 ].x);
102  EXPECT_EQ(4.0f, footprint.points[ 1 ].y);
103 
104  EXPECT_EQ(5.0f, footprint.points[ 2 ].x);
105  EXPECT_EQ(6.0f, footprint.points[ 2 ].y);
106 }
107 
108 TEST(Polygon2D, footprint_from_xmlrpc_param_failure)
109 {
110  ros::NodeHandle nh("~xmlrpc_fail");
111  EXPECT_THROW(polygonFromParams(nh, "footprint"), nav_2d_utils::PolygonParseException);
112  EXPECT_THROW(polygonFromParams(nh, "footprint2"), nav_2d_utils::PolygonParseException);
113  EXPECT_THROW(polygonFromParams(nh, "footprint3"), nav_2d_utils::PolygonParseException);
114  EXPECT_THROW(polygonFromParams(nh, "footprint4"), nav_2d_utils::PolygonParseException);
115  EXPECT_THROW(polygonFromParams(nh, "footprint5"), nav_2d_utils::PolygonParseException);
116  EXPECT_THROW(polygonFromParams(nh, "footprint6"), nav_2d_utils::PolygonParseException);
117  EXPECT_THROW(polygonFromParams(nh, "footprint7"), nav_2d_utils::PolygonParseException);
118  EXPECT_THROW(polygonFromParams(nh, "footprint8"), nav_2d_utils::PolygonParseException);
119  EXPECT_THROW(polygonFromParams(nh, "footprint9"), nav_2d_utils::PolygonParseException);
120 }
121 
122 TEST(Polygon2D, footprint_empty)
123 {
124  ros::NodeHandle nh("~empty");
125  EXPECT_THROW(polygonFromParams(nh, "footprint"), nav_2d_utils::PolygonParseException);
126 }
127 
128 TEST(Polygon2D, test_write)
129 {
130  ros::NodeHandle nh("~unpadded");
131  Polygon2D footprint = polygonFromParams(nh, "footprint");
132  nh.setParam("another_footprint", nav_2d_utils::polygonToXMLRPC(footprint));
133  Polygon2D another_footprint = polygonFromParams(nh, "another_footprint");
134  EXPECT_TRUE(nav_2d_utils::equals(footprint, another_footprint));
135 
136  nh.setParam("third_footprint", nav_2d_utils::polygonToXMLRPC(footprint, false));
137  another_footprint = polygonFromParams(nh, "third_footprint");
138  EXPECT_TRUE(nav_2d_utils::equals(footprint, another_footprint));
139 }
140 
141 int main(int argc, char** argv)
142 {
143  ros::init(argc, argv, "param_tests");
144  testing::InitGoogleTest(&argc, argv);
145  return RUN_ALL_TESTS();
146 }
f
nav_2d_msgs::Polygon2D polygonFromParams(const ros::NodeHandle &nh, const std::string parameter_name, bool search=true)
Load a polygon from a parameter, whether it is a string or array, or two arrays.
Definition: polygons.cpp:249
bool equals(const nav_2d_msgs::Polygon2D &polygon0, const nav_2d_msgs::Polygon2D &polygon1)
check if two polygons are equal. Used in testing
Definition: polygons.cpp:349
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
Exception to throw when Polygon doesn&#39;t load correctly.
Definition: polygons.h:51
TEST(Polygon2D, unpadded_footprint_from_string_param)
Definition: param_tests.cpp:46
int main(int argc, char **argv)
void setParam(const std::string &key, const XmlRpc::XmlRpcValue &v) const
XmlRpc::XmlRpcValue polygonToXMLRPC(const nav_2d_msgs::Polygon2D &polygon, bool array_of_arrays=true)
Create XMLRPC Value for writing the polygon to the parameter server.
Definition: polygons.cpp:286


nav_2d_utils
Author(s):
autogenerated on Wed Jun 26 2019 20:06:11