39 #ifndef COSTMAP_TO_POLYGONS_CONCAVE_H_ 40 #define COSTMAP_TO_POLYGONS_CONCAVE_H_ 46 #include <costmap_converter/CostmapToPolygonsDBSConcaveHullConfig.h> 47 #include <dynamic_reconfigure/server.h> 99 void concaveHull(std::vector<KeyPoint>& cluster,
double depth, geometry_msgs::Polygon& polygon);
101 void concaveHullClusterCut(std::vector<KeyPoint>& cluster,
double depth, geometry_msgs::Polygon& polygon);
103 template <
typename Po
intLine,
typename Po
intCluster,
typename Po
intHull>
104 std::size_t
findNearestInnerPoint(PointLine line_start, PointLine line_end,
const std::vector<PointCluster>& cluster,
const std::vector<PointHull>& hull,
bool* found);
107 template <
typename Po
int1,
typename Po
int2,
typename Po
int3,
typename Po
int4>
108 bool checkLineIntersection(
const Point1& line1_start,
const Point2& line1_end,
const Point3& line2_start,
const Point4& line2_end);
110 template <
typename Po
intHull,
typename Po
int1,
typename Po
int2,
typename Po
int3,
typename Po
int4>
112 const Point2& current_line_end,
const Point3& test_line_start,
const Point4& test_line_end);
125 void reconfigureCB(CostmapToPolygonsDBSConcaveHullConfig& config, uint32_t level);
127 dynamic_reconfigure::Server<CostmapToPolygonsDBSConcaveHullConfig>*
dynamic_recfg_;
133 template <
typename Po
intLine,
typename Po
intCluster,
typename Po
intHull>
136 std::size_t nearsest_idx = 0;
140 for (std::size_t i = 0; i < cluster.size(); ++i)
143 if (std::find_if( hull.begin(), hull.end(), boost::bind(isApprox2d<PointHull, PointCluster>, _1, boost::cref(cluster[i]), 1e-5) ) != hull.end() )
148 for (
int j = 0; !skip && j < (int)hull.size() - 1; ++j)
151 skip |= dist_temp < dist;
156 if (!(*found) || dist < distance)
167 template <
typename Po
int1,
typename Po
int2,
typename Po
int3,
typename Po
int4>
170 double dx1 = line1_end.x - line1_start.x;
171 double dy1 = line1_end.y - line1_start.y;
172 double dx2 = line2_end.x - line2_start.x;
173 double dy2 = line2_end.y - line2_start.y;
174 double s = (-dy1 * (line1_start.x - line2_start.x) + dx1 * (line1_start.y - line2_start.y)) / (-dx2 * dy1 + dx1 * dy2);
175 double t = ( dx2 * (line1_start.y - line2_start.y) - dy2 * (line1_start.x - line2_start.x)) / (-dx2 * dy1 + dx1 * dy2);
176 return (s > 0 && s < 1 && t > 0 && t < 1);
180 template <
typename Po
intHull,
typename Po
int1,
typename Po
int2,
typename Po
int3,
typename Po
int4>
182 const Point2& current_line_end,
const Point3& test_line_start,
const Point4& test_line_end)
184 for (
int i = 0; i < (int)hull.size() - 2; i++)
186 if (
isApprox2d(current_line_start, hull[i], 1e-5) &&
isApprox2d(current_line_end, hull[i+1], 1e-5))
CostmapToPolygonsDBSConcaveHull()
Constructor.
virtual void initialize(ros::NodeHandle nh)
Initialize the plugin.
void concaveHullClusterCut(std::vector< KeyPoint > &cluster, double depth, geometry_msgs::Polygon &polygon)
double computeDistanceToLineSegment(const Point &point, const LinePoint &line_start, const LinePoint &line_end, bool *is_inbetween=NULL)
Calculate the distance between a point and a straight line segment.
virtual ~CostmapToPolygonsDBSConcaveHull()
Destructor.
This class converts the costmap_2d into a set of non-convex polygons (and points) ...
double concave_hull_depth_
bool checkLineIntersection(const Point1 &line1_start, const Point2 &line1_end, const Point3 &line2_start, const Point4 &line2_end)
virtual void compute()
This method performs the actual work (conversion of the costmap to polygons)
void reconfigureCB(CostmapToPolygonsDBSConcaveHullConfig &config, uint32_t level)
Callback for the dynamic_reconfigure node.
double distance(double x0, double y0, double x1, double y1)
dynamic_reconfigure::Server< CostmapToPolygonsDBSConcaveHullConfig > * dynamic_recfg_
Dynamic reconfigure server to allow config modifications at runtime.
std::size_t findNearestInnerPoint(PointLine line_start, PointLine line_end, const std::vector< PointCluster > &cluster, const std::vector< PointHull > &hull, bool *found)
void concaveHull(std::vector< KeyPoint > &cluster, double depth, geometry_msgs::Polygon &polygon)
Compute the concave hull for a single cluster.
This class converts the costmap_2d into a set of convex polygons (and points)
bool isApprox2d(const Point1 &pt1, const Point2 &pt2, double threshold)
Check if two points are approximately defining the same one.