00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00035
00036
00037
00038
00039 #include <costmap_converter/costmap_to_lines_convex_hull.h>
00040 #include <costmap_converter/misc.h>
00041 #include <boost/thread.hpp>
00042 #include <boost/thread/mutex.hpp>
00043 #include <pluginlib/class_list_macros.h>
00044
00045 PLUGINLIB_EXPORT_CLASS(costmap_converter::CostmapToLinesDBSMCCH, costmap_converter::BaseCostmapToPolygons)
00046
00047 namespace costmap_converter
00048 {
00049
00050 CostmapToLinesDBSMCCH::CostmapToLinesDBSMCCH() : CostmapToPolygonsDBSMCCH()
00051 {
00052 dynamic_recfg_ = NULL;
00053 }
00054
00055 CostmapToLinesDBSMCCH::~CostmapToLinesDBSMCCH()
00056 {
00057 if (dynamic_recfg_ != NULL)
00058 delete dynamic_recfg_;
00059 }
00060
00061 void CostmapToLinesDBSMCCH::initialize(ros::NodeHandle nh)
00062 {
00063
00064 max_distance_ = 0.4;
00065 nh.param("cluster_max_distance", max_distance_, max_distance_);
00066
00067 min_pts_ = 2;
00068 nh.param("cluster_min_pts", min_pts_, min_pts_);
00069
00070 max_pts_ = 30;
00071 nh.param("cluster_max_pts", max_pts_, max_pts_);
00072
00073
00074 min_keypoint_separation_ = 0.1;
00075 nh.param("convex_hull_min_pt_separation", min_keypoint_separation_, min_keypoint_separation_);
00076
00077
00078 support_pts_max_dist_ = 0.3;
00079 nh.param("support_pts_max_dist", support_pts_max_dist_, support_pts_max_dist_);
00080
00081 support_pts_max_dist_inbetween_ = 1.0;
00082 nh.param("support_pts_max_dist_inbetween", support_pts_max_dist_inbetween_, support_pts_max_dist_inbetween_);
00083
00084 min_support_pts_ = 2;
00085 nh.param("min_support_pts", min_support_pts_, min_support_pts_);
00086
00087
00088 dynamic_recfg_ = new dynamic_reconfigure::Server<CostmapToLinesDBSMCCHConfig>(nh);
00089 dynamic_reconfigure::Server<CostmapToLinesDBSMCCHConfig>::CallbackType cb = boost::bind(&CostmapToLinesDBSMCCH::reconfigureCB, this, _1, _2);
00090 dynamic_recfg_->setCallback(cb);
00091
00092
00093 if (nh.hasParam("support_pts_min_dist_") || nh.hasParam("support_pts_min_dist"))
00094 ROS_WARN("CostmapToLinesDBSMCCH: Parameter 'support_pts_min_dist' is deprecated and not included anymore.");
00095 if (nh.hasParam("min_support_pts_"))
00096 ROS_WARN("CostmapToLinesDBSMCCH: Parameter 'min_support_pts_' is not found. Remove the underscore.");
00097 }
00098
00099 void CostmapToLinesDBSMCCH::compute()
00100 {
00101 std::vector< std::vector<KeyPoint> > clusters;
00102 dbScan(occupied_cells_, clusters);
00103
00104
00105 PolygonContainerPtr polygons(new std::vector<geometry_msgs::Polygon>());
00106
00107
00108
00109 for (int i = 1; i <clusters.size(); ++i)
00110 {
00111 geometry_msgs::Polygon polygon;
00112 convexHull2(clusters[i], polygon );
00113
00114
00115
00116 extractPointsAndLines(clusters[i], polygon, std::back_inserter(*polygons));
00117 }
00118
00119
00120 if (!clusters.empty())
00121 {
00122 for (int i=0; i < clusters.front().size(); ++i)
00123 {
00124 polygons->push_back( geometry_msgs::Polygon() );
00125 convertPointToPolygon(clusters.front()[i], polygons->back());
00126 }
00127 }
00128
00129
00130 updatePolygonContainer(polygons);
00131 }
00132
00133 typedef CostmapToLinesDBSMCCH CL;
00134 bool sort_keypoint_x(const std::size_t& i, const std::size_t& j, const std::vector<CL::KeyPoint>& cluster)
00135 { return (cluster[i].x<cluster[j].x) || (cluster[i].x == cluster[j].x && cluster[i].y < cluster[j].y); }
00136 bool sort_keypoint_y(const std::size_t& i, const std::size_t& j, const std::vector<CL::KeyPoint>& cluster)
00137 { return (cluster[i].y<cluster[j].y) || (cluster[i].y == cluster[j].y && cluster[i].x < cluster[j].x); }
00138
00139 void CostmapToLinesDBSMCCH::extractPointsAndLines(std::vector<KeyPoint>& cluster, const geometry_msgs::Polygon& polygon,
00140 std::back_insert_iterator< std::vector<geometry_msgs::Polygon> > lines)
00141 {
00142 if (polygon.points.empty())
00143 return;
00144
00145 if (polygon.points.size() < 2)
00146 {
00147 lines = polygon;
00148 return;
00149 }
00150 int n = (int)polygon.points.size();
00151
00152 for (int i=1; i<n; ++i)
00153 {
00154 const geometry_msgs::Point32* vertex1 = &polygon.points[i-1];
00155 const geometry_msgs::Point32* vertex2 = &polygon.points[i];
00156
00157
00158
00159 double dx = vertex2->x - vertex1->x;
00160 double dy = vertex2->y - vertex1->y;
00161
00162
00163
00164
00165
00166
00167
00168
00169
00170
00171
00172
00173
00174
00175
00176
00177
00178
00179
00180
00181 std::vector<std::size_t> support_points;
00182
00183 for (std::size_t k = 0; k < cluster.size(); ++k)
00184 {
00185 bool is_inbetween = false;
00186 double dist_line_to_point = computeDistanceToLineSegment( cluster[k], *vertex1, *vertex2, &is_inbetween );
00187
00188 if(is_inbetween && dist_line_to_point <= support_pts_max_dist_)
00189 {
00190 support_points.push_back(k);
00191 continue;
00192 }
00193 }
00194
00195
00196
00197 bool is_line=true;
00198 if (support_pts_max_dist_inbetween_!=0)
00199 {
00200 if ((int)support_points.size() >= min_support_pts_ + 2)
00201 {
00202
00203 if (std::abs(dx) >= std::abs(dy))
00204 std::sort(support_points.begin(), support_points.end(), boost::bind(sort_keypoint_x, _1, _2, boost::cref(cluster)));
00205 else
00206 std::sort(support_points.begin(), support_points.end(), boost::bind(sort_keypoint_y, _1, _2, boost::cref(cluster)));
00207
00208
00209 for (int k = 1; k < int(support_points.size()); ++k)
00210 {
00211 double dist_x = cluster[support_points[k]].x - cluster[support_points[k-1]].x;
00212 double dist_y = cluster[support_points[k]].y - cluster[support_points[k-1]].y;
00213 double dist = std::sqrt( dist_x*dist_x + dist_y*dist_y);
00214 if (dist > support_pts_max_dist_inbetween_)
00215 {
00216 is_line = false;
00217 break;
00218 }
00219 }
00220
00221 }
00222 else
00223 is_line = false;
00224 }
00225
00226 if (is_line)
00227 {
00228
00229 geometry_msgs::Polygon line;
00230 line.points.push_back(*vertex1);
00231 line.points.push_back(*vertex2);
00232 lines = line;
00233
00234
00235
00236 std::vector<std::size_t>::reverse_iterator support_it = support_points.rbegin();
00237 for (; support_it != support_points.rend(); ++support_it)
00238 {
00239 cluster.erase(cluster.begin() + *support_it);
00240 }
00241 }
00242 else
00243 {
00244
00245
00246
00247
00248
00249
00250
00251
00252
00253
00254
00255
00256
00257
00258
00259
00260
00261
00262 std::vector<std::size_t>::reverse_iterator support_it = support_points.rbegin();
00263 for (; support_it != support_points.rend(); ++support_it)
00264 {
00265 geometry_msgs::Polygon polygon;
00266 convertPointToPolygon(cluster[*support_it], polygon);
00267 lines = polygon;
00268
00269 cluster.erase(cluster.begin() + *support_it);
00270 }
00271 }
00272 }
00273
00274
00275 for (int i=0; i<(int)cluster.size();++i)
00276 {
00277 geometry_msgs::Polygon polygon;
00278 convertPointToPolygon(cluster[i], polygon);
00279 lines = polygon;
00280 }
00281
00282 }
00283
00284 void CostmapToLinesDBSMCCH::reconfigureCB(CostmapToLinesDBSMCCHConfig& config, uint32_t level)
00285 {
00286 max_distance_ = config.cluster_max_distance;
00287 min_pts_ = config.cluster_min_pts;
00288 max_pts_ = config.cluster_max_pts;
00289 min_keypoint_separation_ = config.cluster_min_pts;
00290 support_pts_max_dist_ = config.support_pts_max_dist;
00291 support_pts_max_dist_inbetween_ = config.support_pts_max_dist_inbetween;
00292 min_support_pts_ = config.min_support_pts;
00293 }
00294
00295
00296
00297 }
00298
00299