costmap_to_polygons_concave.h
Go to the documentation of this file.
00001 /*********************************************************************
00002  *
00003  * Software License Agreement (BSD License)
00004  *
00005  *  Copyright (c) 2016,
00006  *  TU Dortmund - Institute of Control Theory and Systems Engineering.
00007  *  All rights reserved.
00008  *
00009  *  Redistribution and use in source and binary forms, with or without
00010  *  modification, are permitted provided that the following conditions
00011  *  are met:
00012  *
00013  *   * Redistributions of source code must retain the above copyright
00014  *     notice, this list of conditions and the following disclaimer.
00015  *   * Redistributions in binary form must reproduce the above
00016  *     copyright notice, this list of conditions and the following
00017  *     disclaimer in the documentation and/or other materials provided
00018  *     with the distribution.
00019  *   * Neither the name of the institute nor the names of its
00020  *     contributors may be used to endorse or promote products derived
00021  *     from this software without specific prior written permission.
00022  *
00023  *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00024  *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00025  *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00026  *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00027  *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00028  *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00029  *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00030  *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00031  *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00032  *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00033  *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00034  *  POSSIBILITY OF SUCH DAMAGE.
00035  *
00036  * Author: Christoph Rösmann
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 // dynamic reconfigure
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         // Skip points that are already in the hull
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 } //end namespace teb_local_planner
00201 
00202 #endif /* COSTMAP_TO_POLYGONS_CONCAVE_H_ */


costmap_converter
Author(s): Christoph Rösmann , Franz Albers , Otniel Rinaldo
autogenerated on Sat Jun 8 2019 20:53:15