Public Member Functions | Protected Member Functions | Protected Attributes | Private Member Functions | Private Attributes | List of all members
costmap_converter::CostmapToPolygonsDBSConcaveHull Class Reference

This class converts the costmap_2d into a set of non-convex polygons (and points) More...

#include <costmap_to_polygons_concave.h>

Inheritance diagram for costmap_converter::CostmapToPolygonsDBSConcaveHull:
Inheritance graph
[legend]

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 &current_line_start, const Point2 &current_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 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 (const std::vector< KeyPoint > &occupied_cells, std::vector< std::vector< KeyPoint > > &clusters)
 DBSCAN algorithm for clustering. More...
 
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. 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
double max_distance_
 Parameter for DB_Scan, maximum distance to neighbors [m]. More...
 
int max_pts_
 Parameter for DB_Scan: maximum number of points that define a cluster (to avoid large L- and U-shapes) More...
 
double min_keypoint_separation_
 Clear keypoints of the convex polygon that are close to each other [distance in meters] (0: keep all) More...
 
int min_pts_
 Parameter for DB_Scan: minimum number of points that define a cluster. More...
 
std::vector< KeyPointoccupied_cells_
 List of occupied cells in the current map (updated by updateCostmap2D()) 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...
 

Detailed Description

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)

Todo:
change the class hierarchy to a clearer and more generic one

Definition at line 60 of file costmap_to_polygons_concave.h.

Constructor & Destructor Documentation

costmap_converter::CostmapToPolygonsDBSConcaveHull::CostmapToPolygonsDBSConcaveHull ( )

Constructor.

Definition at line 48 of file costmap_to_polygons_concave.cpp.

costmap_converter::CostmapToPolygonsDBSConcaveHull::~CostmapToPolygonsDBSConcaveHull ( )
virtual

Destructor.

Definition at line 53 of file costmap_to_polygons_concave.cpp.

Member Function Documentation

template<typename Point1 , typename Point2 , typename Point3 , typename Point4 >
bool costmap_converter::CostmapToPolygonsDBSConcaveHull::checkLineIntersection ( const Point1 &  line1_start,
const Point2 &  line1_end,
const Point3 &  line2_start,
const Point4 &  line2_end 
)
protected

Definition at line 168 of file costmap_to_polygons_concave.h.

template<typename PointHull , typename Point1 , typename Point2 , typename Point3 , typename Point4 >
bool costmap_converter::CostmapToPolygonsDBSConcaveHull::checkLineIntersection ( const std::vector< PointHull > &  hull,
const Point1 &  current_line_start,
const Point2 &  current_line_end,
const Point3 &  test_line_start,
const Point4 &  test_line_end 
)
protected

Definition at line 181 of file costmap_to_polygons_concave.h.

void costmap_converter::CostmapToPolygonsDBSConcaveHull::compute ( )
virtual

This method performs the actual work (conversion of the costmap to polygons)

Reimplemented from costmap_converter::CostmapToPolygonsDBSMCCH.

Definition at line 83 of file costmap_to_polygons_concave.cpp.

void costmap_converter::CostmapToPolygonsDBSConcaveHull::concaveHull ( std::vector< KeyPoint > &  cluster,
double  depth,
geometry_msgs::Polygon &  polygon 
)
protected

Compute the concave hull for a single cluster.

Remarks
The last point is the same as the first one
Parameters
clusterlist of keypoints that should be converted into a polygon
depthSmaller depth: sharper surface, depth -> high value: convex hull
[out]polygonthe resulting convex polygon

Definition at line 114 of file costmap_to_polygons_concave.cpp.

void costmap_converter::CostmapToPolygonsDBSConcaveHull::concaveHullClusterCut ( std::vector< KeyPoint > &  cluster,
double  depth,
geometry_msgs::Polygon &  polygon 
)
protected

Definition at line 158 of file costmap_to_polygons_concave.cpp.

template<typename PointLine , typename PointCluster , typename PointHull >
std::size_t costmap_converter::CostmapToPolygonsDBSConcaveHull::findNearestInnerPoint ( PointLine  line_start,
PointLine  line_end,
const std::vector< PointCluster > &  cluster,
const std::vector< PointHull > &  hull,
bool *  found 
)
protected

Definition at line 134 of file costmap_to_polygons_concave.h.

void costmap_converter::CostmapToPolygonsDBSConcaveHull::initialize ( ros::NodeHandle  nh)
virtual

Initialize the plugin.

Parameters
nhNodehandle that defines the namespace for parameters

Reimplemented from costmap_converter::CostmapToPolygonsDBSMCCH.

Definition at line 59 of file costmap_to_polygons_concave.cpp.

void costmap_converter::CostmapToPolygonsDBSConcaveHull::reconfigureCB ( CostmapToPolygonsDBSConcaveHullConfig &  config,
uint32_t  level 
)
private

Callback for the dynamic_reconfigure node.

This callback allows to modify parameters dynamically at runtime without restarting the node

Parameters
configReference to the dynamic reconfigure config
levelDynamic reconfigure level

Definition at line 215 of file costmap_to_polygons_concave.cpp.

Member Data Documentation

double costmap_converter::CostmapToPolygonsDBSConcaveHull::concave_hull_depth_
protected

Definition at line 114 of file costmap_to_polygons_concave.h.

dynamic_reconfigure::Server<CostmapToPolygonsDBSConcaveHullConfig>* costmap_converter::CostmapToPolygonsDBSConcaveHull::dynamic_recfg_
private

Dynamic reconfigure server to allow config modifications at runtime.

Definition at line 127 of file costmap_to_polygons_concave.h.


The documentation for this class was generated from the following files:


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