19 #ifndef GEOMETRY__HULL_POCKETS_HPP_ 20 #define GEOMETRY__HULL_POCKETS_HPP_ 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
68 auto pockets = std::vector<std::vector<typename std::iterator_traits<Iter1>::value_type>>{};
69 if (std::distance(polygon_start, polygon_end) <= 3) {
74 const auto in_convex_hull = [convex_hull_start, convex_hull_end](Iter1 p) {
76 convex_hull_start, convex_hull_end, [p](
auto hull_entry)
81 *p)) < std::numeric_limits<float32_t>::epsilon();
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);
94 current_pocket.clear();
95 current_pocket.emplace_back(*it);
97 current_pocket.emplace_back(*it);
105 if (current_pocket.size() > 1) {
106 current_pocket.push_back(*polygon_start);
107 pockets.push_back(current_pocket);
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