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

This class converts the costmap_2d into a set of lines (and points) More...

#include <costmap_to_lines_convex_hull.h>

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

Public Member Functions

virtual void compute ()
 This method performs the actual work (conversion of the costmap to polygons) More...
 
 CostmapToLinesDBSMCCH ()
 Constructor. More...
 
virtual void initialize (ros::NodeHandle nh)
 Initialize the plugin. More...
 
virtual ~CostmapToLinesDBSMCCH ()
 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

void extractPointsAndLines (std::vector< KeyPoint > &cluster, const geometry_msgs::Polygon &polygon, std::back_insert_iterator< std::vector< geometry_msgs::Polygon > > lines)
 Extract points and lines from a given cluster by checking all keypoint pairs of the convex hull for a minimum number of support points. More...
 
- 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

int min_support_pts_
 
double support_pts_max_dist_
 
double support_pts_max_dist_inbetween_
 
- 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 (CostmapToLinesDBSMCCHConfig &config, uint32_t level)
 Callback for the dynamic_reconfigure node. More...
 

Private Attributes

dynamic_reconfigure::Server< CostmapToLinesDBSMCCHConfig > * 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 lines (and points)

The conversion is performed in three stages:

  1. Clusters in the costmap are collected using the DBSCAN Algorithm (https://en.wikipedia.org/wiki/DBSCAN) Reference: Ester, Martin; Kriegel, Hans-Peter; Sander, Jörg; Xu, Xiaowei, A density-based algorithm for discovering clusters in large spatial databases with noise. Proceedings of the Second International Conference on Knowledge Discovery and Data Mining. AAAI Press. 1996. pp. 226–231. ISBN 1-57735-004-9.
  2. In the subsequent stage, the convex hull of each cluster is determined using the monotone chain algorithm aka Andrew's algorithm: C++ implementation example: http://www.algorithmist.com/index.php/Monotone_Chain_Convex_Hull ( GNU Free Documentation License 1.2 ) Reference: A. M. Andrew, "Another Efficient Algorithm for Convex Hulls in Two Dimensions", Info. Proc. Letters 9, 216-219 (1979).
  3. In the third step extract lines from each polygon (convex hull) if there exist at least a predefined number of support points.

The output is a container of polygons (but each polygon does only contain a single vertex (point) or two vertices (line)

Definition at line 69 of file costmap_to_lines_convex_hull.h.

Constructor & Destructor Documentation

costmap_converter::CostmapToLinesDBSMCCH::CostmapToLinesDBSMCCH ( )

Constructor.

Definition at line 50 of file costmap_to_lines_convex_hull.cpp.

costmap_converter::CostmapToLinesDBSMCCH::~CostmapToLinesDBSMCCH ( )
virtual

Destructor.

Definition at line 55 of file costmap_to_lines_convex_hull.cpp.

Member Function Documentation

void costmap_converter::CostmapToLinesDBSMCCH::compute ( )
virtual

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

Reimplemented from costmap_converter::CostmapToPolygonsDBSMCCH.

Definition at line 99 of file costmap_to_lines_convex_hull.cpp.

void costmap_converter::CostmapToLinesDBSMCCH::extractPointsAndLines ( std::vector< KeyPoint > &  cluster,
const geometry_msgs::Polygon &  polygon,
std::back_insert_iterator< std::vector< geometry_msgs::Polygon > >  lines 
)
protected

Extract points and lines from a given cluster by checking all keypoint pairs of the convex hull for a minimum number of support points.

Parameters
clusterlist of points in the cluster
polygonconvex hull of the cluster cluster
[out]linesback_inserter object to a sequence of polygon msgs (new lines will be pushed back)

Definition at line 139 of file costmap_to_lines_convex_hull.cpp.

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

Initialize the plugin.

Parameters
nhNodehandle that defines the namespace for parameters

Reimplemented from costmap_converter::CostmapToPolygonsDBSMCCH.

Definition at line 61 of file costmap_to_lines_convex_hull.cpp.

void costmap_converter::CostmapToLinesDBSMCCH::reconfigureCB ( CostmapToLinesDBSMCCHConfig &  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 284 of file costmap_to_lines_convex_hull.cpp.

Member Data Documentation

dynamic_reconfigure::Server<CostmapToLinesDBSMCCHConfig>* costmap_converter::CostmapToLinesDBSMCCH::dynamic_recfg_
private

Dynamic reconfigure server to allow config modifications at runtime.

Definition at line 124 of file costmap_to_lines_convex_hull.h.

int costmap_converter::CostmapToLinesDBSMCCH::min_support_pts_
protected

Definition at line 111 of file costmap_to_lines_convex_hull.h.

double costmap_converter::CostmapToLinesDBSMCCH::support_pts_max_dist_
protected

Definition at line 110 of file costmap_to_lines_convex_hull.h.

double costmap_converter::CostmapToLinesDBSMCCH::support_pts_max_dist_inbetween_
protected

Definition at line 109 of file costmap_to_lines_convex_hull.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