3 #include <gtest/gtest.h>
8 geometry_msgs::Point32 create_point(
double x,
double y)
10 geometry_msgs::Point32 result;
22 const std::vector<costmap_converter::CostmapToPolygonsDBSMCCH::KeyPoint>&
points()
const {
return occupied_cells_;}
44 std::random_device rand_dev;
45 std::mt19937 generator(rand_dev());
46 std::uniform_real_distribution<> random_angle(-M_PI, M_PI);
57 double alpha = random_angle(generator);
58 double dist = random_dist(generator);
59 double wx = center_x + std::cos(alpha) * dist;
60 double wy = center_y + std::sin(alpha) * dist;
73 double alpha = random_angle(generator);
74 double dist = random_dist(generator);
75 double wx = center_x + std::cos(alpha) * dist;
76 double wy = center_y + std::sin(alpha) * dist;
83 neighbor_indices.clear();
90 double dx = query_point.x - kp.x;
91 double dy = query_point.y - kp.y;
92 double dist = sqrt(dx*dx + dy*dy);
94 neighbor_indices.push_back(i);
99 std::shared_ptr<costmap_2d::Costmap2D>
costmap;
104 std::vector<int> neighbors, neighbors_trivial;
105 costmap_to_polygons.regionQuery(0, neighbors);
106 regionQueryTrivial(0, neighbors_trivial);
107 ASSERT_EQ(costmap_to_polygons.parameters().max_pts_ - 1,
int(neighbors.size()));
108 ASSERT_EQ(neighbors_trivial.size(), neighbors.size());
109 std::sort(neighbors.begin(), neighbors.end());
110 ASSERT_EQ(neighbors_trivial, neighbors);
112 costmap_to_polygons.regionQuery(1, neighbors);
113 regionQueryTrivial(1, neighbors_trivial);
114 ASSERT_EQ(costmap_to_polygons.parameters().max_pts_/2,
int(neighbors.size()));
115 ASSERT_EQ(neighbors_trivial.size(), neighbors.size());
116 std::sort(neighbors.begin(), neighbors.end());
117 ASSERT_EQ(neighbors_trivial, neighbors);
122 std::vector< std::vector<costmap_converter::CostmapToPolygonsDBSMCCH::KeyPoint> > clusters;
123 costmap_to_polygons.dbScan(clusters);
125 ASSERT_EQ(3, clusters.size());
126 ASSERT_EQ(2, clusters[0].size());
127 ASSERT_EQ(costmap_to_polygons.parameters().max_pts_, clusters[1].size());
128 ASSERT_EQ(costmap_to_polygons.parameters().max_pts_/2 + 1, clusters[2].size());
131 TEST(CostmapToPolygonsDBSMCCH, EmptyMap)
133 std::shared_ptr<costmap_2d::Costmap2D> costmap =
138 std::vector< std::vector<costmap_converter::CostmapToPolygonsDBSMCCH::KeyPoint> > clusters;
139 costmap_to_polygons.
dbScan(clusters);
140 ASSERT_EQ(1, clusters.size());
141 ASSERT_EQ(0, clusters[0].size());
144 TEST(CostmapToPolygonsDBSMCCH, SimplifyPolygon)
146 const double simplification_threshold = 0.1;
150 geometry_msgs::Polygon polygon;
151 polygon.points.push_back(create_point(0., 0.));
152 polygon.points.push_back(create_point(1., 0.));
155 geometry_msgs::Polygon original_polygon = polygon;
157 ASSERT_EQ(2, polygon.points.size());
158 for (
size_t i = 0; i < polygon.points.size(); ++i)
160 ASSERT_FLOAT_EQ(original_polygon.points[i].x, polygon.points[i].x);
161 ASSERT_FLOAT_EQ(original_polygon.points[i].y, polygon.points[i].y);
165 polygon.points.push_back(create_point(1., simplification_threshold / 2.));
166 original_polygon = polygon;
168 ASSERT_EQ(3, polygon.points.size());
169 for (
size_t i = 0; i < polygon.points.size(); ++i)
171 ASSERT_FLOAT_EQ(original_polygon.points[i].x, polygon.points[i].x);
172 ASSERT_FLOAT_EQ(original_polygon.points[i].y, polygon.points[i].y);
175 polygon.points.push_back(create_point(1., 1.));
176 original_polygon = polygon;
178 original_polygon.points.erase(original_polygon.points.begin()+2);
180 ASSERT_EQ(3, polygon.points.size());
181 for (
size_t i = 0; i < polygon.points.size(); ++i)
183 ASSERT_FLOAT_EQ(original_polygon.points[i].x, polygon.points[i].x);
184 ASSERT_FLOAT_EQ(original_polygon.points[i].y, polygon.points[i].y);
188 TEST(CostmapToPolygonsDBSMCCH, SimplifyPolygonPerfectLines)
190 const double simplification_threshold = 0.1;
194 geometry_msgs::Polygon polygon;
195 for (
int i = 0; i <= 100; ++i)
196 polygon.points.push_back(create_point(i*1., 0.));
197 geometry_msgs::Point32 lastPoint = polygon.points.back();
198 for (
int i = 0; i <= 100; ++i)
199 polygon.points.push_back(create_point(lastPoint.x, lastPoint.y + i * 1.));
200 lastPoint = polygon.points.back();
201 for (
int i = 0; i <= 100; ++i)
202 polygon.points.push_back(create_point(lastPoint.x + i * 1., lastPoint.y));
203 lastPoint = polygon.points.back();
204 for (
int i = 0; i <= 100; ++i)
205 polygon.points.push_back(create_point(lastPoint.x, lastPoint.y + i * 1.));
206 lastPoint = polygon.points.back();
207 for (
int i = 0; i <= 100; ++i)
208 polygon.points.push_back(create_point(lastPoint.x + i * 1., lastPoint.y));
211 ASSERT_EQ(6, polygon.points.size());
212 ASSERT_FLOAT_EQ( 0., polygon.points[0].x);
213 ASSERT_FLOAT_EQ( 0., polygon.points[0].y);
214 ASSERT_FLOAT_EQ(100., polygon.points[1].x);
215 ASSERT_FLOAT_EQ( 0., polygon.points[1].y);
216 ASSERT_FLOAT_EQ(100., polygon.points[2].x);
217 ASSERT_FLOAT_EQ(100., polygon.points[2].y);
218 ASSERT_FLOAT_EQ(200., polygon.points[3].x);
219 ASSERT_FLOAT_EQ(100., polygon.points[3].y);
220 ASSERT_FLOAT_EQ(200., polygon.points[4].x);
221 ASSERT_FLOAT_EQ(200., polygon.points[4].y);
222 ASSERT_FLOAT_EQ(300., polygon.points[5].x);
223 ASSERT_FLOAT_EQ(200., polygon.points[5].y);
226 int main(
int argc,
char** argv)
228 testing::InitGoogleTest(&argc, argv);
229 ros::init(argc, argv,
"CostmapConverterTester");
231 return RUN_ALL_TESTS();