costmap_to_polygons.h
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 
39 #ifndef COSTMAP_TO_POLYGONS_H_
40 #define COSTMAP_TO_POLYGONS_H_
41 
42 #include <ros/ros.h>
44 #include <nav_msgs/OccupancyGrid.h>
45 #include <visualization_msgs/Marker.h>
46 #include <geometry_msgs/Point.h>
47 #include <geometry_msgs/Polygon.h>
48 #include <vector>
49 #include <algorithm>
50 #include <Eigen/Core>
51 #include <Eigen/StdVector>
52 #include <boost/thread/mutex.hpp>
53 #include <boost/thread/thread.hpp>
54 
55 // dynamic reconfigure
56 #include <costmap_converter/CostmapToPolygonsDBSMCCHConfig.h>
57 #include <dynamic_reconfigure/server.h>
58 
59 
60 namespace costmap_converter
61 {
62 
80 {
81  public:
82 
87  struct KeyPoint
88  {
90  KeyPoint() {}
92  KeyPoint(double x_, double y_) : x(x_), y(y_) {}
93  double x;
94  double y;
95 
97  void toPointMsg(geometry_msgs::Point& point) const {point.x=x; point.y=y; point.z=0;}
99  void toPointMsg(geometry_msgs::Point32& point) const {point.x=x; point.y=y; point.z=0;}
100  };
101 
102 
107 
111  virtual ~CostmapToPolygonsDBSMCCH();
112 
117  virtual void initialize(ros::NodeHandle nh);
118 
122  virtual void compute();
123 
129  virtual void setCostmap2D(costmap_2d::Costmap2D* costmap);
130 
135  virtual void updateCostmap2D();
136 
137 
144  template< typename Point>
145  static void convertPointToPolygon(const Point& point, geometry_msgs::Polygon& polygon)
146  {
147  polygon.points.resize(1);
148  polygon.points.front().x = point.x;
149  polygon.points.front().y = point.y;
150  polygon.points.front().z = 0;
151  }
152 
159 
160 
161 
162  protected:
163 
176  void dbScan(const std::vector<KeyPoint>& occupied_cells, std::vector< std::vector<KeyPoint> >& clusters);
177 
185  void regionQuery(const std::vector<KeyPoint>& occupied_cells, int curr_index, std::vector<int>& neighbor_indices);
186 
187 
200  void convexHull(std::vector<KeyPoint>& cluster, geometry_msgs::Polygon& polygon);
201 
215  void convexHull2(std::vector<KeyPoint>& cluster, geometry_msgs::Polygon& polygon);
216 
226  template <typename P1, typename P2, typename P3>
227  long double cross(const P1& O, const P2& A, const P3& B)
228  {
229  return (long double)(A.x - O.x) * (long double)(B.y - O.y) - (long double)(A.y - O.y) * (long double)(B.x - O.x);
230  }
231 
232 
238 
239 
240  std::vector<KeyPoint> occupied_cells_;
241 
242  // DBSCAN parameters
243  double max_distance_;
244  int min_pts_;
245  int max_pts_;
246 
247  // convex hull parameters
249 
250  private:
251 
259  void reconfigureCB(CostmapToPolygonsDBSMCCHConfig& config, uint32_t level);
260 
261 
263  boost::mutex mutex_;
264 
265  dynamic_reconfigure::Server<CostmapToPolygonsDBSMCCHConfig>* dynamic_recfg_;
266 
268 
269 };
270 
271 
272 } //end namespace teb_local_planner
273 
274 #endif /* COSTMAP_TO_POLYGONS_H_ */
virtual void updateCostmap2D()
Get updated data from the previously set Costmap2D.
void reconfigureCB(CostmapToPolygonsDBSMCCHConfig &config, uint32_t level)
Callback for the dynamic_reconfigure node.
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...
void toPointMsg(geometry_msgs::Point32 &point) const
Convert keypoint to geometry_msgs::Point32 message type.
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)...
virtual void compute()
This method performs the actual work (conversion of the costmap to polygons)
virtual void setCostmap2D(costmap_2d::Costmap2D *costmap)
Pass a pointer to the costap to the plugin.
TFSIMD_FORCE_INLINE const tfScalar & x() const
costmap_2d::Costmap2D * costmap_
Pointer to the costmap2d.
This abstract class defines the interface for plugins that convert the costmap into polygon types...
TFSIMD_FORCE_INLINE const tfScalar & y() const
dynamic_reconfigure::Server< CostmapToPolygonsDBSMCCHConfig > * dynamic_recfg_
Dynamic reconfigure server to allow config modifications at runtime.
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)
PolygonContainerPtr polygons_
Current shared container of polygons.
KeyPoint(double x_, double y_)
Constructor with point initialization.
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.
boost::mutex mutex_
Mutex that keeps track about the ownership of the shared polygon instance.
void regionQuery(const std::vector< KeyPoint > &occupied_cells, int curr_index, std::vector< int > &neighbor_indices)
Helper function for dbScan to search for neighboring points.
Defines a keypoint in metric coordinates of the map.
void updatePolygonContainer(PolygonContainerPtr polygons)
Thread-safe update of the internal polygon container (that is shared using getPolygons() from outside...
void convexHull(std::vector< KeyPoint > &cluster, geometry_msgs::Polygon &polygon)
Compute the convex hull for a single cluster (monotone chain algorithm)
PolygonContainerConstPtr getPolygons()
Get a shared instance of the current polygon container.
void toPointMsg(geometry_msgs::Point &point) const
Convert keypoint to geometry_msgs::Point message type.
virtual void initialize(ros::NodeHandle nh)
Initialize the plugin.
long double cross(const P1 &O, const P2 &A, const P3 &B)
2D Cross product of two vectors defined by two points and a common origin


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