77 dynamic_recfg_ =
new dynamic_reconfigure::Server<CostmapToPolygonsDBSConcaveHullConfig>(nh);
85 std::vector< std::vector<KeyPoint> > clusters;
93 for (
int i = 1; i <clusters.size(); ++i)
95 polygons->push_back( geometry_msgs::Polygon() );
100 if (!clusters.empty())
102 for (
int i=0; i < clusters.front().size(); ++i)
104 polygons->push_back( geometry_msgs::Polygon() );
119 std::vector<geometry_msgs::Point32>& concave_list = polygon.points;
121 for (
int i = 0; i < (int)concave_list.size() - 1; ++i)
125 const geometry_msgs::Point32& vertex1 = concave_list[i];
126 const geometry_msgs::Point32& vertex2 = concave_list[i+1];
133 double line_length =
norm2d(vertex1, vertex2);
135 double dst1 =
norm2d(cluster[nearest_idx], vertex1);
136 double dst2 =
norm2d(cluster[nearest_idx], vertex2);
137 double dd = std::min(dst1, dst2);
141 if (line_length / dd > depth)
148 geometry_msgs::Point32 new_point;
149 cluster[nearest_idx].toPointMsg(new_point);
150 concave_list.insert(concave_list.begin() + i + 1, new_point);
163 std::vector<geometry_msgs::Point32>& concave_list = polygon.points;
166 double mean_length = 0;
167 for (
int i = 0; i < (int)concave_list.size() - 1; ++i)
169 mean_length +=
norm2d(concave_list[i],concave_list[i+1]);
171 mean_length /= double(concave_list.size());
173 for (
int i = 0; i < (int)concave_list.size() - 1; ++i)
177 const geometry_msgs::Point32& vertex1 = concave_list[i];
178 const geometry_msgs::Point32& vertex2 = concave_list[i+1];
180 double line_length =
norm2d(vertex1, vertex2);
190 double dst1 =
norm2d(cluster[nearest_idx], vertex1);
191 double dst2 =
norm2d(cluster[nearest_idx], vertex2);
192 double dd = std::min(dst1, dst2);
196 if (line_length / dd > depth)
203 geometry_msgs::Point32 new_point;
204 cluster[nearest_idx].toPointMsg(new_point);
205 concave_list.insert(concave_list.begin() + i + 1, new_point);
bool intersects(std::vector< geometry_msgs::Point > &polygon, float testx, float testy)
std::vector< KeyPoint > occupied_cells_
List of occupied cells in the current map (updated by updateCostmap2D())
int max_pts_
Parameter for DB_Scan: maximum number of points that define a cluster (to avoid large L- and U-shapes...
double norm2d(const Point1 &pt1, const Point2 &pt2)
Calculate the distance between two 2d points.
virtual void initialize(ros::NodeHandle nh)
Initialize the plugin.
void concaveHullClusterCut(std::vector< KeyPoint > &cluster, double depth, geometry_msgs::Polygon &polygon)
static void convertPointToPolygon(const Point &point, geometry_msgs::Polygon &polygon)
Convert a generi point type to a geometry_msgs::Polygon.
double max_distance_
Parameter for DB_Scan, maximum distance to neighbors [m].
double min_keypoint_separation_
Clear keypoints of the convex polygon that are close to each other [distance in meters] (0: keep all)...
virtual ~CostmapToPolygonsDBSConcaveHull()
Destructor.
PLUGINLIB_EXPORT_CLASS(BAGReader, nodelet::Nodelet)
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.
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)
bool param(const std::string ¶m_name, T ¶m_val, const T &default_val) const
This abstract class defines the interface for plugins that convert the costmap into polygon types...
void concaveHull(std::vector< KeyPoint > &cluster, double depth, geometry_msgs::Polygon &polygon)
Compute the concave hull for a single cluster.
int min_pts_
Parameter for DB_Scan: minimum number of points that define a cluster.
This class converts the costmap_2d into a set of convex polygons (and points)
void dbScan(const std::vector< KeyPoint > &occupied_cells, std::vector< std::vector< KeyPoint > > &clusters)
DBSCAN algorithm for clustering.
void convexHull2(std::vector< KeyPoint > &cluster, geometry_msgs::Polygon &polygon)
Compute the convex hull for a single cluster.
void updatePolygonContainer(PolygonContainerPtr polygons)
Thread-safe update of the internal polygon container (that is shared using getPolygons() from outside...