primitives/Polygon.h
Go to the documentation of this file.
1 #pragma once
2 
6 
7 namespace lanelet {
8 
19  public:
20  explicit BasicPolygon2d(const BasicLineString2d& other) : BasicLineString2d(other) {}
26  BasicPolygon2d() = default;
27 };
28 
39  public:
40  explicit BasicPolygon3d(const BasicLineString3d& other) : BasicLineString3d(other) {}
46  BasicPolygon3d() = default;
47 };
48 
75 
82 class ConstPolygon2d : public ConstLineStringImpl<Point2d> {
83  public:
91 
99  explicit ConstPolygon2d(const ConstLineString2d& other) : ConstLineStringImpl(other) {}
100  explicit operator ConstLineString2d() const { return ConstLineString2d(constData(), inverted()); }
101 
102  ConstPolygon2d() = default;
103 
105  BasicPolygon2d basicPolygon() const { return {basicBegin(), basicEnd()}; }
106 
108  operator BasicPolygon2d() const { // NOLINT
109  return {basicBegin(), basicEnd()};
110  }
111 
113  size_t numSegments() const noexcept { return size() < 2 ? 0 : size(); }
114 };
115 
122 class ConstPolygon3d : public ConstLineStringImpl<Point3d> {
123  public:
131 
132  ConstPolygon3d() = default;
133 
136  explicit ConstPolygon3d(const ConstLineString3d& other) : ConstLineStringImpl(other) {}
137  explicit operator ConstLineString3d() const { return ConstLineString3d(constData(), inverted()); }
138 
140  BasicPolygon3d basicPolygon() const { return {basicBegin(), basicEnd()}; }
141 
143  operator BasicPolygon3d() const { // NOLINT
144  return {basicBegin(), basicEnd()};
145  }
146 
148  size_t numSegments() const noexcept { return size() < 2 ? 0 : size(); }
149 };
150 
157 class Polygon3d : public LineStringImpl<ConstPolygon3d> {
158  public:
164 
165  Polygon3d() = default; // gcc5 needs this
166 
168  explicit Polygon3d(const LineString3d& other) : LineStringImpl(other) {}
169  explicit operator LineString3d() const { return LineString3d(data(), inverted()); }
170 
171  friend class Polygon2d;
172 
174  BasicPolygon3d basicPolygon() const { return {basicBegin(), basicEnd()}; }
175 
177  operator BasicPolygon3d() const { // NOLINT
178  return {basicBegin(), basicEnd()};
179  }
180 };
181 
188 class Polygon2d : public LineStringImpl<ConstPolygon2d> {
189  public:
195 
196  Polygon2d() = default;
197 
199  explicit Polygon2d(const LineString2d& other) : LineStringImpl(other) {}
200  explicit operator LineString2d() const { return LineString2d(data(), inverted()); }
201 
205  inline BasicPolygon2d basicPolygon() const {
206  BasicPolygon2d::allocator_type alloc; // gcc produces undef refs otherwise
207  return BasicPolygon2d(basicBegin(), basicEnd(), alloc);
208  }
209  inline operator BasicPolygon2d() const { // NOLINT
210  return BasicPolygon2d(basicBegin(), basicEnd());
211  }
212  friend class Polygon3d;
213 };
214 
229  public:
230  using const_iterator = BasicIterator; // NOLINT
231  using iterator = BasicIterator; // NOLINT
232 
238 
239  ConstHybridPolygon3d() = default;
240 
242  explicit ConstHybridPolygon3d(const ConstPolygon3d& poly) : ConstPolygon3d(poly) {}
243 
245  BasicIterator begin() const noexcept { return basicBegin(); }
246 
248  BasicIterator end() const noexcept { return basicEnd(); }
249 
251  const BasicPointType& front() const noexcept { return ConstPolygon3d::front().basicPoint(); }
252 
254  const BasicPointType& back() const noexcept { return ConstPolygon3d::back().basicPoint(); }
255 
257  const BasicPointType& operator[](size_t idx) const noexcept { return ConstPolygon3d::operator[](idx).basicPoint(); }
258 };
259 
274  public:
275  using const_iterator = BasicIterator; // NOLINT
276  using iterator = BasicIterator; // NOLINT
277 
284 
285  ConstHybridPolygon2d() = default;
286 
288  explicit ConstHybridPolygon2d(const ConstPolygon2d& poly) : ConstPolygon2d(poly) {}
289 
291  BasicIterator begin() const noexcept { return basicBegin(); }
292 
294  BasicIterator end() const noexcept { return basicEnd(); }
295 
297  BasicPointType front() const noexcept { return ConstPolygon2d::front().basicPoint(); }
298 
300  BasicPointType back() const noexcept { return ConstPolygon2d::back().basicPoint(); }
301 
303  BasicPointType operator[](size_t idx) const noexcept { return ConstPolygon2d::operator[](idx).basicPoint(); }
304 };
305 
314  public:
317 };
318 
327  public:
330 };
331 
332 inline std::ostream& operator<<(std::ostream& stream, const ConstPolygon2d& obj) {
333  return stream << ConstLineString2d(obj);
334 }
335 
336 inline std::ostream& operator<<(std::ostream& stream, const ConstPolygon3d& obj) {
337  return stream << ConstLineString2d(obj);
338 }
339 
340 namespace internal {
341 
342 template <>
343 class Converter<const ConstPolygon3d> {
344  public:
345  template <typename T>
346  const ConstPolygon3d& convert(const T& t) const {
347  val_ = t;
348  return val_;
349  }
350 
351  private:
353 };
354 template <>
355 class Converter<const ConstPolygon2d> {
356  public:
357  template <typename T>
358  const ConstPolygon2d& convert(const T& t) const {
359  val_ = t;
360  return val_;
361  }
362 
363  private:
365 };
366 } // namespace internal
367 
368 namespace traits {
369 template <typename T>
370 constexpr bool isPolygonT() {
371  return isCategory<T, traits::PolygonTag>();
372 }
373 
374 template <>
381 };
382 template <>
389 };
390 template <>
392  BasicPolygon2d p2d(primitive.size());
393  std::transform(primitive.begin(), primitive.end(), p2d.begin(), utils::to2D<BasicPoint3d>);
394  return p2d;
395 }
396 
397 template <typename PolygonT>
398 std::enable_if_t<traits::isPolygonT<PolygonT>(), BasicPolygon2d> toBasicPolygon2d(const PolygonT& t) {
399  return traits::to2D(t).basicPolygon();
400 }
401 
402 template <>
404  return t;
405 }
406 
407 template <>
409  return traits::to2D(t);
410 }
411 
412 inline BasicPolygon2d toBasicPolygon2d(BasicPolygon2d&& t) { return std::move(t); }
413 
414 template <typename PolygonT>
415 std::enable_if_t<traits::isPolygonT<PolygonT>(), BasicPolygon3d> toBasicPolygon3d(const PolygonT& t) {
416  return traits::to3D(t).basicPolygon();
417 }
418 
419 template <>
421  return t;
422 }
423 
424 inline BasicPolygon3d toBasicPolygon3d(BasicPolygon3d&& t) { return std::move(t); }
425 
426 } // namespace traits
427 template <typename T, typename RetT>
428 using IfPoly = std::enable_if_t<traits::isPolygonT<T>(), RetT>;
429 
430 } // namespace lanelet
431 
432 // Hash function for usage in containers
433 namespace std {
434 template <>
435 struct hash<lanelet::Polygon3d> : public lanelet::HashBase<lanelet::Polygon3d> {};
436 template <>
437 struct hash<lanelet::ConstPolygon3d> : public lanelet::HashBase<lanelet::ConstPolygon3d> {};
438 template <>
439 struct hash<lanelet::Polygon2d> : public lanelet::HashBase<lanelet::Polygon2d> {};
440 template <>
441 struct hash<lanelet::ConstPolygon2d> : public lanelet::HashBase<lanelet::ConstPolygon2d> {};
442 } // namespace std
Polygon with access to primitive points.
const ConstPolygon2d & convert(const T &t) const
Polygon3d(const LineString3d &other)
Conversion from LineString3d. Does not ensure validity of the polygon!
Implementation template class that is common to all non-const types.
BasicPoints3d BasicLineString3d
Implementation template class that is common to all LineStrings.
BasicPolygon2d basicPolygon() const
create a simple 2d polygon from this (just a vector)
A (basic) 2d polygon with holes insideThis class is thought for geometry calculations, it has no properties of a normal lanelet primitive.
An mutable clockwise oriented, open (ie start point != end point) polygon in 2d.
An immutable clockwise oriented, open (ie start point != end point) polygon in 2d.
Eigen::Vector3d BasicPoint3d
a simple 3d-point
std::ostream & operator<<(std::ostream &stream, const Attribute &obj)
Definition: Attribute.h:369
traits::BasicPointT< Point3d > BasicPointType
Polygon2d(const LineString2d &other)
Conversion from LineString2d. Does not ensure validity of the polygon!
BasicPolygon3d toBasicPolygon3d(BasicPolygon3d &&t)
const ConstPointType & back() const noexcept
returns the last point (if it exist)
const ConstPointType & front() const noexcept
returns the first point (if it exist)
ConstPolygon3d(const ConstLineString3d &other)
BasicIterator end() const noexcept
BasicPoint2d Iterator to past-the-end.
const ConstPolygon3d & convert(const T &t) const
BasicPolygon2d toBasicPolygon2d(BasicPolygon2d &&t)
BasicPointType front() const noexcept
Get first BasicPoint2d.
Primitive 2d polygon with basic points.
size_t numSegments() const noexcept
Returns the number of (geometrically valid) segments.
A normal 3d linestring with immutable data.
BasicPolygon3d(const BasicLineString3d &other)
BasicPointType back() const noexcept
Get last BasicPoint2d.
Identifies RegulatoryElementPrimitives.
Definition: Traits.h:20
const BasicPointType & operator[](size_t idx) const noexcept
access BasicPoint3d at specific position
Identifies LineStringPrimitives.
Definition: Traits.h:9
A normal 3d linestring with mutable data.
ConstHybridPolygon3d(const ConstPolygon3d &poly)
Conversion from ConstPolygon3d.
BasicIterator begin() const noexcept
BasicPoint3d Iterator to begin.
Polygon with access to primitive points.
A (basic) 2d polygon with holes insideThis class is thought for geometry calculations, it has no properties of a normal lanelet primitive.
BasicPoints2d BasicLineString2d
size_t numSegments() const noexcept
Returns the number of (geometrically valid) segments.
const ConstPointType & operator[](size_t idx) const noexcept
returns the point at this position
auto transform(Container &&c, Func f)
Definition: Utilities.h:120
BasicPolygon2d to2D< BasicPolygon3d >(const BasicPolygon3d &primitive)
A mutable clockwise oriented, open (ie start point != end point) polygon in 3d.
ConstPolygon2d(const ConstLineString2d &other)
Conversion from/to ConstLineString2d.
Eigen::Matrix< double, 2, 1, Eigen::DontAlign > BasicPoint2d
a simple 2d-point
An immutable clockwise oriented, open (ie start point != end point) polygon in 3d.
BasicPolygon3d basicPolygon() const
create a simple 3d polygon from this (just a vector)
std::vector< BasicPolygon3d > BasicPolygons3d
Definition: Forward.h:154
BasicPolygon3d basicPolygon() const
create a simple 3d polygon from this (just a vector)
const BasicPointType & front() const noexcept
Get first BasicPoint3d.
BasicIterator end() const noexcept
BasicPoint3d Iterator to past-the-end.
BasicIterator begin() const noexcept
BasicPoint2d Iterator to begin.
BasicPolygon2d(const BasicLineString2d &other)
BasicPolygon3d toBasicPolygon3d< BasicPolygon3d >(const BasicPolygon3d &t)
std::enable_if_t< traits::isPolygonT< T >(), RetT > IfPoly
BasicPolygon2d basicPolygon() const
create a simple 2d polygon from this (just a vector)
BasicPointType operator[](size_t idx) const noexcept
access element at specific position
BoundingBox2d to2D(const BoundingBox3d &primitive)
constexpr bool isPolygonT()
const BasicPointType & back() const noexcept
Get last BasicPoint3d.
BoundingBox3d to3D(const BoundingBox2d &primitive)
BasicPolygon2d toBasicPolygon2d< BasicPolygon2d >(const BasicPolygon2d &t)
ConstHybridPolygon2d(const ConstPolygon2d &poly)
Conversion from ConstPolygon2d.
Primitive 3d polygon with basic points.
BasicPolygon2d toBasicPolygon2d< BasicPolygon3d >(const BasicPolygon3d &t)
A normal 2d linestring with immutable data.
A normal 2d linestring with mutable data.
ConstLineStringImpl(Id id=InvalId, Points3d points=Points3d(), const AttributeMap &attributes=AttributeMap())
Constructs a LineString or similar from an Id and a list of points.
std::vector< BasicPolygon2d > BasicPolygons2d
Definition: Forward.h:153


lanelet2_core
Author(s): Fabian Poggenhans
autogenerated on Tue Jun 6 2023 02:23:32