39 #ifndef COSTMAP_TO_POLYGONS_H_ 40 #define COSTMAP_TO_POLYGONS_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> 51 #include <Eigen/StdVector> 52 #include <boost/thread/mutex.hpp> 53 #include <boost/thread/thread.hpp> 56 #include <costmap_converter/CostmapToPolygonsDBSMCCHConfig.h> 57 #include <dynamic_reconfigure/server.h> 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;}
144 template<
typename Po
int>
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;
176 void dbScan(
const std::vector<KeyPoint>& occupied_cells, std::vector< std::vector<KeyPoint> >& clusters);
185 void regionQuery(
const std::vector<KeyPoint>& occupied_cells,
int curr_index, std::vector<int>& neighbor_indices);
200 void convexHull(std::vector<KeyPoint>& cluster, geometry_msgs::Polygon& polygon);
215 void convexHull2(std::vector<KeyPoint>& cluster, geometry_msgs::Polygon& polygon);
226 template <
typename P1,
typename P2,
typename P3>
227 long double cross(
const P1& O,
const P2& A,
const P3& B)
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);
259 void reconfigureCB(CostmapToPolygonsDBSMCCHConfig& config, uint32_t level);
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)
KeyPoint()
Default constructor.
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.
virtual ~CostmapToPolygonsDBSMCCH()
Destructor.
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.
CostmapToPolygonsDBSMCCH()
Constructor.
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