Public Member Functions | List of all members
CostmapToPolygons Class Reference
Inheritance diagram for CostmapToPolygons:
Inheritance graph
[legend]

Public Member Functions

costmap_converter::CostmapToPolygonsDBSMCCH::Parametersparameters ()
 
const std::vector< costmap_converter::CostmapToPolygonsDBSMCCH::KeyPoint > & points () const
 
- Public Member Functions inherited from costmap_converter::CostmapToPolygonsDBSMCCH
virtual void compute ()
 This method performs the actual work (conversion of the costmap to polygons) More...
 
 CostmapToPolygonsDBSMCCH ()
 Constructor. More...
 
PolygonContainerConstPtr getPolygons ()
 Get a shared instance of the current polygon container. More...
 
virtual void initialize (ros::NodeHandle nh)
 Initialize the plugin. 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...
 

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...
 
- 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 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< KeyPointoccupied_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...
 

Detailed Description

Definition at line 19 of file costmap_polygons.cpp.

Member Function Documentation

costmap_converter::CostmapToPolygonsDBSMCCH::Parameters& CostmapToPolygons::parameters ( )
inline

Definition at line 23 of file costmap_polygons.cpp.

const std::vector<costmap_converter::CostmapToPolygonsDBSMCCH::KeyPoint>& CostmapToPolygons::points ( ) const
inline

Definition at line 22 of file costmap_polygons.cpp.


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


costmap_converter
Author(s): Christoph Rösmann , Franz Albers , Otniel Rinaldo
autogenerated on Sat May 16 2020 03:19:18