39 #include <gtest/gtest.h> 44 using nav_2d_msgs::Polygon2D;
46 TEST(Polygon2D, unpadded_footprint_from_string_param)
50 ASSERT_EQ(3U, footprint.points.size());
52 EXPECT_EQ(1.0
f, footprint.points[ 0 ].x);
53 EXPECT_EQ(1.0
f, footprint.points[ 0 ].y);
55 EXPECT_EQ(-1.0
f, footprint.points[ 1 ].x);
56 EXPECT_EQ(1.0
f, footprint.points[ 1 ].y);
58 EXPECT_EQ(-1.0
f, footprint.points[ 2 ].x);
59 EXPECT_EQ(-1.0
f, footprint.points[ 2 ].y);
62 TEST(Polygon2D, check_search_capabilities)
66 ASSERT_EQ(3U, footprint.points.size());
70 TEST(Polygon2D, footprint_from_xmlrpc_param)
74 ASSERT_EQ(4U, footprint.points.size());
76 EXPECT_FLOAT_EQ(0.1
f, footprint.points[ 0 ].x);
77 EXPECT_FLOAT_EQ(0.1
f, footprint.points[ 0 ].y);
79 EXPECT_FLOAT_EQ(-0.1
f, footprint.points[ 1 ].x);
80 EXPECT_FLOAT_EQ(0.1
f, footprint.points[ 1 ].y);
82 EXPECT_FLOAT_EQ(-0.1
f, footprint.points[ 2 ].x);
83 EXPECT_FLOAT_EQ(-0.1
f, footprint.points[ 2 ].y);
85 EXPECT_FLOAT_EQ(0.1
f, footprint.points[ 3 ].x);
86 EXPECT_FLOAT_EQ(-0.1
f, footprint.points[ 3 ].y);
92 TEST(Polygon2D, footprint_from_same_level_param)
96 ASSERT_EQ(3U, footprint.points.size());
98 EXPECT_EQ(1.0
f, footprint.points[ 0 ].x);
99 EXPECT_EQ(2.0
f, footprint.points[ 0 ].y);
101 EXPECT_EQ(3.0
f, footprint.points[ 1 ].x);
102 EXPECT_EQ(4.0
f, footprint.points[ 1 ].y);
104 EXPECT_EQ(5.0
f, footprint.points[ 2 ].x);
105 EXPECT_EQ(6.0
f, footprint.points[ 2 ].y);
108 TEST(Polygon2D, footprint_from_xmlrpc_param_failure)
122 TEST(Polygon2D, footprint_empty)
141 int main(
int argc,
char** argv)
144 testing::InitGoogleTest(&argc, argv);
145 return RUN_ALL_TESTS();
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.
bool equals(const nav_2d_msgs::Polygon2D &polygon0, const nav_2d_msgs::Polygon2D &polygon1)
check if two polygons are equal. Used in testing
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
Exception to throw when Polygon doesn't load correctly.
TEST(Polygon2D, unpadded_footprint_from_string_param)
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.