41 #include <boost/thread.hpp> 42 #include <boost/thread/mutex.hpp> 60 std::vector<geometry_msgs::Point32> douglasPeucker(std::vector<geometry_msgs::Point32>::iterator begin,
61 std::vector<geometry_msgs::Point32>::iterator end,
double epsilon)
63 if (std::distance(begin, end) <= 2)
65 return std::vector<geometry_msgs::Point32>(begin, end);
69 double dmax = std::numeric_limits<double>::lowest();
70 std::vector<geometry_msgs::Point32>::iterator max_dist_it;
71 std::vector<geometry_msgs::Point32>::iterator last = std::prev(end);
72 for (
auto it = std::next(begin); it != last; ++it)
82 if (dmax < epsilon * epsilon)
84 std::vector<geometry_msgs::Point32> result;
85 result.push_back(*begin);
86 result.push_back(*last);
91 auto firstLineSimplified = douglasPeucker(begin, std::next(max_dist_it), epsilon);
92 auto secondLineSimplified = douglasPeucker(max_dist_it, end, epsilon);
96 firstLineSimplified.insert(firstLineSimplified.end(),
97 std::make_move_iterator(std::next(secondLineSimplified.begin())),
98 std::make_move_iterator(secondLineSimplified.end()));
99 return firstLineSimplified;
133 dynamic_recfg_ =
new dynamic_reconfigure::Server<CostmapToPolygonsDBSMCCHConfig>(nh);
141 std::vector< std::vector<KeyPoint> > clusters;
149 for (std::size_t i = 1; i <clusters.size(); ++i)
151 polygons->push_back( geometry_msgs::Polygon() );
156 if (!clusters.empty())
158 for (std::size_t i=0; i < clusters.front().size(); ++i)
160 polygons->push_back( geometry_msgs::Polygon() );
185 ROS_ERROR(
"Cannot update costmap since the mutex pointer is null");
235 clusters.push_back(std::vector<KeyPoint>());
241 std::vector<int> neighbors;
250 clusters.push_back(std::vector<KeyPoint>());
254 for(
int j = 0; j<(int)neighbors.size(); j++)
259 if(!visited[neighbors[j]])
261 visited[neighbors[j]] =
true;
262 std::vector<int> further_neighbors;
272 neighbors.insert(neighbors.end(), further_neighbors.begin(), further_neighbors.end());
292 const int offsets[9][2] = {{-1, -1}, {0, -1}, {1, -1},
293 {-1, 0}, {0, 0}, {1, 0},
294 {-1, 1}, {0, 1}, {1, 1}};
295 for (
int i = 0; i < 9; ++i)
301 for (
int point_idx : pointIndicesToCheck) {
302 if (point_idx == curr_index)
305 double dx = other.
x - kp.
x;
306 double dy = other.
y - kp.
y;
307 double dist_sqr = dx*dx + dy*dy;
308 if (dist_sqr <= dist_sqr_threshold)
309 neighbors.push_back(point_idx);
316 return p1.
x < p2.
x || (p1.
x == p2.
x && p1.
y < p2.
y);
324 int n = cluster.size();
329 polygon.points.resize(2*n);
332 for (
int i = 0; i < n; ++i)
334 while (k >= 2 &&
cross(polygon.points[k-2], polygon.points[k-1], cluster[i]) <= 0)
338 cluster[i].toPointMsg(polygon.points[k]);
343 for (
int i = n-2, t = k+1; i >= 0; --i)
345 while (k >= t &&
cross(polygon.points[k-2], polygon.points[k-1], cluster[i]) <= 0)
349 cluster[i].toPointMsg(polygon.points[k]);
354 polygon.points.resize(k);
365 std::vector<KeyPoint>& P = cluster;
366 std::vector<geometry_msgs::Point32>& points = polygon.points;
375 int minmin = 0, minmax;
376 double xmin = P[0].x;
377 for (i = 1; i < (int)P.size(); i++)
378 if (P[i].
x != xmin)
break;
380 if (minmax == (
int)P.size() - 1)
382 points.push_back(geometry_msgs::Point32());
383 P[minmin].toPointMsg(points.back());
384 if (P[minmax].
y != P[minmin].
y)
386 points.push_back(geometry_msgs::Point32());
387 P[minmax].toPointMsg(points.back());
390 points.push_back(geometry_msgs::Point32());
391 P[minmin].toPointMsg(points.back());
396 int maxmin, maxmax = (int)P.size() - 1;
397 double xmax = P.back().x;
398 for (i = P.size() - 2; i >= 0; i--)
399 if (P[i].
x != xmax)
break;
404 points.push_back(geometry_msgs::Point32());
405 P[minmin].toPointMsg(points.back());
407 while (++i <= maxmin)
410 if (
cross(P[minmin], P[maxmin], P[i]) >= 0 && i < maxmin)
413 while (points.size() > 1)
416 if (
cross(points[points.size() - 2], points.back(), P[i]) > 0)
421 points.push_back(geometry_msgs::Point32());
422 P[i].toPointMsg(points.back());
426 if (maxmax != maxmin)
429 points.push_back(geometry_msgs::Point32());
430 P[maxmax].toPointMsg(points.back());
432 int bot = (int)points.size();
434 while (--i >= minmax)
437 if (
cross( P[maxmax], P[minmax], P[i]) >= 0 && i > minmax)
440 while ((
int)points.size() > bot)
443 if (
cross(points[points.size() - 2], points.back(), P[i]) > 0)
448 points.push_back(geometry_msgs::Point32());
449 P[i].toPointMsg(points.back());
451 if (minmax != minmin)
454 points.push_back(geometry_msgs::Point32());
455 P[minmin].toPointMsg(points.back());
463 size_t triangleThreshold = 3;
465 if (polygon.points.size() > 1
466 && std::abs(polygon.points.front().x - polygon.points.back().x) < 1e-5
467 && std::abs(polygon.points.front().y - polygon.points.back().y) < 1e-5)
469 triangleThreshold = 4;
471 if (polygon.points.size() <= triangleThreshold)
480 boost::mutex::scoped_lock lock(
mutex_);
487 boost::mutex::scoped_lock lock(
mutex_);
virtual void updateCostmap2D()
Get updated data from the previously set Costmap2D.
void reconfigureCB(CostmapToPolygonsDBSMCCHConfig &config, uint32_t level)
Callback for the dynamic_reconfigure node.
std::vector< KeyPoint > occupied_cells_
List of occupied cells in the current map (updated by updateCostmap2D())
double min_keypoint_separation_
Clear keypoints of the convex polygon that are close to each other [distance in meters] (0: keep all)...
void pointToNeighborCells(const KeyPoint &kp, int &cx, int &cy)
compute the cell indices of a keypoint
static void convertPointToPolygon(const Point &point, geometry_msgs::Polygon &polygon)
Convert a generi point type to a geometry_msgs::Polygon.
void dbScan(std::vector< std::vector< KeyPoint > > &clusters)
DBSCAN algorithm for clustering.
double offset_y_
offset [meters] in x for the lookup grid
void mapToWorld(unsigned int mx, unsigned int my, double &wx, double &wy) const
void simplifyPolygon(geometry_msgs::Polygon &polygon)
Simplify a polygon by removing points.
void addPoint(double x, double y)
helper function for adding a point to the lookup data structures
virtual void compute()
This method performs the actual work (conversion of the costmap to polygons)
int max_pts_
Parameter for DB_Scan: maximum number of points that define a cluster (to avoid large L- and U-shapes...
PLUGINLIB_EXPORT_CLASS(BAGReader, nodelet::Nodelet)
double getOriginX() const
double getSizeInMetersX() const
int neighbor_size_y_
size of the neighbour lookup in x (number of cells)
TFSIMD_FORCE_INLINE const tfScalar & y() const
double getSizeInMetersY() const
virtual void setCostmap2D(costmap_2d::Costmap2D *costmap)
Pass a pointer to the costap to the plugin.
unsigned char getCost(unsigned int mx, unsigned int my) const
costmap_2d::Costmap2D * costmap_
Pointer to the costmap2d.
int neighbor_size_x_
array of cells for neighbor lookup
int min_pts_
Parameter for DB_Scan: minimum number of points that define a cluster.
boost::mutex parameter_mutex_
Mutex that keeps track about the ownership of the shared polygon instance.
double offset_x_
size of the neighbour lookup in y (number of cells)
double max_distance_
Parameter for DB_Scan, maximum distance to neighbors [m].
bool param(const std::string ¶m_name, T ¶m_val, const T &default_val) const
double computeSquaredDistanceToLineSegment(const Point &point, const LinePoint &line_start, const LinePoint &line_end, bool *is_inbetween=NULL)
Calculate the squared distance between a point and a straight line segment.
This abstract class defines the interface for plugins that convert the costmap into polygon types...
TFSIMD_FORCE_INLINE const tfScalar & x() const
double getOriginY() const
dynamic_reconfigure::Server< CostmapToPolygonsDBSMCCHConfig > * dynamic_recfg_
Dynamic reconfigure server to allow config modifications at runtime.
unsigned int getSizeInCellsY() const
This class converts the costmap_2d into a set of convex polygons (and points)
PolygonContainerPtr polygons_
Current shared container of polygons.
virtual ~CostmapToPolygonsDBSMCCH()
Destructor.
void regionQuery(int curr_index, std::vector< int > &neighbor_indices)
Helper function for dbScan to search for neighboring points.
void convexHull2(std::vector< KeyPoint > &cluster, geometry_msgs::Polygon &polygon)
Compute the convex hull for a single cluster.
unsigned int getSizeInCellsX() const
static const unsigned char LETHAL_OBSTACLE
boost::mutex mutex_
Mutex that keeps track about the ownership of the shared polygon instance.
int neighborCellsToIndex(int cx, int cy)
offset [meters] in y for the lookup grid
bool isXCoordinateSmaller(const CostmapToPolygonsDBSMCCH::KeyPoint &p1, const CostmapToPolygonsDBSMCCH::KeyPoint &p2)
Defines a keypoint in metric coordinates of the map.
void updatePolygonContainer(PolygonContainerPtr polygons)
Thread-safe update of the internal polygon container (that is shared using getPolygons() from outside...
Parameters parameter_buffered_
void convexHull(std::vector< KeyPoint > &cluster, geometry_msgs::Polygon &polygon)
Compute the convex hull for a single cluster (monotone chain algorithm)
PolygonContainerConstPtr getPolygons()
Get a shared instance of the current polygon container.
std::vector< std::vector< int > > neighbor_lookup_
virtual void initialize(ros::NodeHandle nh)
Initialize the plugin.
CostmapToPolygonsDBSMCCH()
Constructor.
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