39 #ifndef COSTMAP_TO_LINES_CONVEX_HULL_H_ 40 #define COSTMAP_TO_LINES_CONVEX_HULL_H_ 46 #include <costmap_converter/CostmapToLinesDBSMCCHConfig.h> 103 void extractPointsAndLines(std::vector<KeyPoint>& cluster,
const geometry_msgs::Polygon& polygon, std::back_insert_iterator< std::vector<geometry_msgs::Polygon> > lines);
122 void reconfigureCB(CostmapToLinesDBSMCCHConfig& config, uint32_t level);
virtual void compute()
This method performs the actual work (conversion of the costmap to polygons)
double support_pts_max_dist_
virtual void initialize(ros::NodeHandle nh)
Initialize the plugin.
This class converts the costmap_2d into a set of lines (and points)
virtual ~CostmapToLinesDBSMCCH()
Destructor.
dynamic_reconfigure::Server< CostmapToLinesDBSMCCHConfig > * dynamic_recfg_
Dynamic reconfigure server to allow config modifications at runtime.
double support_pts_max_dist_inbetween_
This class converts the costmap_2d into a set of convex polygons (and points)
void reconfigureCB(CostmapToLinesDBSMCCHConfig &config, uint32_t level)
Callback for the dynamic_reconfigure node.
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...
CostmapToLinesDBSMCCH()
Constructor.