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 #ifndef COSTMAP_TO_POLYGONS_CONCAVE_H_
00040 #define COSTMAP_TO_POLYGONS_CONCAVE_H_
00041
00042 #include <costmap_converter/costmap_to_polygons.h>
00043 #include <costmap_converter/misc.h>
00044
00045
00046 #include <costmap_converter/CostmapToPolygonsDBSConcaveHullConfig.h>
00047 #include <dynamic_reconfigure/server.h>
00048
00049
00050 namespace costmap_converter
00051 {
00052
00060 class CostmapToPolygonsDBSConcaveHull : public CostmapToPolygonsDBSMCCH
00061 {
00062 public:
00063
00064
00065
00069 CostmapToPolygonsDBSConcaveHull();
00070
00074 virtual ~CostmapToPolygonsDBSConcaveHull();
00075
00080 virtual void initialize(ros::NodeHandle nh);
00081
00082
00086 virtual void compute();
00087
00088 protected:
00089
00090
00099 void concaveHull(std::vector<KeyPoint>& cluster, double depth, geometry_msgs::Polygon& polygon);
00100
00101 void concaveHullClusterCut(std::vector<KeyPoint>& cluster, double depth, geometry_msgs::Polygon& polygon);
00102
00103 template <typename PointLine, typename PointCluster, typename PointHull>
00104 std::size_t findNearestInnerPoint(PointLine line_start, PointLine line_end, const std::vector<PointCluster>& cluster, const std::vector<PointHull>& hull, bool* found);
00105
00106
00107 template <typename Point1, typename Point2, typename Point3, typename Point4>
00108 bool checkLineIntersection(const Point1& line1_start, const Point2& line1_end, const Point3& line2_start, const Point4& line2_end);
00109
00110 template <typename PointHull, typename Point1, typename Point2, typename Point3, typename Point4>
00111 bool checkLineIntersection(const std::vector<PointHull>& hull, const Point1& current_line_start,
00112 const Point2& current_line_end, const Point3& test_line_start, const Point4& test_line_end);
00113
00114 double concave_hull_depth_;
00115
00116 private:
00117
00125 void reconfigureCB(CostmapToPolygonsDBSConcaveHullConfig& config, uint32_t level);
00126
00127 dynamic_reconfigure::Server<CostmapToPolygonsDBSConcaveHullConfig>* dynamic_recfg_;
00128
00129
00130 };
00131
00132
00133 template <typename PointLine, typename PointCluster, typename PointHull>
00134 std::size_t CostmapToPolygonsDBSConcaveHull::findNearestInnerPoint(PointLine line_start, PointLine line_end, const std::vector<PointCluster>& cluster, const std::vector<PointHull>& hull, bool* found)
00135 {
00136 std::size_t nearsest_idx = 0;
00137 double distance = 0;
00138 *found = false;
00139
00140 for (std::size_t i = 0; i < cluster.size(); ++i)
00141 {
00142
00143 if (std::find_if( hull.begin(), hull.end(), boost::bind(isApprox2d<PointHull, PointCluster>, _1, boost::cref(cluster[i]), 1e-5) ) != hull.end() )
00144 continue;
00145
00146 double dist = computeDistanceToLineSegment(cluster[i], line_start, line_end);
00147 bool skip = false;
00148 for (int j = 0; !skip && j < (int)hull.size() - 1; ++j)
00149 {
00150 double dist_temp = computeDistanceToLineSegment(cluster[i], hull[j], hull[j + 1]);
00151 skip |= dist_temp < dist;
00152 }
00153 if (skip)
00154 continue;
00155
00156 if (!(*found) || dist < distance)
00157 {
00158 nearsest_idx = i;
00159 distance = dist;
00160 *found = true;
00161 }
00162 }
00163 return nearsest_idx;
00164 }
00165
00166
00167 template <typename Point1, typename Point2, typename Point3, typename Point4>
00168 bool CostmapToPolygonsDBSConcaveHull::checkLineIntersection(const Point1& line1_start, const Point2& line1_end, const Point3& line2_start, const Point4& line2_end)
00169 {
00170 double dx1 = line1_end.x - line1_start.x;
00171 double dy1 = line1_end.y - line1_start.y;
00172 double dx2 = line2_end.x - line2_start.x;
00173 double dy2 = line2_end.y - line2_start.y;
00174 double s = (-dy1 * (line1_start.x - line2_start.x) + dx1 * (line1_start.y - line2_start.y)) / (-dx2 * dy1 + dx1 * dy2);
00175 double t = ( dx2 * (line1_start.y - line2_start.y) - dy2 * (line1_start.x - line2_start.x)) / (-dx2 * dy1 + dx1 * dy2);
00176 return (s > 0 && s < 1 && t > 0 && t < 1);
00177 }
00178
00179
00180 template <typename PointHull, typename Point1, typename Point2, typename Point3, typename Point4>
00181 bool CostmapToPolygonsDBSConcaveHull::checkLineIntersection(const std::vector<PointHull>& hull, const Point1& current_line_start,
00182 const Point2& current_line_end, const Point3& test_line_start, const Point4& test_line_end)
00183 {
00184 for (int i = 0; i < (int)hull.size() - 2; i++)
00185 {
00186 if (isApprox2d(current_line_start, hull[i], 1e-5) && isApprox2d(current_line_end, hull[i+1], 1e-5))
00187 {
00188 continue;
00189 }
00190
00191 if (checkLineIntersection(test_line_start, test_line_end, hull[i], hull[i+1]))
00192 {
00193 return true;
00194 }
00195 }
00196 return false;
00197 }
00198
00199
00200 }
00201
00202 #endif