This class converts the costmap_2d into a set of non-convex polygons (and points) More...
#include <costmap_to_polygons_concave.h>
Public Member Functions | |
virtual void | compute () |
This method performs the actual work (conversion of the costmap to polygons) More... | |
CostmapToPolygonsDBSConcaveHull () | |
Constructor. More... | |
virtual void | initialize (ros::NodeHandle nh) |
Initialize the plugin. More... | |
virtual | ~CostmapToPolygonsDBSConcaveHull () |
Destructor. More... | |
Public Member Functions inherited from costmap_converter::CostmapToPolygonsDBSMCCH | |
CostmapToPolygonsDBSMCCH () | |
Constructor. More... | |
PolygonContainerConstPtr | getPolygons () |
Get a shared instance of the current polygon container. More... | |
virtual void | setCostmap2D (costmap_2d::Costmap2D *costmap) |
Pass a pointer to the costap to the plugin. More... | |
virtual void | updateCostmap2D () |
Get updated data from the previously set Costmap2D. More... | |
virtual | ~CostmapToPolygonsDBSMCCH () |
Destructor. More... | |
Public Member Functions inherited from costmap_converter::BaseCostmapToPolygons | |
virtual ObstacleArrayConstPtr | getObstacles () |
Get a shared instance of the current obstacle container If this method is not overwritten by the underlying plugin, the obstacle container just imports getPolygons(). More... | |
virtual void | setOdomTopic (const std::string &odom_topic) |
Set name of robot's odometry topic. More... | |
virtual bool | stackedCostmapConversion () |
Determines whether an additional plugin for subsequent costmap conversion is specified. More... | |
void | startWorker (ros::Rate rate, costmap_2d::Costmap2D *costmap, bool spin_thread=false) |
Instantiate a worker that repeatedly coverts the most recent costmap to polygons. The worker is implemented as a timer event that is invoked at a specific rate . The passed costmap pointer must be valid at the complete time and must be lockable. By specifying the argument spin_thread the timer event is invoked in a separate thread and callback queue or otherwise it is called from the global callback queue (of the node in which the plugin is used). More... | |
void | stopWorker () |
Stop the worker that repeatedly converts the costmap to polygons. More... | |
virtual | ~BaseCostmapToPolygons () |
Destructor. More... | |
Protected Member Functions | |
template<typename Point1 , typename Point2 , typename Point3 , typename Point4 > | |
bool | checkLineIntersection (const Point1 &line1_start, const Point2 &line1_end, const Point3 &line2_start, const Point4 &line2_end) |
template<typename PointHull , typename Point1 , typename Point2 , typename Point3 , typename Point4 > | |
bool | checkLineIntersection (const std::vector< PointHull > &hull, const Point1 ¤t_line_start, const Point2 ¤t_line_end, const Point3 &test_line_start, const Point4 &test_line_end) |
void | concaveHull (std::vector< KeyPoint > &cluster, double depth, geometry_msgs::Polygon &polygon) |
Compute the concave hull for a single cluster. More... | |
void | concaveHullClusterCut (std::vector< KeyPoint > &cluster, double depth, geometry_msgs::Polygon &polygon) |
template<typename PointLine , typename PointCluster , typename PointHull > | |
std::size_t | findNearestInnerPoint (PointLine line_start, PointLine line_end, const std::vector< PointCluster > &cluster, const std::vector< PointHull > &hull, bool *found) |
Protected Member Functions inherited from costmap_converter::CostmapToPolygonsDBSMCCH | |
void | addPoint (double x, double y) |
helper function for adding a point to the lookup data structures More... | |
void | convexHull (std::vector< KeyPoint > &cluster, geometry_msgs::Polygon &polygon) |
Compute the convex hull for a single cluster (monotone chain algorithm) More... | |
void | convexHull2 (std::vector< KeyPoint > &cluster, geometry_msgs::Polygon &polygon) |
Compute the convex hull for a single cluster. More... | |
template<typename P1 , typename P2 , typename P3 > | |
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 More... | |
void | dbScan (std::vector< std::vector< KeyPoint > > &clusters) |
DBSCAN algorithm for clustering. More... | |
int | neighborCellsToIndex (int cx, int cy) |
offset [meters] in y for the lookup grid More... | |
void | pointToNeighborCells (const KeyPoint &kp, int &cx, int &cy) |
compute the cell indices of a keypoint More... | |
void | regionQuery (int curr_index, std::vector< int > &neighbor_indices) |
Helper function for dbScan to search for neighboring points. More... | |
void | simplifyPolygon (geometry_msgs::Polygon &polygon) |
Simplify a polygon by removing points. More... | |
void | updatePolygonContainer (PolygonContainerPtr polygons) |
Thread-safe update of the internal polygon container (that is shared using getPolygons() from outside this class) More... | |
Protected Member Functions inherited from costmap_converter::BaseCostmapToPolygons | |
BaseCostmapToPolygons () | |
Protected constructor that should be called by subclasses. More... | |
void | spinThread () |
Blocking method that checks for new timer events (active if startWorker() is called with spin_thread enabled) More... | |
void | workerCallback (const ros::TimerEvent &) |
The callback of the worker that performs the actual work (updating the costmap and converting it to polygons) More... | |
Protected Attributes | |
double | concave_hull_depth_ |
Protected Attributes inherited from costmap_converter::CostmapToPolygonsDBSMCCH | |
std::vector< std::vector< int > > | neighbor_lookup_ |
int | neighbor_size_x_ |
array of cells for neighbor lookup More... | |
int | neighbor_size_y_ |
size of the neighbour lookup in x (number of cells) More... | |
std::vector< KeyPoint > | occupied_cells_ |
List of occupied cells in the current map (updated by updateCostmap2D()) More... | |
double | offset_x_ |
size of the neighbour lookup in y (number of cells) More... | |
double | offset_y_ |
offset [meters] in x for the lookup grid More... | |
Parameters | parameter_ |
Parameters | parameter_buffered_ |
boost::mutex | parameter_mutex_ |
Mutex that keeps track about the ownership of the shared polygon instance. More... | |
Private Member Functions | |
void | reconfigureCB (CostmapToPolygonsDBSConcaveHullConfig &config, uint32_t level) |
Callback for the dynamic_reconfigure node. More... | |
Private Attributes | |
dynamic_reconfigure::Server< CostmapToPolygonsDBSConcaveHullConfig > * | dynamic_recfg_ |
Dynamic reconfigure server to allow config modifications at runtime. More... | |
Additional Inherited Members | |
Static Public Member Functions inherited from costmap_converter::CostmapToPolygonsDBSMCCH | |
template<typename Point > | |
static void | convertPointToPolygon (const Point &point, geometry_msgs::Polygon &polygon) |
Convert a generi point type to a geometry_msgs::Polygon. More... | |
This class converts the costmap_2d into a set of non-convex polygons (and points)
All single points that do not define a cluster (noise) are also treated as polygon (represented as a single vertex)
Definition at line 60 of file costmap_to_polygons_concave.h.
costmap_converter::CostmapToPolygonsDBSConcaveHull::CostmapToPolygonsDBSConcaveHull | ( | ) |
Constructor.
Definition at line 48 of file costmap_to_polygons_concave.cpp.
|
virtual |
Destructor.
Definition at line 53 of file costmap_to_polygons_concave.cpp.
|
protected |
Definition at line 168 of file costmap_to_polygons_concave.h.
|
protected |
Definition at line 181 of file costmap_to_polygons_concave.h.
|
virtual |
This method performs the actual work (conversion of the costmap to polygons)
Reimplemented from costmap_converter::CostmapToPolygonsDBSMCCH.
Definition at line 76 of file costmap_to_polygons_concave.cpp.
|
protected |
Compute the concave hull for a single cluster.
cluster | list of keypoints that should be converted into a polygon | |
depth | Smaller depth: sharper surface, depth -> high value: convex hull | |
[out] | polygon | the resulting convex polygon |
Definition at line 107 of file costmap_to_polygons_concave.cpp.
|
protected |
Definition at line 151 of file costmap_to_polygons_concave.cpp.
|
protected |
Definition at line 134 of file costmap_to_polygons_concave.h.
|
virtual |
Initialize the plugin.
nh | Nodehandle that defines the namespace for parameters |
Reimplemented from costmap_converter::CostmapToPolygonsDBSMCCH.
Definition at line 59 of file costmap_to_polygons_concave.cpp.
|
private |
Callback for the dynamic_reconfigure node.
This callback allows to modify parameters dynamically at runtime without restarting the node
config | Reference to the dynamic reconfigure config |
level | Dynamic reconfigure level |
Definition at line 208 of file costmap_to_polygons_concave.cpp.
|
protected |
Definition at line 114 of file costmap_to_polygons_concave.h.
|
private |
Dynamic reconfigure server to allow config modifications at runtime.
Definition at line 127 of file costmap_to_polygons_concave.h.