costmap_polygons.cpp
Go to the documentation of this file.
1 #include <random>
2 #include <memory>
3 #include <gtest/gtest.h>
4 
6 
7 namespace {
8 geometry_msgs::Point32 create_point(double x, double y)
9 {
10  geometry_msgs::Point32 result;
11  result.x = x;
12  result.y = y;
13  result.z = 0.;
14  return result;
15 }
16 } // end namespace
17 
18 // make things accesible in the test
20 {
21  public:
22  const std::vector<costmap_converter::CostmapToPolygonsDBSMCCH::KeyPoint>& points() const {return occupied_cells_;}
29 };
30 
31 class CostmapToPolygonsDBSMCCHTest : public ::testing::Test
32 {
33  protected:
34  void SetUp() override {
35  // parameters
36  costmap_to_polygons.parameters().max_distance_ = 0.5;
37  costmap_to_polygons.parameters().max_pts_ = 100;
38  costmap_to_polygons.parameters().min_pts_ = 2;
39  costmap_to_polygons.parameters().min_keypoint_separation_ = 0.1;
40 
41  costmap.reset(new costmap_2d::Costmap2D(100, 100, 0.1, -5., -5.));
42  costmap_to_polygons.setCostmap2D(costmap.get());
43 
44  std::random_device rand_dev;
45  std::mt19937 generator(rand_dev());
46  std::uniform_real_distribution<> random_angle(-M_PI, M_PI);
47  std::uniform_real_distribution<> random_dist(0., costmap_to_polygons.parameters().max_distance_);
48 
49  costmap_to_polygons.addPoint(0., 0.);
50  costmap_to_polygons.addPoint(1.3, 1.3);
51 
52  // adding random points
53  double center_x = costmap_to_polygons.points()[0].x;
54  double center_y = costmap_to_polygons.points()[0].y;
55  for (int i = 0; i < costmap_to_polygons.parameters().max_pts_ - 1; ++i)
56  {
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;
61  costmap_to_polygons.addPoint(wx, wy);
62  }
63 
64  // some noisy points not belonging to a cluster
65  costmap_to_polygons.addPoint(-1, -1);
66  costmap_to_polygons.addPoint(-2, -2);
67 
68  // adding random points
69  center_x = costmap_to_polygons.points()[1].x;
70  center_y = costmap_to_polygons.points()[1].y;
71  for (int i = 0; i < costmap_to_polygons.parameters().max_pts_/2; ++i)
72  {
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;
77  costmap_to_polygons.addPoint(wx, wy);
78  }
79  }
80 
81  void regionQueryTrivial(int curr_index, std::vector<int>& neighbor_indices)
82  {
83  neighbor_indices.clear();
84  const auto& query_point = costmap_to_polygons.points()[curr_index];
85  for (int i = 0; i < int(costmap_to_polygons.points().size()); ++i)
86  {
87  if (i == curr_index)
88  continue;
89  const auto& kp = costmap_to_polygons.points()[i];
90  double dx = query_point.x - kp.x;
91  double dy = query_point.y - kp.y;
92  double dist = sqrt(dx*dx + dy*dy);
93  if (dist < costmap_to_polygons.parameters().max_distance_)
94  neighbor_indices.push_back(i);
95  }
96  }
97 
99  std::shared_ptr<costmap_2d::Costmap2D> costmap;
100 };
101 
103 {
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);
111 
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);
118 }
119 
121 {
122  std::vector< std::vector<costmap_converter::CostmapToPolygonsDBSMCCH::KeyPoint> > clusters;
123  costmap_to_polygons.dbScan(clusters);
124 
125  ASSERT_EQ(3, clusters.size());
126  ASSERT_EQ(2, clusters[0].size()); // noisy points not belonging to a cluster
127  ASSERT_EQ(costmap_to_polygons.parameters().max_pts_, clusters[1].size()); // first cluster at (0,0)
128  ASSERT_EQ(costmap_to_polygons.parameters().max_pts_/2 + 1, clusters[2].size()); // second cluster at (1,1)
129 }
130 
132 {
133  std::shared_ptr<costmap_2d::Costmap2D> costmap =
134  std::make_shared<costmap_2d::Costmap2D>(costmap_2d::Costmap2D(100, 100, 0.1, -5., -5.));
135  CostmapToPolygons costmap_to_polygons;
136  costmap_to_polygons.setCostmap2D(costmap.get());
137 
138  std::vector< std::vector<costmap_converter::CostmapToPolygonsDBSMCCH::KeyPoint> > clusters;
139  costmap_to_polygons.dbScan(clusters);
140  ASSERT_EQ(1, clusters.size()); // noise cluster exists
141  ASSERT_EQ(0, clusters[0].size()); // noise clsuter is empty
142 }
143 
145 {
146  const double simplification_threshold = 0.1;
147  CostmapToPolygons costmap_to_polygons;
148  costmap_to_polygons.parameters().min_keypoint_separation_ = simplification_threshold;
149 
150  geometry_msgs::Polygon polygon;
151  polygon.points.push_back(create_point(0., 0.));
152  polygon.points.push_back(create_point(1., 0.));
153 
154  // degenerate case with just two points
155  geometry_msgs::Polygon original_polygon = polygon;
156  costmap_to_polygons.simplifyPolygon(polygon);
157  ASSERT_EQ(2, polygon.points.size());
158  for (size_t i = 0; i < polygon.points.size(); ++i)
159  {
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);
162  }
163 
164  // degenerate case with three points
165  polygon.points.push_back(create_point(1., simplification_threshold / 2.));
166  original_polygon = polygon;
167  costmap_to_polygons.simplifyPolygon(polygon);
168  ASSERT_EQ(3, polygon.points.size());
169  for (size_t i = 0; i < polygon.points.size(); ++i)
170  {
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);
173  }
174 
175  polygon.points.push_back(create_point(1., 1.));
176  original_polygon = polygon;
177  // remove the point that has to be removed by the simplification
178  original_polygon.points.erase(original_polygon.points.begin()+2);
179  costmap_to_polygons.simplifyPolygon(polygon);
180  ASSERT_EQ(3, polygon.points.size());
181  for (size_t i = 0; i < polygon.points.size(); ++i)
182  {
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);
185  }
186 }
187 
188 TEST(CostmapToPolygonsDBSMCCH, SimplifyPolygonPerfectLines)
189 {
190  const double simplification_threshold = 0.1;
191  CostmapToPolygons costmap_to_polygons;
192  costmap_to_polygons.parameters().min_keypoint_separation_ = simplification_threshold;
193 
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));
209 
210  costmap_to_polygons.simplifyPolygon(polygon);
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);
224 }
225 
226 int main(int argc, char** argv)
227 {
228  testing::InitGoogleTest(&argc, argv);
229  ros::init(argc, argv, "CostmapConverterTester");
230  ros::NodeHandle nh;
231  return RUN_ALL_TESTS();
232 }
const std::vector< costmap_converter::CostmapToPolygonsDBSMCCH::KeyPoint > & points() const
std::vector< KeyPoint > occupied_cells_
List of occupied cells in the current map (updated by updateCostmap2D())
double min_keypoint_separation_
Clear keypoints of the convex polygon that are close to each other [distance in meters] (0: keep all)...
TEST_F(CostmapToPolygonsDBSMCCHTest, regionQuery)
void dbScan(std::vector< std::vector< KeyPoint > > &clusters)
DBSCAN algorithm for clustering.
void simplifyPolygon(geometry_msgs::Polygon &polygon)
Simplify a polygon by removing points.
void addPoint(double x, double y)
helper function for adding a point to the lookup data structures
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
virtual void setCostmap2D(costmap_2d::Costmap2D *costmap)
Pass a pointer to the costap to the plugin.
void regionQueryTrivial(int curr_index, std::vector< int > &neighbor_indices)
costmap_converter::CostmapToPolygonsDBSMCCH::Parameters & parameters()
TEST(CostmapToPolygonsDBSMCCH, EmptyMap)
int main(int argc, char **argv)
This class converts the costmap_2d into a set of convex polygons (and points)
void regionQuery(int curr_index, std::vector< int > &neighbor_indices)
Helper function for dbScan to search for neighboring points.
CostmapToPolygons costmap_to_polygons
void convexHull2(std::vector< KeyPoint > &cluster, geometry_msgs::Polygon &polygon)
Compute the convex hull for a single cluster.
std::shared_ptr< costmap_2d::Costmap2D > costmap


costmap_converter
Author(s): Christoph Rösmann , Franz Albers , Otniel Rinaldo
autogenerated on Sat May 16 2020 03:19:18