LineStringOrPolygon.h
Go to the documentation of this file.
1 #pragma once
2 #include <boost/variant.hpp>
3 
7 
8 namespace lanelet {
10 template <typename LineStringT, typename PolygonT>
12  public:
13  LineStringOrPolygonBase() = default;
14  LineStringOrPolygonBase(LineStringOrPolygonBase&& rhs) = default; // NOLINT
15  LineStringOrPolygonBase& operator=(LineStringOrPolygonBase&& rhs) = default; // NOLINT
18  ~LineStringOrPolygonBase() noexcept = default;
19 
20  LineStringOrPolygonBase(LineStringT linestring) // NOLINT
21  : lsOrPoly_{std::move(linestring)} {}
22  LineStringOrPolygonBase(PolygonT polygon) // NOLINT
23  : lsOrPoly_{std::move(polygon)} {}
24  LineStringOrPolygonBase& operator=(LineStringT linestring) {
25  lsOrPoly_ = std::move(linestring);
26  return *this;
27  }
29  lsOrPoly_ = std::move(poly);
30  return *this;
31  }
32 
34  bool isPolygon() const { return lsOrPoly_.which() == 1; }
35 
37  bool isLineString() const { return lsOrPoly_.which() == 0; }
38 
40  explicit operator const LineStringT&() const { return boost::get<LineStringT>(lsOrPoly_); }
41 
43  explicit operator const PolygonT&() const { return boost::get<PolygonT>(lsOrPoly_); }
44 
46  template <typename VisitorT>
47  decltype(auto) applyVisitor(VisitorT visitor) const {
48  return boost::apply_visitor(visitor, lsOrPoly_);
49  }
50 
52  Id id() const {
53  return applyVisitor([](auto& elem) { return elem.id(); });
54  }
55 
57  const AttributeMap& attributes() const {
58  return applyVisitor([](auto& elem) -> const AttributeMap& { return elem.attributes(); });
59  }
60 
63  const auto* ls = boost::get<LineStringT>(&lsOrPoly_);
64  if (ls != nullptr) {
65  return *ls;
66  }
67  return {};
68  }
69 
72  const auto* poly = boost::get<PolygonT>(&lsOrPoly_);
73  if (poly != nullptr) {
74  return *poly;
75  }
76  return {};
77  }
78 
79  bool equals(const LineStringOrPolygonBase& other) const { return lsOrPoly_ == other.lsOrPoly_; }
80 
81  protected:
82  boost::variant<LineStringT, PolygonT> lsOrPoly_; // NOLINT
83 };
84 
86 class LineStringOrPolygon3d : public LineStringOrPolygonBase<LineString3d, Polygon3d> {
87  public:
89  using Base::LineStringOrPolygonBase;
90  operator RuleParameter() const { return asRuleParameter(); } // NOLINT
92  return applyVisitor([](auto& prim) { return RuleParameter(prim); });
93  }
94 
95  using Base::applyVisitor;
97  template <typename VisitorT>
98  decltype(auto) applyVisitor(VisitorT visitor) {
99  return boost::apply_visitor(visitor, lsOrPoly_);
100  }
101 };
102 
104 class ConstLineStringOrPolygon3d : public LineStringOrPolygonBase<ConstLineString3d, ConstPolygon3d> {
105  public:
107  using Base::LineStringOrPolygonBase;
109  if (lsOrPoly.isLineString()) {
110  *this = *lsOrPoly.lineString();
111  }
112  if (lsOrPoly.isPolygon()) {
113  *this = *lsOrPoly.polygon();
114  }
115  }
116  operator ConstRuleParameter() const { return asRuleParameter(); } // NOLINT
118  return applyVisitor([](auto& prim) { return ConstRuleParameter(prim); });
119  }
120 };
121 
122 inline bool operator==(const LineStringOrPolygon3d& lhs, const LineStringOrPolygon3d& rhs) { return lhs.equals(rhs); }
123 inline bool operator!=(const LineStringOrPolygon3d& lhs, const LineStringOrPolygon3d& rhs) { return !(lhs == rhs); }
124 
126  return lhs.equals(rhs);
127 }
129  return !(lhs == rhs);
130 }
131 
132 using LineStringsOrPolygons3d = std::vector<LineStringOrPolygon3d>;
133 using ConstLineStringsOrPolygons3d = std::vector<ConstLineStringOrPolygon3d>;
134 
135 inline std::ostream& operator<<(std::ostream& stream, const LineStringOrPolygon3d& obj) {
136  obj.applyVisitor([&stream](auto& prim) { stream << prim; });
137  return stream;
138 }
139 inline std::ostream& operator<<(std::ostream& stream, const ConstLineStringOrPolygon3d& obj) {
140  obj.applyVisitor([&stream](auto& prim) { stream << prim; });
141  return stream;
142 }
143 } // namespace lanelet
ConstLineStringOrPolygon3d(const LineStringOrPolygon3d &lsOrPoly)
Id id() const
get the id of the linestring or polygon
std::vector< ConstLineStringOrPolygon3d > ConstLineStringsOrPolygons3d
bool isPolygon() const
true if this object holds an polygon
LineStringOrPolygonBase & operator=(PolygonT poly)
int64_t Id
Definition: Forward.h:198
Base class for objects that can either refer to linestrings or polygons.
std::ostream & operator<<(std::ostream &stream, const Attribute &obj)
Definition: Attribute.h:369
Optional< PolygonT > polygon() const
get the managed polygon
This class holds either a LineString3d or a Polygon3d.
bool operator==(const Attribute &lhs, const Attribute &rhs)
Definition: Attribute.h:179
RuleParameter asRuleParameter() const
bool isLineString() const
true if this objct holds a lineString
This class holds either a ConstLineString3d or a ConstPolygon3d.
boost::optional< T > Optional
Definition: Optional.h:7
bool operator!=(const Attribute &lhs, const Attribute &rhs)
Definition: Attribute.h:180
boost::variant< ConstPoint3d, ConstLineString3d, ConstPolygon3d, ConstWeakLanelet, ConstWeakArea > ConstRuleParameter
Const-version of the parameters.
LineStringOrPolygonBase & operator=(LineStringT linestring)
ConstRuleParameter asRuleParameter() const
LineStringOrPolygonBase & operator=(LineStringOrPolygonBase &&rhs)=default
std::vector< LineStringOrPolygon3d > LineStringsOrPolygons3d
boost::variant< LineStringT, PolygonT > lsOrPoly_
const AttributeMap & attributes() const
get the attributes of the linestring or polygon
decltype(auto) applyVisitor(VisitorT visitor) const
apply a generic visitor
~LineStringOrPolygonBase() noexcept=default
Optional< LineStringT > lineString() const
return the managed linestring
LineStringOrPolygonBase(LineStringT linestring)
decltype(auto) applyVisitor(VisitorT visitor)
apply a generic visitor
boost::variant< Point3d, LineString3d, Polygon3d, WeakLanelet, WeakArea > RuleParameter
bool equals(const LineStringOrPolygonBase &other) const


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