Public Member Functions | Protected Member Functions | Protected Attributes | Private Member Functions | Private Attributes
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]

List of all members.

Public Member Functions

virtual void compute ()
 This method performs the actual work (conversion of the costmap to polygons)
 CostmapToPolygonsDBSConcaveHull ()
 Constructor.
virtual void initialize (ros::NodeHandle nh)
 Initialize the plugin.
virtual ~CostmapToPolygonsDBSConcaveHull ()
 Destructor.

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

double concave_hull_depth_

Private Member Functions

void reconfigureCB (CostmapToPolygonsDBSConcaveHullConfig &config, uint32_t level)
 Callback for the dynamic_reconfigure node.

Private Attributes

dynamic_reconfigure::Server
< CostmapToPolygonsDBSConcaveHullConfig > * 
dynamic_recfg_
 Dynamic reconfigure server to allow config modifications at runtime.

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

Constructor.

Definition at line 48 of file costmap_to_polygons_concave.cpp.

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.

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.

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

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.

Reimplemented from costmap_converter::CostmapToPolygonsDBSMCCH.

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 Wed Sep 20 2017 03:00:37