Go to the documentation of this file.
2 #include <boost/variant.hpp>
45 template <
typename VisitorT>
52 return applyVisitor([](
auto& elem) {
return elem.id(); });
61 return applyVisitor([](
auto& elem) {
return elem.regulatoryElements(); });
66 return applyVisitor([](
auto& elem) {
return elem.template regulatoryElementsAs<T>(); });
92 return area()->outerBoundPolygon();
106 stream << *obj.
area();
117 lanelets.reserve(lars.size());
118 for (
const auto& lar : lars) {
119 if (lar.isLanelet()) {
120 lanelets.push_back(
static_cast<const ConstLanelet&
>(lar));
127 lanelets.reserve(lars.size());
128 for (
const auto& lar : lars) {
130 lanelets.push_back(
static_cast<const ConstArea&
>(lar));
ConstLaneletOrArea(ConstLanelet lanelet)
std::vector< ConstLaneletOrArea > ConstLaneletOrAreas
decltype(auto) applyVisitor(VisitorT visitor) const
apply a generic visitor
Combines multiple linestrings to one polygon in 3d.
A const (i.e. immutable) Area.
ConstLaneletOrArea & operator=(ConstLanelet lanelet)
An object that can either refer to a lanelet or an area.
bool operator==(const Attribute &lhs, const Attribute &rhs)
std::ostream & operator<<(std::ostream &stream, const Attribute &obj)
ConstLaneletOrArea & operator=(ConstArea area)
ConstLaneletOrArea(ConstArea area)
boost::optional< T > Optional
bool isLanelet() const
true if this objct holds a lanelet
bool isArea() const
true if this object holds an area
Id id() const
get the id of the lanelet or area
RegulatoryElementConstPtrs regulatoryElements() const
Optional< ConstArea > area() const
get the managed area
bool operator!=(const Attribute &lhs, const Attribute &rhs)
boost::variant< ConstLanelet, ConstArea > laneletOrArea_
ConstLaneletOrArea & operator=(ConstLaneletOrArea &&rhs)=default
std::vector< std::shared_ptr< const T > > regulatoryElementsAs() const
CompoundPolygon3d boundingPolygon() const
returns the outer bound if it is an area or the polygon made of the lanelet bounds if it's a lanelet
bool equals(const ConstLaneletOrArea &other) const
compares this lanelet or area
ConstAreas getAllAreas(const ConstLaneletOrAreas &lars)
ConstLanelets getAllLanelets(const ConstLaneletOrAreas &lars)
~ConstLaneletOrArea() noexcept=default
const AttributeMap & attributes() const
get the attributes of the lanelet or area
std::vector< RegulatoryElementConstPtr > RegulatoryElementConstPtrs
std::vector< ConstArea > ConstAreas
Optional< ConstLanelet > lanelet() const
return the managed lanelet
std::vector< ConstLanelet > ConstLanelets
ConstLaneletOrArea()=default
lanelet2_core
Author(s): Fabian Poggenhans
autogenerated on Thu Mar 6 2025 03:25:52