costmap_to_polygons_concave.h
Go to the documentation of this file.
1 /*********************************************************************
2  *
3  * Software License Agreement (BSD License)
4  *
5  * Copyright (c) 2016,
6  * TU Dortmund - Institute of Control Theory and Systems Engineering.
7  * All rights reserved.
8  *
9  * Redistribution and use in source and binary forms, with or without
10  * modification, are permitted provided that the following conditions
11  * are met:
12  *
13  * * Redistributions of source code must retain the above copyright
14  * notice, this list of conditions and the following disclaimer.
15  * * Redistributions in binary form must reproduce the above
16  * copyright notice, this list of conditions and the following
17  * disclaimer in the documentation and/or other materials provided
18  * with the distribution.
19  * * Neither the name of the institute nor the names of its
20  * contributors may be used to endorse or promote products derived
21  * from this software without specific prior written permission.
22  *
23  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
24  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
25  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
26  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
27  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
28  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
29  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
30  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
31  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
32  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
33  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
34  * POSSIBILITY OF SUCH DAMAGE.
35  *
36  * Author: Christoph Rösmann
37  *********************************************************************/
38 
39 #ifndef COSTMAP_TO_POLYGONS_CONCAVE_H_
40 #define COSTMAP_TO_POLYGONS_CONCAVE_H_
41 
43 #include <costmap_converter/misc.h>
44 
45 // dynamic reconfigure
46 #include <costmap_converter/CostmapToPolygonsDBSConcaveHullConfig.h>
47 #include <dynamic_reconfigure/server.h>
48 
49 
50 namespace costmap_converter
51 {
52 
61 {
62  public:
63 
64 
65 
70 
75 
80  virtual void initialize(ros::NodeHandle nh);
81 
82 
86  virtual void compute();
87 
88  protected:
89 
90 
99  void concaveHull(std::vector<KeyPoint>& cluster, double depth, geometry_msgs::Polygon& polygon);
100 
101  void concaveHullClusterCut(std::vector<KeyPoint>& cluster, double depth, geometry_msgs::Polygon& polygon);
102 
103  template <typename PointLine, typename PointCluster, typename PointHull>
104  std::size_t findNearestInnerPoint(PointLine line_start, PointLine line_end, const std::vector<PointCluster>& cluster, const std::vector<PointHull>& hull, bool* found);
105 
106 
107  template <typename Point1, typename Point2, typename Point3, typename Point4>
108  bool checkLineIntersection(const Point1& line1_start, const Point2& line1_end, const Point3& line2_start, const Point4& line2_end);
109 
110  template <typename PointHull, typename Point1, typename Point2, typename Point3, typename Point4>
111  bool checkLineIntersection(const std::vector<PointHull>& hull, const Point1& current_line_start,
112  const Point2& current_line_end, const Point3& test_line_start, const Point4& test_line_end);
113 
115 
116  private:
117 
125  void reconfigureCB(CostmapToPolygonsDBSConcaveHullConfig& config, uint32_t level);
126 
127  dynamic_reconfigure::Server<CostmapToPolygonsDBSConcaveHullConfig>* dynamic_recfg_;
128 
129 
130 };
131 
132 
133 template <typename PointLine, typename PointCluster, typename PointHull>
134 std::size_t CostmapToPolygonsDBSConcaveHull::findNearestInnerPoint(PointLine line_start, PointLine line_end, const std::vector<PointCluster>& cluster, const std::vector<PointHull>& hull, bool* found)
135 {
136  std::size_t nearsest_idx = 0;
137  double distance = 0;
138  *found = false;
139 
140  for (std::size_t i = 0; i < cluster.size(); ++i)
141  {
142  // Skip points that are already in the hull
143  if (std::find_if( hull.begin(), hull.end(), boost::bind(isApprox2d<PointHull, PointCluster>, _1, boost::cref(cluster[i]), 1e-5) ) != hull.end() )
144  continue;
145 
146  double dist = computeDistanceToLineSegment(cluster[i], line_start, line_end);
147  bool skip = false;
148  for (int j = 0; !skip && j < (int)hull.size() - 1; ++j)
149  {
150  double dist_temp = computeDistanceToLineSegment(cluster[i], hull[j], hull[j + 1]);
151  skip |= dist_temp < dist;
152  }
153  if (skip)
154  continue;
155 
156  if (!(*found) || dist < distance)
157  {
158  nearsest_idx = i;
159  distance = dist;
160  *found = true;
161  }
162  }
163  return nearsest_idx;
164 }
165 
166 
167 template <typename Point1, typename Point2, typename Point3, typename Point4>
168 bool CostmapToPolygonsDBSConcaveHull::checkLineIntersection(const Point1& line1_start, const Point2& line1_end, const Point3& line2_start, const Point4& line2_end)
169 {
170  double dx1 = line1_end.x - line1_start.x;
171  double dy1 = line1_end.y - line1_start.y;
172  double dx2 = line2_end.x - line2_start.x;
173  double dy2 = line2_end.y - line2_start.y;
174  double s = (-dy1 * (line1_start.x - line2_start.x) + dx1 * (line1_start.y - line2_start.y)) / (-dx2 * dy1 + dx1 * dy2);
175  double t = ( dx2 * (line1_start.y - line2_start.y) - dy2 * (line1_start.x - line2_start.x)) / (-dx2 * dy1 + dx1 * dy2);
176  return (s > 0 && s < 1 && t > 0 && t < 1);
177 }
178 
179 
180 template <typename PointHull, typename Point1, typename Point2, typename Point3, typename Point4>
181 bool CostmapToPolygonsDBSConcaveHull::checkLineIntersection(const std::vector<PointHull>& hull, const Point1& current_line_start,
182  const Point2& current_line_end, const Point3& test_line_start, const Point4& test_line_end)
183 {
184  for (int i = 0; i < (int)hull.size() - 2; i++)
185  {
186  if (isApprox2d(current_line_start, hull[i], 1e-5) && isApprox2d(current_line_end, hull[i+1], 1e-5))
187  {
188  continue;
189  }
190 
191  if (checkLineIntersection(test_line_start, test_line_end, hull[i], hull[i+1]))
192  {
193  return true;
194  }
195  }
196  return false;
197 }
198 
199 
200 } //end namespace teb_local_planner
201 
202 #endif /* COSTMAP_TO_POLYGONS_CONCAVE_H_ */
virtual void initialize(ros::NodeHandle nh)
Initialize the plugin.
void concaveHullClusterCut(std::vector< KeyPoint > &cluster, double depth, geometry_msgs::Polygon &polygon)
double computeDistanceToLineSegment(const Point &point, const LinePoint &line_start, const LinePoint &line_end, bool *is_inbetween=NULL)
Calculate the distance between a point and a straight line segment.
Definition: misc.h:118
XmlRpcServer s
This class converts the costmap_2d into a set of non-convex polygons (and points) ...
bool checkLineIntersection(const Point1 &line1_start, const Point2 &line1_end, const Point3 &line2_start, const Point4 &line2_end)
virtual void compute()
This method performs the actual work (conversion of the costmap to polygons)
void reconfigureCB(CostmapToPolygonsDBSConcaveHullConfig &config, uint32_t level)
Callback for the dynamic_reconfigure node.
double distance(double x0, double y0, double x1, double y1)
dynamic_reconfigure::Server< CostmapToPolygonsDBSConcaveHullConfig > * dynamic_recfg_
Dynamic reconfigure server to allow config modifications at runtime.
std::size_t findNearestInnerPoint(PointLine line_start, PointLine line_end, const std::vector< PointCluster > &cluster, const std::vector< PointHull > &hull, bool *found)
void concaveHull(std::vector< KeyPoint > &cluster, double depth, geometry_msgs::Polygon &polygon)
Compute the concave hull for a single cluster.
This class converts the costmap_2d into a set of convex polygons (and points)
bool isApprox2d(const Point1 &pt1, const Point2 &pt2, double threshold)
Check if two points are approximately defining the same one.
Definition: misc.h:148


costmap_converter
Author(s): Christoph Rösmann , Franz Albers , Otniel Rinaldo
autogenerated on Sat May 16 2020 03:19:18