Go to the documentation of this file.
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>
79 class CostmapToPolygonsDBSMCCH :
public BaseCostmapToPolygons
92 KeyPoint(
double x_,
double y_) :
x(x_),
y(y_) {}
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;}
159 template<
typename Po
int>
162 polygon.points.resize(1);
163 polygon.points.front().x = point.x;
164 polygon.points.front().y = point.y;
165 polygon.points.front().z = 0;
190 void dbScan(std::vector< std::vector<KeyPoint> >& clusters);
198 void regionQuery(
int curr_index, std::vector<int>& neighbor_indices);
226 void convexHull(std::vector<KeyPoint>& cluster, geometry_msgs::Polygon& polygon);
241 void convexHull2(std::vector<KeyPoint>& cluster, geometry_msgs::Polygon& polygon);
261 template <
typename P1,
typename P2,
typename P3>
262 long double cross(
const P1& O,
const P2& A,
const P3& B)
264 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);
321 void reconfigureCB(CostmapToPolygonsDBSMCCHConfig& config, uint32_t level);
327 dynamic_reconfigure::Server<CostmapToPolygonsDBSMCCHConfig>*
dynamic_recfg_;
int neighborCellsToIndex(int cx, int cy)
offset [meters] in y for the lookup grid
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.
KeyPoint()
Default constructor.
void toPointMsg(geometry_msgs::Point &point) const
Convert keypoint to geometry_msgs::Point message type.
costmap_2d::Costmap2D * costmap_
Pointer to the costmap2d.
int neighbor_size_x_
array of cells for neighbor lookup
PolygonContainerConstPtr getPolygons()
Get a shared instance of the current polygon container.
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
virtual void updateCostmap2D()
Get updated data from the previously set Costmap2D.
Parameters parameter_buffered_
void reconfigureCB(CostmapToPolygonsDBSMCCHConfig &config, uint32_t level)
Callback for the dynamic_reconfigure node.
void dbScan(std::vector< std::vector< KeyPoint > > &clusters)
DBSCAN algorithm for clustering.
PolygonContainerPtr polygons_
Current shared container of polygons.
static void convertPointToPolygon(const Point &point, geometry_msgs::Polygon &polygon)
Convert a generi point type to a geometry_msgs::Polygon.
void addPoint(double x, double y)
helper function for adding a point to the lookup data structures
void updatePolygonContainer(PolygonContainerPtr polygons)
Thread-safe update of the internal polygon container (that is shared using getPolygons() from outside...
CostmapToPolygonsDBSMCCH()
Constructor.
int neighbor_size_y_
size of the neighbour lookup in x (number of cells)
double max_distance_
Parameter for DB_Scan, maximum distance to neighbors [m].
virtual void setCostmap2D(costmap_2d::Costmap2D *costmap)
Pass a pointer to the costap to the plugin.
boost::shared_ptr< std::vector< geometry_msgs::Polygon > > PolygonContainerPtr
Typedef for a shared polygon container.
void convexHull(std::vector< KeyPoint > &cluster, geometry_msgs::Polygon &polygon)
Compute the convex hull for a single cluster (monotone chain algorithm)
std::vector< std::vector< int > > neighbor_lookup_
std::vector< KeyPoint > occupied_cells_
List of occupied cells in the current map (updated by updateCostmap2D())
void pointToNeighborCells(const KeyPoint &kp, int &cx, int &cy)
compute the cell indices of a keypoint
boost::mutex parameter_mutex_
Mutex that keeps track about the ownership of the shared polygon instance.
double min_keypoint_separation_
Clear keypoints of the convex polygon that are close to each other [distance in meters] (0: keep all)
double offset_y_
offset [meters] in x for the lookup grid
virtual void compute()
This method performs the actual work (conversion of the costmap to polygons)
double offset_x_
size of the neighbour lookup in y (number of cells)
void simplifyPolygon(geometry_msgs::Polygon &polygon)
Simplify a polygon by removing points.
int max_pts_
Parameter for DB_Scan: maximum number of points that define a cluster (to avoid large L- and U-shapes...
virtual ~CostmapToPolygonsDBSMCCH()
Destructor.
void regionQuery(int curr_index, std::vector< int > &neighbor_indices)
Helper function for dbScan to search for neighboring points.
int min_pts_
Parameter for DB_Scan: minimum number of points that define a cluster.
dynamic_reconfigure::Server< CostmapToPolygonsDBSMCCHConfig > * dynamic_recfg_
Dynamic reconfigure server to allow config modifications at runtime
costmap_converter
Author(s): Christoph Rösmann
, Franz Albers , Otniel Rinaldo
autogenerated on Fri Sep 20 2024 02:19:25