2 #include <boost/variant.hpp> 10 template <
typename LineStringT,
typename PolygonT>
40 explicit operator const LineStringT&()
const {
return boost::get<LineStringT>(
lsOrPoly_); }
43 explicit operator const PolygonT&()
const {
return boost::get<PolygonT>(
lsOrPoly_); }
46 template <
typename VisitorT>
48 return boost::apply_visitor(visitor,
lsOrPoly_);
53 return applyVisitor([](
auto& elem) {
return elem.id(); });
63 const auto* ls = boost::get<LineStringT>(&
lsOrPoly_);
72 const auto* poly = boost::get<PolygonT>(&
lsOrPoly_);
73 if (poly !=
nullptr) {
89 using Base::LineStringOrPolygonBase;
95 using Base::applyVisitor;
97 template <
typename VisitorT>
99 return boost::apply_visitor(visitor,
lsOrPoly_);
107 using Base::LineStringOrPolygonBase;
129 return !(lhs == rhs);
136 obj.
applyVisitor([&stream](
auto& prim) { stream << prim; });
140 obj.
applyVisitor([&stream](
auto& prim) { stream << prim; });
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)
Base class for objects that can either refer to linestrings or polygons.
std::ostream & operator<<(std::ostream &stream, const Attribute &obj)
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)
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
bool operator!=(const Attribute &lhs, const Attribute &rhs)
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_
LineStringOrPolygonBase(PolygonT polygon)
const AttributeMap & attributes() const
get the attributes of the linestring or polygon
decltype(auto) applyVisitor(VisitorT visitor) const
apply a generic visitor
LineStringOrPolygonBase()=default
~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