primitives/Area.h
Go to the documentation of this file.
1 // this is for emacs file handling -*- mode: c++; c-basic-offset: 2;
2 // indent-tabs-mode: nil -*-
3 
4 #pragma once
5 
6 #include <memory>
7 #include <utility>
8 
15 
16 namespace lanelet {
37 
38 using InnerBounds = std::vector<LineStrings3d>;
39 using ConstInnerBounds = std::vector<ConstLineStrings3d>;
40 
43 class AreaData : public PrimitiveData {
44  public:
46  AreaData(Id id, LineStrings3d outerBound, std::vector<LineStrings3d> innerBounds = std::vector<LineStrings3d>(),
48  : PrimitiveData(id, std::move(attributes)),
49  outerBound_{std::move(outerBound)},
50  innerBounds_{std::move(innerBounds)},
52  resetCache();
53  }
54 
56  return utils::transform(outerBound_, [](const auto& elem) { return ConstLineString3d(elem); });
57  }
59  return utils::transform(innerBounds_, [](const auto& elem) {
60  return utils::transform(elem, [](const auto& ls) { return ConstLineString3d(ls); });
61  });
62  }
63  const LineStrings3d& outerBound() { return outerBound_; }
64  const InnerBounds& innerBounds() { return innerBounds_; }
65 
67 
69 
71  return utils::transform(regulatoryElements_, [](const auto& elem) { return RegulatoryElementConstPtr(elem); });
72  }
74 
75  template <typename RegElemT>
76  std::vector<std::shared_ptr<const RegElemT>> regulatoryElementsAs() const {
77  return utils::transformSharedPtr<const RegElemT>(regulatoryElements_);
78  }
79  template <typename RegElemT>
80  std::vector<std::shared_ptr<RegElemT>> regulatoryElementsAs() {
81  return utils::transformSharedPtr<RegElemT>(regulatoryElements_);
82  }
83 
85  void setOuterBound(const LineStrings3d& bound) {
86  outerBound_ = bound;
87  resetCache();
88  }
89 
90  void setInnerBounds(const std::vector<LineStrings3d>& bounds) {
91  innerBounds_ = bounds;
92  resetCache();
93  }
94 
95  void resetCache() {
98  [](const auto& elem) { return CompoundPolygon3d(elem); });
99  }
100 
101  private:
103  std::vector<LineStrings3d> innerBounds_;
105 
106  // caches
109 };
110 
114 class ConstArea : public ConstPrimitive<AreaData> {
115  public:
117  using MutableType = Area;
121 
128  explicit ConstArea(Id id = InvalId) : ConstArea(std::make_shared<AreaData>(id, LineStrings3d())) {}
129 
144  : ConstPrimitive{std::make_shared<AreaData>(id, outerBound, innerBounds, attributes, regulatoryElements)} {}
145 
147  explicit ConstArea(const std::shared_ptr<const AreaData>& data) : ConstPrimitive<AreaData>(data) {}
148 
150  ConstLineStrings3d outerBound() const { return constData()->outerBound(); }
151 
153  ConstInnerBounds innerBounds() const { return constData()->innerBounds(); }
154 
159  CompoundPolygon3d outerBoundPolygon() const { return constData()->outerBoundPolygon(); }
160 
162  CompoundPolygons3d innerBoundPolygons() const { return constData()->innerBoundPolygons(); }
163 
171  return {outerBoundPolygon().basicPolygon(),
172  utils::transform(innerBoundPolygons(), [](const auto& poly) { return poly.basicPolygon(); })};
173  }
174 
182  return {traits::to2D(outerBoundPolygon()).basicPolygon(),
183  utils::transform(innerBoundPolygons(), [](const auto& poly) { return traits::to2D(poly).basicPolygon(); })};
184  }
185 
187  RegulatoryElementConstPtrs regulatoryElements() const { return constData()->regulatoryElements(); }
188 
197  template <typename RegElemT>
198  std::vector<std::shared_ptr<const RegElemT>> regulatoryElementsAs() const {
199  return constData()->regulatoryElementsAs<RegElemT>();
200  }
201 };
202 
206 class Area : public Primitive<ConstArea> {
207  public:
208  using Primitive::Primitive;
209  using TwoDType = Area;
210  using ThreeDType = Area;
211  friend class ConstWeakArea;
212  Area() = default;
213  Area(const AreaDataConstPtr&) = delete;
214  explicit Area(const AreaDataPtr& data) : Primitive{data} {}
215 
216  using Primitive::innerBounds;
217  using Primitive::outerBound;
218  using Primitive::regulatoryElements;
219  using Primitive::regulatoryElementsAs;
220 
222  const LineStrings3d& outerBound() { return data()->outerBound(); }
223 
225  const InnerBounds& innerBounds() { return data()->innerBounds(); }
226 
228  void setOuterBound(const LineStrings3d& bound) { data()->setOuterBound(bound); }
229 
231  void setInnerBounds(const std::vector<LineStrings3d>& bounds) { data()->setInnerBounds(bounds); }
232 
234  const RegulatoryElementPtrs& regulatoryElements() { return data()->regulatoryElements(); }
235 
241  if (regElem == nullptr) {
242  throw NullptrError("regulatory element is a nullptr.");
243  }
244  data()->regulatoryElements().push_back(std::move(regElem));
245  }
246 
249  auto& regElems = data()->regulatoryElements();
250  auto remove = std::find(regElems.begin(), regElems.end(), regElem);
251  if (remove != regElems.end()) {
252  regElems.erase(remove);
253  return true;
254  }
255  return false;
256  }
257 
259  template <typename RegElemT>
260  std::vector<std::shared_ptr<RegElemT>> regulatoryElementsAs() {
261  return data()->regulatoryElementsAs<RegElemT>();
262  }
263 };
264 
272  public:
277  ConstWeakArea() = default;
278  ConstWeakArea(ConstArea area) // NOLINT
279  : areaData_(area.constData()) {}
280 
285  ConstArea lock() const { return ConstArea(areaData_.lock()); }
286 
288  bool expired() const noexcept { return areaData_.expired(); }
289 
290  protected:
291  std::weak_ptr<const AreaData> areaData_; // NOLINT
292 };
293 
300 class WeakArea final : public ConstWeakArea {
301  public:
302  WeakArea() = default;
303  WeakArea(Area llet) : ConstWeakArea(std::move(llet)) {} // NOLINT
304 
309  Area lock() const { return Area(std::const_pointer_cast<AreaData>(areaData_.lock())); }
310 };
311 
312 namespace utils {
324 inline bool has(const ConstArea& ll, Id id) { return has(ll.outerBoundPolygon(), id); }
325 } // namespace utils
326 
327 inline bool operator==(const ConstArea& lhs, const ConstArea& rhs) { return lhs.constData() == rhs.constData(); }
328 inline bool operator!=(const ConstArea& lhs, const ConstArea& rhs) { return !(lhs == rhs); }
329 inline bool operator==(const ConstWeakArea& lhs, const ConstWeakArea& rhs) {
330  return !lhs.expired() && !rhs.expired() && lhs.lock() == rhs.lock();
331 }
332 inline bool operator!=(const ConstWeakArea& lhs, const ConstWeakArea& rhs) { return !(lhs == rhs); }
333 inline std::ostream& operator<<(std::ostream& stream, const ConstArea& obj) {
334  stream << "[id: ";
335  stream << obj.id();
336  auto obId = obj.outerBoundPolygon().ids();
337  if (!obId.empty()) {
338  stream << " outer: [";
339  std::copy(obId.begin(), obId.end(), std::ostream_iterator<Id>(stream, ","));
340  stream << "]";
341  }
342  auto ibs = obj.innerBoundPolygons();
343  if (!ibs.empty()) {
344  stream << " inner: ";
345  for (const auto& ib : ibs) {
346  stream << "[";
347  auto ibId = ib.ids();
348  std::copy(ibId.begin(), ibId.end(), std::ostream_iterator<Id>(stream, ","));
349  stream << "]";
350  }
351  }
352  stream << "]";
353  return stream;
354 }
355 
356 namespace traits {
357 template <typename T>
358 constexpr bool isAreaT() {
359  return isCategory<T, traits::AreaTag>();
360 }
361 } // namespace traits
362 
363 template <typename T, typename RetT>
364 using IfAr = std::enable_if_t<traits::isAreaT<T>(), RetT>;
365 
366 } // namespace lanelet
367 
368 // Hash function for usage in containers
369 namespace std {
370 template <>
371 struct hash<lanelet::Area> : public lanelet::HashBase<lanelet::Area> {};
372 template <>
373 struct hash<lanelet::ConstArea> : public lanelet::HashBase<lanelet::ConstArea> {};
374 } // namespace std
lanelet::InvalId
constexpr Id InvalId
indicates a primitive that is not part of a map
Definition: Forward.h:199
lanelet::HashBase
Definition: Primitive.h:328
lanelet::AreaData::outerBound_
LineStrings3d outerBound_
linestrings that together form the outer bound
Definition: primitives/Area.h:102
lanelet::ConstLineStrings3d
std::vector< ConstLineString3d > ConstLineStrings3d
Definition: Forward.h:58
lanelet::Primitive
Base class for all mutable Primitives of lanelet2.
Definition: Primitive.h:243
lanelet::LineStrings3d
std::vector< LineString3d > LineStrings3d
Definition: Forward.h:57
lanelet::CompoundPolygon3d::basicPolygon
BasicPolygon3d basicPolygon() const
Definition: CompoundPolygon.h:61
lanelet::AreaData::innerBounds
ConstInnerBounds innerBounds() const
Definition: primitives/Area.h:58
Optional.h
lanelet::RegulatoryElementPtrs
std::vector< RegulatoryElementPtr > RegulatoryElementPtrs
Definition: Forward.h:193
lanelet::PrimitiveData
Common data class for all lanelet primitives.
Definition: Primitive.h:31
lanelet::CompoundPolygon3d
Combines multiple linestrings to one polygon in 3d.
Definition: CompoundPolygon.h:40
lanelet::traits::to2D
BoundingBox2d to2D(const BoundingBox3d &primitive)
Definition: primitives/BoundingBox.h:304
lanelet
Definition: Attribute.h:13
Point.h
lanelet::RegulatoryElementPtr
std::shared_ptr< RegulatoryElement > RegulatoryElementPtr
Definition: Forward.h:192
lanelet::ConstPrimitive< AreaData >::attributes
const AttributeMap & attributes() const
get the attributes of this primitive
Definition: Primitive.h:89
lanelet::ConstArea::innerBoundPolygons
CompoundPolygons3d innerBoundPolygons() const
get the inner bounds as polygon
Definition: primitives/Area.h:162
lanelet::ConstArea
A const (i.e. immutable) Area.
Definition: primitives/Area.h:114
lanelet::AreaData::resetCache
void resetCache()
Definition: primitives/Area.h:95
lanelet::AttributeMap
HybridMap< Attribute, decltype(AttributeNamesString::Map)&, AttributeNamesString::Map > AttributeMap
Definition: Attribute.h:371
lanelet::ConstArea::ConstArea
ConstArea(Id id=InvalId)
Constructs an empty or invalid area.
Definition: primitives/Area.h:128
lanelet::AreaData::setInnerBounds
void setInnerBounds(const std::vector< LineStrings3d > &bounds)
Definition: primitives/Area.h:90
lanelet::Area::addRegulatoryElement
void addRegulatoryElement(RegulatoryElementPtr regElem)
adds a new regulatory element
Definition: primitives/Area.h:240
lanelet::operator==
bool operator==(const Attribute &lhs, const Attribute &rhs)
Definition: Attribute.h:179
lanelet::AreaData::innerBoundPolygons
const CompoundPolygons3d & innerBoundPolygons() const
Definition: primitives/Area.h:68
lanelet::WeakArea::WeakArea
WeakArea(Area llet)
Definition: primitives/Area.h:303
lanelet::Id
int64_t Id
Definition: Forward.h:198
lanelet::operator<<
std::ostream & operator<<(std::ostream &stream, const Attribute &obj)
Definition: Attribute.h:369
lanelet::InnerBounds
std::vector< LineStrings3d > InnerBounds
Definition: primitives/Area.h:38
lanelet::utils::transform
auto transform(Iterator begin, Iterator end, const Func f)
Definition: Utilities.h:176
lanelet::AreaData::regulatoryElements
RegulatoryElementConstPtrs regulatoryElements() const
Definition: primitives/Area.h:70
lanelet::ConstArea::innerBounds
ConstInnerBounds innerBounds() const
get the linestrings that form the inner bounds
Definition: primitives/Area.h:153
lanelet::Area::innerBounds
const InnerBounds & innerBounds()
Get the linestrings that form the inner bound.
Definition: primitives/Area.h:225
lanelet::Area::outerBound
const LineStrings3d & outerBound()
Get linestrings that form the outer bound.
Definition: primitives/Area.h:222
lanelet::WeakArea::WeakArea
WeakArea()=default
lanelet::ConstWeakArea::areaData_
std::weak_ptr< const AreaData > areaData_
Definition: primitives/Area.h:291
lanelet::AreaData::innerBounds_
std::vector< LineStrings3d > innerBounds_
vector of ls for inner bounds
Definition: primitives/Area.h:103
lanelet::BasicPolygonWithHoles2d
A (basic) 2d polygon with holes inside.
Definition: primitives/Polygon.h:326
lanelet::Area
Famous Area class that represents a basic area as element of the map.
Definition: primitives/Area.h:206
lanelet::AreaData::regulatoryElements_
RegulatoryElementPtrs regulatoryElements_
regulatory elements that apply
Definition: primitives/Area.h:104
lanelet::AreaDataConstPtr
std::shared_ptr< const AreaData > AreaDataConstPtr
Definition: Forward.h:132
lanelet::ConstPrimitive< AreaData >::constData
const std::shared_ptr< const AreaData > & constData() const
get the internal data of this primitive
Definition: Primitive.h:178
lanelet::AreaData::outerBound
ConstLineStrings3d outerBound() const
Definition: primitives/Area.h:55
Primitive.h
lanelet::ConstWeakArea::ConstWeakArea
ConstWeakArea(ConstArea area)
Definition: primitives/Area.h:278
lanelet::ConstArea::regulatoryElements
RegulatoryElementConstPtrs regulatoryElements() const
get a list of regulatory elements that affect this area
Definition: primitives/Area.h:187
lanelet::AreaData::outerBound
const LineStrings3d & outerBound()
Definition: primitives/Area.h:63
lanelet::ConstArea::basicPolygonWithHoles2d
BasicPolygonWithHoles2d basicPolygonWithHoles2d() const
generates a basic polygon in 2d with holes for this area
Definition: primitives/Area.h:181
lanelet::PrimitiveData::attributes
AttributeMap attributes
attributes of this primitive
Definition: Primitive.h:45
lanelet::traits::isAreaT
constexpr bool isAreaT()
Definition: primitives/Area.h:358
lanelet::WeakArea
used internally by RegulatoryElements to avoid cyclic dependencies.
Definition: primitives/Area.h:300
lanelet::Primitive::Primitive
friend class Primitive
Definition: Primitive.h:280
lanelet::AreaData::regulatoryElements
RegulatoryElementPtrs & regulatoryElements()
Definition: primitives/Area.h:73
lanelet::utils::addConst
const T & addConst(T &t)
Definition: Utilities.h:149
lanelet::AreaData::outerBoundPolygon
const CompoundPolygon3d & outerBoundPolygon() const
Definition: primitives/Area.h:66
lanelet::CompoundLineStringImpl::ids
Ids ids() const
returns the ids of all linestrings in order
Definition: CompoundLineString.h:245
lanelet::Area::removeRegulatoryElement
bool removeRegulatoryElement(const RegulatoryElementPtr &regElem)
removes a regulatory element, returns true on success
Definition: primitives/Area.h:248
lanelet::Area::setOuterBound
void setOuterBound(const LineStrings3d &bound)
Sets a new outer bound and resets the cache.
Definition: primitives/Area.h:228
lanelet::Area::setInnerBounds
void setInnerBounds(const std::vector< LineStrings3d > &bounds)
sets a new inner bound and resets the cache
Definition: primitives/Area.h:231
lanelet::ConstArea::regulatoryElementsAs
std::vector< std::shared_ptr< const RegElemT > > regulatoryElementsAs() const
get the regulatoryElements that could be converted to a type
Definition: primitives/Area.h:198
lanelet::operator!=
bool operator!=(const Attribute &lhs, const Attribute &rhs)
Definition: Attribute.h:180
lanelet::AreaData::innerBounds
const InnerBounds & innerBounds()
Definition: primitives/Area.h:64
lanelet::AreaData::innerBoundPolygons_
CompoundPolygons3d innerBoundPolygons_
represents the inner bounds of the area
Definition: primitives/Area.h:108
lanelet::AreaData::outerBoundPolygon_
CompoundPolygon3d outerBoundPolygon_
represents the outer bounds of the area
Definition: primitives/Area.h:107
lanelet::AreaData
Common data management class for all Area-Typed objects.
Definition: primitives/Area.h:43
CompoundPolygon.h
lanelet::ConstWeakArea::ConstWeakArea
ConstWeakArea()=default
lanelet::RegulatoryElementConstPtr
std::shared_ptr< const RegulatoryElement > RegulatoryElementConstPtr
Definition: Forward.h:194
lanelet::ConstWeakArea::expired
bool expired() const noexcept
tests whether the WeakArea is still valid
Definition: primitives/Area.h:288
lanelet::Area::Area
Area()=default
lanelet::AreaData::AreaData
AreaData(Id id, LineStrings3d outerBound, std::vector< LineStrings3d > innerBounds=std::vector< LineStrings3d >(), AttributeMap attributes=AttributeMap(), RegulatoryElementPtrs regulatoryElements=RegulatoryElementPtrs())
Constructs a new, AreaData object.
Definition: primitives/Area.h:46
lanelet::Area::regulatoryElementsAs
std::vector< std::shared_ptr< RegElemT > > regulatoryElementsAs()
get the regulatoryElements that could be converted to RegElemT
Definition: primitives/Area.h:260
lanelet::ConstArea::outerBoundPolygon
CompoundPolygon3d outerBoundPolygon() const
get the outer bound as polygon
Definition: primitives/Area.h:159
lanelet::HybridMap< Attribute, decltype(AttributeNamesString::Map)&, AttributeNamesString::Map >
lanelet::ConstArea::ConstArea
ConstArea(const std::shared_ptr< const AreaData > &data)
Constructor to construct from the data of a different Area.
Definition: primitives/Area.h:147
lanelet::utils::has
bool has(const ConstArea &ll, Id id)
returns true if element of a regulatory element has a matching Id
Definition: primitives/Area.h:324
lanelet::AreaDataPtr
std::shared_ptr< AreaData > AreaDataPtr
Definition: Forward.h:130
lanelet::ConstPrimitive
Basic Primitive class for all primitives of lanelet2.
Definition: Primitive.h:70
lanelet::Area::regulatoryElements
const RegulatoryElementPtrs & regulatoryElements()
return regulatoryElements that affect this area.
Definition: primitives/Area.h:234
std
Definition: primitives/Area.h:369
lanelet::ConstArea::basicPolygonWithHoles3d
BasicPolygonWithHoles3d basicPolygonWithHoles3d() const
generates a basic polygon in 2d with holes for this area
Definition: primitives/Area.h:170
lanelet::RegulatoryElementConstPtrs
std::vector< RegulatoryElementConstPtr > RegulatoryElementConstPtrs
Definition: Forward.h:195
lanelet::ConstLineString3d
A normal 3d linestring with immutable data.
Definition: primitives/LineString.h:521
lanelet::IfAr
std::enable_if_t< traits::isAreaT< T >(), RetT > IfAr
Definition: primitives/Area.h:364
lanelet::traits::AreaTag
Identifies LaneletPrimitives.
Definition: Traits.h:11
lanelet::ConstWeakArea::lock
ConstArea lock() const
Obtains the original ConstArea.
Definition: primitives/Area.h:285
lanelet::ConstArea::outerBound
ConstLineStrings3d outerBound() const
Get linestrings that form the outer bound.
Definition: primitives/Area.h:150
lanelet::CompoundPolygons3d
std::vector< CompoundPolygon3d > CompoundPolygons3d
Definition: Forward.h:86
lanelet::AreaData::regulatoryElementsAs
std::vector< std::shared_ptr< RegElemT > > regulatoryElementsAs()
Definition: primitives/Area.h:80
lanelet::ConstWeakArea
used internally by RegulatoryElements to avoid cyclic dependencies.
Definition: primitives/Area.h:271
lanelet::NullptrError
SharedPtrs in lanelet2 must never point to null. If this is violated, this exception is thrown (usual...
Definition: Exceptions.h:80
lanelet::ConstInnerBounds
std::vector< ConstLineStrings3d > ConstInnerBounds
Definition: primitives/Area.h:39
Polygon.h
lanelet::PrimitiveData::id
Id id
Id of this primitive (unique across one map)
Definition: Primitive.h:44
lanelet::Area::Area
Area(const AreaDataPtr &data)
Definition: primitives/Area.h:214
Forward.h
lanelet::Primitive< ConstArea >::data
std::shared_ptr< DataType > data() const
Definition: Primitive.h:287
lanelet::BasicPolygonWithHoles3d
A (basic) 2d polygon with holes inside.
Definition: primitives/Polygon.h:313
lanelet::AreaData::setOuterBound
void setOuterBound(const LineStrings3d &bound)
sets a new outer bound.
Definition: primitives/Area.h:85
lanelet::utils::find
auto find(ContainerT &&c, const ValueT &val)
Definition: Utilities.h:186
lanelet::ConstPrimitive< AreaData >::id
Id id() const noexcept
get the unique id of this primitive
Definition: Primitive.h:96
lanelet::WeakArea::lock
Area lock() const
Obtains the original ConstArea.
Definition: primitives/Area.h:309
lanelet::ConstArea::ConstArea
ConstArea(Id id, const LineStrings3d &outerBound, const InnerBounds &innerBounds=InnerBounds(), const AttributeMap &attributes=AttributeMap(), const RegulatoryElementPtrs &regulatoryElements=RegulatoryElementPtrs())
Constructs a new area.
Definition: primitives/Area.h:141
lanelet::AreaData::regulatoryElementsAs
std::vector< std::shared_ptr< const RegElemT > > regulatoryElementsAs() const
Definition: primitives/Area.h:76


lanelet2_core
Author(s): Fabian Poggenhans
autogenerated on Thu Mar 6 2025 03:25:52