41 #include <boost/thread.hpp>
42 #include <boost/thread/mutex.hpp>
77 dynamic_recfg_ =
new dynamic_reconfigure::Server<CostmapToLinesDBSMCCHConfig>(nh);
82 if (nh.
hasParam(
"support_pts_min_dist_") || nh.
hasParam(
"support_pts_min_dist"))
83 ROS_WARN(
"CostmapToLinesDBSMCCH: Parameter 'support_pts_min_dist' is deprecated and not included anymore.");
85 ROS_WARN(
"CostmapToLinesDBSMCCH: Parameter 'min_support_pts_' is not found. Remove the underscore.");
90 std::vector< std::vector<KeyPoint> > clusters;
98 for (
int i = 1; i <clusters.size(); ++i)
100 geometry_msgs::Polygon polygon;
109 if (!clusters.empty())
111 for (
int i=0; i < clusters.front().size(); ++i)
113 polygons->push_back( geometry_msgs::Polygon() );
122 typedef CostmapToLinesDBSMCCH
CL;
123 bool sort_keypoint_x(
const std::size_t& i,
const std::size_t& j,
const std::vector<CL::KeyPoint>& cluster)
124 {
return (cluster[i].x<cluster[j].x) || (cluster[i].x == cluster[j].x && cluster[i].y < cluster[j].y); }
125 bool sort_keypoint_y(
const std::size_t& i,
const std::size_t& j,
const std::vector<CL::KeyPoint>& cluster)
126 {
return (cluster[i].y<cluster[j].y) || (cluster[i].y == cluster[j].y && cluster[i].x < cluster[j].x); }
129 std::back_insert_iterator< std::vector<geometry_msgs::Polygon> > lines)
131 if (polygon.points.empty())
134 if (polygon.points.size() < 2)
139 int n = (int)polygon.points.size();
141 for (
int i=1; i<n; ++i)
143 const geometry_msgs::Point32* vertex1 = &polygon.points[i-1];
144 const geometry_msgs::Point32* vertex2 = &polygon.points[i];
148 double dx = vertex2->x - vertex1->x;
149 double dy = vertex2->y - vertex1->y;
170 std::vector<std::size_t> support_points;
172 for (std::size_t k = 0; k < cluster.size(); ++k)
174 bool is_inbetween =
false;
179 support_points.push_back(k);
192 if (std::abs(dx) >= std::abs(dy))
193 std::sort(support_points.begin(), support_points.end(), boost::bind(
sort_keypoint_x, _1, _2, boost::cref(cluster)));
195 std::sort(support_points.begin(), support_points.end(), boost::bind(
sort_keypoint_y, _1, _2, boost::cref(cluster)));
198 for (
int k = 1; k < int(support_points.size()); ++k)
200 double dist_x = cluster[support_points[k]].x - cluster[support_points[k-1]].x;
201 double dist_y = cluster[support_points[k]].y - cluster[support_points[k-1]].y;
202 double dist = std::sqrt( dist_x*dist_x + dist_y*dist_y);
218 geometry_msgs::Polygon line;
219 line.points.push_back(*vertex1);
220 line.points.push_back(*vertex2);
225 std::vector<std::size_t>::reverse_iterator support_it = support_points.rbegin();
226 for (; support_it != support_points.rend(); ++support_it)
228 cluster.erase(cluster.begin() + *support_it);
251 std::vector<std::size_t>::reverse_iterator support_it = support_points.rbegin();
252 for (; support_it != support_points.rend(); ++support_it)
254 geometry_msgs::Polygon polygon;
258 cluster.erase(cluster.begin() + *support_it);
264 for (
int i=0; i<(int)cluster.size();++i)
266 geometry_msgs::Polygon polygon;