costmap_to_polygons_concave.cpp
Go to the documentation of this file.
1 /*********************************************************************
2  *
3  * Software License Agreement (BSD License)
4  *
5  * Copyright (c) 2016,
6  * TU Dortmund - Institute of Control Theory and Systems Engineering.
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 the institute 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: Christoph Rösmann, Otniel Rinaldo
37  *********************************************************************/
38 
40 
42 
44 
45 namespace costmap_converter
46 {
47 
48 CostmapToPolygonsDBSConcaveHull::CostmapToPolygonsDBSConcaveHull() : CostmapToPolygonsDBSMCCH()
49 {
50  dynamic_recfg_ = NULL;
51 }
52 
54 {
55  if (dynamic_recfg_ != NULL)
56  delete dynamic_recfg_;
57 }
58 
60 {
61  max_distance_ = 0.4;
62  nh.param("cluster_max_distance", max_distance_, max_distance_);
63 
64  min_pts_ = 2;
65  nh.param("cluster_min_pts", min_pts_, min_pts_);
66 
67  max_pts_ = 30;
68  nh.param("cluster_max_pts", max_pts_, max_pts_);
69 
71  nh.param("convex_hull_min_pt_separation", min_keypoint_separation_, min_keypoint_separation_);
72 
73  concave_hull_depth_ = 2.0;
74  nh.param("concave_hull_depth", concave_hull_depth_, concave_hull_depth_);
75 
76  // setup dynamic reconfigure
77  dynamic_recfg_ = new dynamic_reconfigure::Server<CostmapToPolygonsDBSConcaveHullConfig>(nh);
78  dynamic_reconfigure::Server<CostmapToPolygonsDBSConcaveHullConfig>::CallbackType cb = boost::bind(&CostmapToPolygonsDBSConcaveHull::reconfigureCB, this, _1, _2);
79  dynamic_recfg_->setCallback(cb);
80 }
81 
82 
84 {
85  std::vector< std::vector<KeyPoint> > clusters;
86  dbScan(occupied_cells_, clusters);
87 
88  // Create new polygon container
89  PolygonContainerPtr polygons(new std::vector<geometry_msgs::Polygon>());
90 
91 
92  // add convex hulls to polygon container
93  for (int i = 1; i <clusters.size(); ++i) // skip first cluster, since it is just noise
94  {
95  polygons->push_back( geometry_msgs::Polygon() );
96  concaveHull(clusters[i], concave_hull_depth_, polygons->back() );
97  }
98 
99  // add our non-cluster points to the polygon container (as single points)
100  if (!clusters.empty())
101  {
102  for (int i=0; i < clusters.front().size(); ++i)
103  {
104  polygons->push_back( geometry_msgs::Polygon() );
105  convertPointToPolygon(clusters.front()[i], polygons->back());
106  }
107  }
108 
109  // replace shared polygon container
110  updatePolygonContainer(polygons);
111 }
112 
113 
114 void CostmapToPolygonsDBSConcaveHull::concaveHull(std::vector<KeyPoint>& cluster, double depth, geometry_msgs::Polygon& polygon)
115 {
116  // start with convex hull
117  convexHull2(cluster, polygon);
118 
119  std::vector<geometry_msgs::Point32>& concave_list = polygon.points;
120 
121  for (int i = 0; i < (int)concave_list.size() - 1; ++i)
122  {
123 
124  // find nearest inner point pk from line (vertex1 -> vertex2)
125  const geometry_msgs::Point32& vertex1 = concave_list[i];
126  const geometry_msgs::Point32& vertex2 = concave_list[i+1];
127 
128  bool found;
129  size_t nearest_idx = findNearestInnerPoint(vertex1, vertex2, cluster, concave_list, &found);
130  if (!found)
131  continue;
132 
133  double line_length = norm2d(vertex1, vertex2);
134 
135  double dst1 = norm2d(cluster[nearest_idx], vertex1);
136  double dst2 = norm2d(cluster[nearest_idx], vertex2);
137  double dd = std::min(dst1, dst2);
138  if (dd<1e-8)
139  continue;
140 
141  if (line_length / dd > depth)
142  {
143  // Check that new candidate edge will not intersect existing edges.
144  bool intersects = checkLineIntersection(concave_list, vertex1, vertex2, vertex1, cluster[nearest_idx]);
145  intersects |= checkLineIntersection(concave_list, vertex1, vertex2, cluster[nearest_idx], vertex2);
146  if (!intersects)
147  {
148  geometry_msgs::Point32 new_point;
149  cluster[nearest_idx].toPointMsg(new_point);
150  concave_list.insert(concave_list.begin() + i + 1, new_point);
151  i--;
152  }
153  }
154  }
155 }
156 
157 
158 void CostmapToPolygonsDBSConcaveHull::concaveHullClusterCut(std::vector<KeyPoint>& cluster, double depth, geometry_msgs::Polygon& polygon)
159 {
160  // start with convex hull
161  convexHull2(cluster, polygon);
162 
163  std::vector<geometry_msgs::Point32>& concave_list = polygon.points;
164 
165  // get line length
166  double mean_length = 0;
167  for (int i = 0; i < (int)concave_list.size() - 1; ++i)
168  {
169  mean_length += norm2d(concave_list[i],concave_list[i+1]);
170  }
171  mean_length /= double(concave_list.size());
172 
173  for (int i = 0; i < (int)concave_list.size() - 1; ++i)
174  {
175 
176  // find nearest inner point pk from line (vertex1 -> vertex2)
177  const geometry_msgs::Point32& vertex1 = concave_list[i];
178  const geometry_msgs::Point32& vertex2 = concave_list[i+1];
179 
180  double line_length = norm2d(vertex1, vertex2);
181 
182  bool found;
183  size_t nearest_idx = findNearestInnerPoint(vertex1, vertex2, cluster, concave_list, &found);
184  if (!found)
185  {
186  continue;
187  }
188 
189 
190  double dst1 = norm2d(cluster[nearest_idx], vertex1);
191  double dst2 = norm2d(cluster[nearest_idx], vertex2);
192  double dd = std::min(dst1, dst2);
193  if (dd<1e-8)
194  continue;
195 
196  if (line_length / dd > depth)
197  {
198  // Check that new candidate edge will not intersect existing edges.
199  bool intersects = checkLineIntersection(concave_list, vertex1, vertex2, vertex1, cluster[nearest_idx]);
200  intersects |= checkLineIntersection(concave_list, vertex1, vertex2, cluster[nearest_idx], vertex2);
201  if (!intersects)
202  {
203  geometry_msgs::Point32 new_point;
204  cluster[nearest_idx].toPointMsg(new_point);
205  concave_list.insert(concave_list.begin() + i + 1, new_point);
206  i--;
207  }
208  }
209  }
210 }
211 
212 
213 
214 
215 void CostmapToPolygonsDBSConcaveHull::reconfigureCB(CostmapToPolygonsDBSConcaveHullConfig& config, uint32_t level)
216 {
217  max_distance_ = config.cluster_max_distance;
218  min_pts_ = config.cluster_min_pts;
219  max_pts_ = config.cluster_max_pts;
220  min_keypoint_separation_ = config.cluster_min_pts;
221  concave_hull_depth_ = config.concave_hull_depth;
222 }
223 
224 }//end namespace costmap_converter
225 
226 
bool intersects(std::vector< geometry_msgs::Point > &polygon, float testx, float testy)
std::vector< KeyPoint > occupied_cells_
List of occupied cells in the current map (updated by updateCostmap2D())
int max_pts_
Parameter for DB_Scan: maximum number of points that define a cluster (to avoid large L- and U-shapes...
double norm2d(const Point1 &pt1, const Point2 &pt2)
Calculate the distance between two 2d points.
Definition: misc.h:117
virtual void initialize(ros::NodeHandle nh)
Initialize the plugin.
void concaveHullClusterCut(std::vector< KeyPoint > &cluster, double depth, geometry_msgs::Polygon &polygon)
static void convertPointToPolygon(const Point &point, geometry_msgs::Polygon &polygon)
Convert a generi point type to a geometry_msgs::Polygon.
double max_distance_
Parameter for DB_Scan, maximum distance to neighbors [m].
double min_keypoint_separation_
Clear keypoints of the convex polygon that are close to each other [distance in meters] (0: keep all)...
PLUGINLIB_EXPORT_CLASS(BAGReader, nodelet::Nodelet)
This class converts the costmap_2d into a set of non-convex polygons (and points) ...
bool checkLineIntersection(const Point1 &line1_start, const Point2 &line1_end, const Point3 &line2_start, const Point4 &line2_end)
virtual void compute()
This method performs the actual work (conversion of the costmap to polygons)
void reconfigureCB(CostmapToPolygonsDBSConcaveHullConfig &config, uint32_t level)
Callback for the dynamic_reconfigure node.
dynamic_reconfigure::Server< CostmapToPolygonsDBSConcaveHullConfig > * dynamic_recfg_
Dynamic reconfigure server to allow config modifications at runtime.
std::size_t findNearestInnerPoint(PointLine line_start, PointLine line_end, const std::vector< PointCluster > &cluster, const std::vector< PointHull > &hull, bool *found)
bool param(const std::string &param_name, T &param_val, const T &default_val) const
This abstract class defines the interface for plugins that convert the costmap into polygon types...
void concaveHull(std::vector< KeyPoint > &cluster, double depth, geometry_msgs::Polygon &polygon)
Compute the concave hull for a single cluster.
int min_pts_
Parameter for DB_Scan: minimum number of points that define a cluster.
This class converts the costmap_2d into a set of convex polygons (and points)
void dbScan(const std::vector< KeyPoint > &occupied_cells, std::vector< std::vector< KeyPoint > > &clusters)
DBSCAN algorithm for clustering.
void convexHull2(std::vector< KeyPoint > &cluster, geometry_msgs::Polygon &polygon)
Compute the convex hull for a single cluster.
void updatePolygonContainer(PolygonContainerPtr polygons)
Thread-safe update of the internal polygon container (that is shared using getPolygons() from outside...


costmap_converter
Author(s): Christoph Rösmann , Franz Albers , Otniel Rinaldo
autogenerated on Fri Jun 7 2019 21:48:43