Autoware.Auto
hull_pockets.hpp
Go to the documentation of this file.
1 // Copyright 2020 Embotech AG, Zurich, Switzerland. All rights reserved.
2 //
3 // Licensed under the Apache License, Version 2.0 (the "License");
4 // you may not use this file except in compliance with the License.
5 // You may obtain a copy of the License at
6 //
7 //    http://www.apache.org/licenses/LICENSE-2.0
8 //
9 // Unless required by applicable law or agreed to in writing, software
10 // distributed under the License is distributed on an "AS IS" BASIS,
11 // WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
12 // See the License for the specific language governing permissions and
13 // limitations under the License.
14 
18 
19 #ifndef GEOMETRY__HULL_POCKETS_HPP_
20 #define GEOMETRY__HULL_POCKETS_HPP_
21 
22 #include <common/types.hpp>
23 #include <geometry/common_2d.hpp>
24 #include <vector>
25 #include <utility>
26 #include <limits>
27 #include <algorithm>
28 #include <iterator>
29 
31 
32 namespace autoware
33 {
34 namespace common
35 {
36 namespace geometry
37 {
38 
39 
44 // * "Rollover" is not properly handled - if a pocket contains the segment from
45 // the last point in the list to the first point (which is still part of the
46 // polygon), that does not get added
60 template<typename Iter1, typename Iter2>
61 typename std::vector<std::vector<typename std::iterator_traits<Iter1>::value_type>> hull_pockets(
62  const Iter1 polygon_start,
63  const Iter1 polygon_end,
64  const Iter2 convex_hull_start,
65  const Iter2 convex_hull_end
66 )
67 {
68  auto pockets = std::vector<std::vector<typename std::iterator_traits<Iter1>::value_type>>{};
69  if (std::distance(polygon_start, polygon_end) <= 3) {
70  return pockets;
71  }
72 
73  // Function to check whether a point is in the convex hull.
74  const auto in_convex_hull = [convex_hull_start, convex_hull_end](Iter1 p) {
75  return std::any_of(
76  convex_hull_start, convex_hull_end, [p](auto hull_entry)
77  {
78  return norm_2d(
79  minus_2d(
80  hull_entry,
81  *p)) < std::numeric_limits<float32_t>::epsilon();
82  });
83  };
84 
85  // We go through the points of the polygon only once, adding pockets to the list of pockets
86  // as we detect them.
87  std::vector<typename std::iterator_traits<Iter1>::value_type> current_pocket{};
88  for (auto it = polygon_start; it != polygon_end; it = std::next(it)) {
89  if (in_convex_hull(it)) {
90  if (current_pocket.size() > 1) {
91  current_pocket.emplace_back(*it);
92  pockets.push_back(current_pocket);
93  }
94  current_pocket.clear();
95  current_pocket.emplace_back(*it);
96  } else {
97  current_pocket.emplace_back(*it);
98  }
99  }
100 
101  // At this point, we have reached the end of the polygon, but have not considered the connection
102  // of the final point back to the first. In case the first point is part of a pocket as well, we
103  // have some points left in current_pocket, and we add one final pocket that is made up by those
104  // points plus the first point in the collection.
105  if (current_pocket.size() > 1) {
106  current_pocket.push_back(*polygon_start);
107  pockets.push_back(current_pocket);
108  }
109 
110  return pockets;
111 }
112 } // namespace geometry
113 } // namespace common
114 } // namespace autoware
115 
116 #endif // GEOMETRY__HULL_POCKETS_HPP_
This file includes common functionality for 2D geometry, such as dot products.
float float32_t
Definition: types.hpp:36
std::vector< std::vector< typename std::iterator_traits< Iter1 >::value_type > > hull_pockets(const Iter1 polygon_start, const Iter1 polygon_end, const Iter2 convex_hull_start, const Iter2 convex_hull_end)
Compute a list of "pockets" of a simple polygon (https://en.wikipedia.org/wiki/Simple_polygon), that is, the areas that make up the difference between the polygon and its convex hull. This currently has a bug:
Definition: hull_pockets.hpp:61
This file includes common type definition.
auto norm_2d(const T &pt)
get magnitude of x and y components:
Definition: common_2d.hpp:278
T minus_2d(const T &p, const T &q)
Compute the 2d difference between two points, p - q.
Definition: common_2d.hpp:145
This file defines the lanelet2_map_provider_node class.
Definition: quick_sort.hpp:24