Primitive.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 #include <limits>
6 #include <utility>
7 
11 
12 namespace lanelet {
20 
32  public:
33  PrimitiveData() noexcept = default;
34  PrimitiveData(PrimitiveData&& rhs) noexcept = default;
35  PrimitiveData& operator=(PrimitiveData&& rhs) noexcept = default;
36  PrimitiveData(const PrimitiveData& rhs) = default;
37  PrimitiveData& operator=(const PrimitiveData& rhs) = default;
38 
42  explicit PrimitiveData(Id id, AttributeMap attributes = AttributeMap()) : id{id}, attributes{std::move(attributes)} {}
43 
44  Id id{InvalId};
46  protected:
47  ~PrimitiveData() = default;
48 }; // class PrimitiveData
49 
63 
69 template <typename Data>
71  public:
72  using DataType = Data;
73  static constexpr bool IsConst = true;
78  explicit ConstPrimitive(const std::shared_ptr<const Data>& data) : constData_{data} {
79  if (!data) {
80  throw lanelet::NullptrError("Nullptr passed to constructor!");
81  }
82  }
83 
84  // Comparison
85  bool operator==(const ConstPrimitive& rhs) const { return this->constData_ == rhs.constData_; }
86  bool operator!=(const ConstPrimitive& rhs) const { return !(*this == rhs); }
87 
89  const AttributeMap& attributes() const { return constData_->attributes; }
90 
92 
96  Id id() const noexcept { return constData_->id; }
97 
99  bool hasAttribute(const std::string& name) const noexcept { return attributes().find(name) != attributes().end(); }
100 
102 
107  bool hasAttribute(AttributeName name) const noexcept { return attributes().find(name) != attributes().end(); }
108 
113  const Attribute& attribute(const std::string& name) const {
114  try {
115  return attributes().at(name);
116  } catch (std::out_of_range& err) {
117  throw NoSuchAttributeError(err.what());
118  }
119  }
120 
125  const Attribute& attribute(AttributeName name) const {
126  try {
127  return attributes().at(name);
128  } catch (std::out_of_range& err) {
129  throw NoSuchAttributeError(err.what());
130  }
131  }
132 
142  template <typename T>
143  T attributeOr(const std::string& name, T defaultVal) const noexcept {
144  auto elem = attributes().find(name);
145  if (elem == attributes().end()) {
146  return defaultVal;
147  }
148  auto val = elem->second.template as<T>();
149  if (!!val) {
150  return *val;
151  }
152  return defaultVal;
153  }
154 
164  template <typename T>
165  T attributeOr(AttributeName name, T defaultVal) const {
166  auto elem = attributes().find(name);
167  if (elem == attributes().end()) {
168  return defaultVal;
169  }
170  auto val = elem->second.template as<T>();
171  if (!!val) {
172  return *val;
173  }
174  return defaultVal;
175  }
176 
178  const std::shared_ptr<const Data>& constData() const { return constData_; }
179 
180  protected:
181  // This class is only an implementation class and should never be instanciated
182  ConstPrimitive(ConstPrimitive&& rhs) noexcept = default;
183  ConstPrimitive& operator=(ConstPrimitive&& rhs) noexcept = default;
184  ConstPrimitive(const ConstPrimitive& rhs) = default;
185  ConstPrimitive& operator=(const ConstPrimitive& rhs) = default;
186  ~ConstPrimitive() noexcept = default;
187 
188  private:
189  std::shared_ptr<const Data> constData_;
190 
191 }; // class ConstPrimitive
192 
235 
242 template <typename DerivedConstPrimitive>
243 class Primitive : public DerivedConstPrimitive {
244  public:
245  Primitive() = default; // not inherited
246  using DataType = typename DerivedConstPrimitive::DataType;
247  using DerivedConstPrimitive::DerivedConstPrimitive;
248  static constexpr bool IsConst = false;
249 
250  // needs a non-const shared_ptr to construct
251  Primitive(const std::shared_ptr<const DataType>&) = delete;
252 
254  explicit Primitive(const std::shared_ptr<DataType>& data) : DerivedConstPrimitive(data) {
255  if (!data) {
256  throw lanelet::NullptrError("Nullptr passed to constructor!");
257  }
258  }
259 
261  template <typename OtherT>
262  explicit Primitive(const Primitive<OtherT>& rhs) : DerivedConstPrimitive(rhs) {}
263 
270  void setId(Id id) noexcept { data()->id = id; }
271 
273  void setAttribute(const std::string& name, const Attribute& attribute) { attributes()[name] = attribute; }
274 
276  void setAttribute(AttributeName name, const Attribute& attribute) { attributes()[name] = attribute; }
277 
278  // need this for copy construction to work
279  template <typename>
280  friend class Primitive;
281 
282  using DerivedConstPrimitive::attributes;
284  AttributeMap& attributes() noexcept { return data()->attributes; }
285 
286  protected:
287  std::shared_ptr<DataType> data() const {
288  // const_pointer_cast is ok. Non-const primitives cannot be created without
289  // a non-const pointer.
290  return std::const_pointer_cast<DataType>(this->constData());
291  }
292 
293  // This class is only an implementation class and should never be instanciated
294  Primitive(Primitive&& rhs) noexcept;
295  Primitive& operator=(Primitive&& rhs) noexcept;
296  Primitive(const Primitive& rhs) noexcept;
297  Primitive& operator=(const Primitive& rhs) noexcept;
298  ~Primitive() noexcept = default; // NOLINT
299 };
300 
301 namespace traits {
302 
303 namespace internal {
304 template <typename PrimitiveT>
305 class IsPrimitiveHelper : public std::false_type {};
306 template <typename PrimitiveT>
307 class IsPrimitiveHelper<ConstPrimitive<PrimitiveT>> : public std::true_type {};
308 
309 template <typename DataT>
310 bool isLaneletPrimitiveHelper(ConstPrimitive<DataT>* /*unused*/, int /*unused*/) {
311  return true;
312 }
313 
314 template <typename NotPrimitive>
315 bool isLaneletPrimitiveHelper(NotPrimitive* /*unused*/, long /*unused*/) { // NOLINT
316  return false;
317 }
318 } // namespace internal
319 
320 template <typename PrimitiveT>
321 constexpr bool isLaneletPrimitive() {
322  PrimitiveT* v = nullptr;
323  return IsLaneletPrimitiveHelper(v, 0);
324 }
325 } // namespace traits
326 
327 template <typename PrimitiveT>
328 struct HashBase {
329  size_t operator()(const PrimitiveT& x) const noexcept { return std::hash<Id>()(x.id()); }
330 };
331 
332 template <typename DerivedConstPrimitive>
334 
335 template <typename DerivedConstPrimitive>
337 
338 template <typename DerivedConstPrimitive>
339 Primitive<DerivedConstPrimitive>::Primitive(const Primitive& rhs) noexcept = default;
340 
341 template <typename DerivedConstPrimitive>
343 
344 } // namespace lanelet
Id id() const noexcept
get the unique id of this primitive
Definition: Primitive.h:96
iterator end()
Definition: HybridMap.h:126
bool hasAttribute(const std::string &name) const noexcept
check whether this primitive has a specific attribute
Definition: Primitive.h:99
AttributeMap attributes
attributes of this primitive
Definition: Primitive.h:45
Primitive(const Primitive< OtherT > &rhs)
Construct from another primitive. Only works if both share the same.
Definition: Primitive.h:262
int64_t Id
Definition: Forward.h:198
PrimitiveData(Id id, AttributeMap attributes=AttributeMap())
Constructs a PrimitiveData object.
Definition: Primitive.h:42
iterator find(const key_type &k)
Definition: HybridMap.h:114
HybridMap< Attribute, decltype(AttributeNamesString::Map)&, AttributeNamesString::Map > AttributeMap
Definition: Attribute.h:371
const AttributeMap & attributes() const
get the attributes of this primitive
Definition: Primitive.h:89
T attributeOr(const std::string &name, T defaultVal) const noexcept
retrieve an attribute (string version)
Definition: Primitive.h:143
T attributeOr(AttributeName name, T defaultVal) const
retrieve an attribute (enum version)
Definition: Primitive.h:165
PrimitiveData & operator=(PrimitiveData &&rhs) noexcept=default
const ValueT & at(const key_type &k) const
Definition: HybridMap.h:178
bool operator==(const ConstPrimitive &rhs) const
Definition: Primitive.h:85
const Attribute & attribute(const std::string &name) const
retrieve an attribute
Definition: Primitive.h:113
typename ConstLineStringT ::DataType DataType
Definition: Primitive.h:246
Primitive & operator=(Primitive &&rhs) noexcept
const std::shared_ptr< const Data > & constData() const
get the internal data of this primitive
Definition: Primitive.h:178
void setAttribute(AttributeName name, const Attribute &attribute)
set or overwrite an attribute (enum version)
Definition: Primitive.h:276
SharedPtrs in lanelet2 must never point to null. If this is violated, this exception is thrown (usual...
Definition: Exceptions.h:80
Basic Primitive class for all primitives of lanelet2.
Definition: Primitive.h:70
An attribute represents one value of a tag of a lanelet primitive.
Definition: Attribute.h:32
Base class for all mutable Primitives of lanelet2.
Definition: Primitive.h:243
std::shared_ptr< const Data > constData_
the data this primitive holds
Definition: Primitive.h:189
Common data class for all lanelet primitivesThis class provides the data that all lanelet primitives ...
Definition: Primitive.h:31
size_t operator()(const PrimitiveT &x) const noexcept
Definition: Primitive.h:329
void setId(Id id) noexcept
set a new id for this primitive
Definition: Primitive.h:270
AttributeMap & attributes() noexcept
get the attributes in a mutable way
Definition: Primitive.h:284
std::shared_ptr< DataType > data() const
Definition: Primitive.h:287
Common data management class for all Area-Typed objects.
bool isLaneletPrimitiveHelper(NotPrimitive *, long)
Definition: Primitive.h:315
Thrown when an attribute has been queried that does not exist.
Definition: Exceptions.h:42
constexpr bool isLaneletPrimitive()
Definition: Primitive.h:321
Id id
Id of this primitive (unique across one map)
Definition: Primitive.h:44
Primitive(const std::shared_ptr< DataType > &data)
Construct a new primitive from shared_ptr to its data.
Definition: Primitive.h:254
ConstPrimitive(const std::shared_ptr< const Data > &data)
Construct from a pointer to the data.
Definition: Primitive.h:78
const Attribute & attribute(AttributeName name) const
retrieve an attribute (enum version)
Definition: Primitive.h:125
void setAttribute(const std::string &name, const Attribute &attribute)
set or overwrite an attribute
Definition: Primitive.h:273
bool hasAttribute(AttributeName name) const noexcept
check for an attribute (enum version)
Definition: Primitive.h:107
bool operator!=(const ConstPrimitive &rhs) const
Definition: Primitive.h:86
AttributeName
Typical Attributes names within lanelet.
Definition: Attribute.h:185
constexpr Id InvalId
indicates a primitive that is not part of a map
Definition: Forward.h:199
PrimitiveData() noexcept=default


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