4 #include "boost/foreach.hpp" 6 #include <gtest/gtest.h> 12 geometry_msgs::Point32 point;
13 point.x = -1; point.y = 1;
15 point.x = 1; point.y = 1;
17 point.x = -1; point.y = -1;
19 point.x = 1; point.y = -1;
26 geometry_msgs::Point point;
27 point.x = 0.5; point.y = 0;
29 point.x = -0.5; point.y = 0;
31 point.x = 0; point.y = 1.1;
33 point.x = 0; point.y = -1.1;
38 geometry_msgs::Point point;
39 point.x = 0; point.y = 0.5;
41 point.x = 0; point.y = 0.5;
45 TEST(PointsAdjacentTest, different)
47 geometry_msgs::Point a, b;
54 TEST(PointsAdjacentTest, identical)
56 geometry_msgs::Point a, b;
64 int main(
int argc,
char **argv){
65 testing::InitGoogleTest(&argc, argv);
66 return RUN_ALL_TESTS();
bool pointsNearby(const T &one, const S &two, const double &proximity)
Evaluate whether two points are approximately adjacent, within a specified proximity distance...
geometry_msgs::Polygon polygon_
bool pointInPolygon(const T &point, const geometry_msgs::Polygon &polygon)
Evaluate if point is inside area defined by polygon. Undefined behaviour for points on line...