Serialize.h
Go to the documentation of this file.
1 #pragma once
3 
4 #include <boost/serialization/map.hpp>
5 #include <boost/serialization/serialization.hpp>
6 #include <boost/serialization/shared_ptr.hpp>
7 #include <boost/serialization/split_free.hpp>
8 #include <boost/serialization/variant.hpp>
9 #include <boost/serialization/vector.hpp>
10 #include <map>
11 #include <set>
12 
13 namespace lanelet {
14 namespace impl {
15 // these methods are there because serializing vectors on boost 1.54 is done through a proxy object.
16 // this does not work here, because we need the real, final address for RegelemDeserialization.
17 // In Boost 1.60 and up, this is fixed and a simple ar<<regelems would be enough.
18 template <typename Archive, typename RegelemsT>
19 void saveRegelems(Archive& ar, RegelemsT regelems) {
20  auto size = regelems.size();
21  ar << size;
22  for (auto& regelem : regelems) {
23  auto ncRegelem = std::const_pointer_cast<RegulatoryElement>(regelem);
24  ar << ncRegelem;
25  }
26 }
27 template <typename Archive, typename RegelemsT>
28 void loadRegelems(Archive& ar, RegelemsT& regelems) {
29  size_t size{};
30  ar >> size;
31  regelems.resize(size);
32  for (auto i = 0u; i < size; ++i) {
33  ar >> regelems[i];
34  }
35 }
36 } // namespace impl
37 } // namespace lanelet
38 
39 namespace boost {
40 namespace serialization {
41 template <typename Archive>
42 void load(Archive& ar, lanelet::Attribute& p, unsigned int /*version*/) {
43  std::string val;
44  ar& val;
45  p = std::move(val);
46 }
47 
48 template <typename Archive>
49 void save(Archive& ar, const lanelet::Attribute& p, unsigned int /*version*/) {
50  ar& p.value();
51 }
52 
53 template <typename Archive>
54 void load(Archive& ar, lanelet::AttributeMap& p, unsigned int /*version*/) {
55  boost::serialization::load_map_collection(ar, p);
56 }
57 
58 template <typename Archive>
59 void save(Archive& ar, const lanelet::AttributeMap& p, unsigned int /*version*/) {
60  boost::serialization::stl::save_collection(ar, p);
61 }
62 
63 template <typename Archive>
64 void load(Archive& ar, lanelet::RuleParameterMap& p, unsigned int /*version*/) {
65  boost::serialization::load_map_collection(ar, p);
66 }
67 
68 template <typename Archive>
69 void save(Archive& ar, const lanelet::RuleParameterMap& p, unsigned int /*version*/) {
70  boost::serialization::stl::save_collection(ar, p);
71 }
72 
74 template <typename Archive>
75 void serialize(Archive& /*ar*/, lanelet::LaneletData& /*p*/, unsigned int /*version*/) {}
76 template <class Archive>
77 // NOLINTNEXTLINE
78 inline void save_construct_data(Archive& ar, const lanelet::LaneletData* llt, unsigned int /*version*/) {
79  auto lltnc = const_cast<lanelet::LaneletData*>(llt); // NOLINT
80  ar << lltnc->id << lltnc->attributes << lltnc->leftBound() << lltnc->rightBound();
82  auto hasCenterline = llt->hasCustomCenterline();
83  ar << hasCenterline;
84  if (hasCenterline) {
85  auto centerline = llt->centerline();
86  lanelet::LineString3d center(std::const_pointer_cast<lanelet::LineStringData>(centerline.constData()),
87  centerline.inverted());
88  ar << center;
89  }
90 }
91 
92 template <class Archive>
93 // NOLINTNEXTLINE
94 inline void load_construct_data(Archive& ar, lanelet::LaneletData* llt, unsigned int /*version*/
95 ) {
96  using namespace lanelet;
97  Id id = 0;
98  AttributeMap attrs;
99  LineString3d left;
100  LineString3d right;
101  ar >> id >> attrs >> left >> right;
102  new (llt) LaneletData(id, left, right, attrs);
103  lanelet::impl::loadRegelems(ar, llt->regulatoryElements()); // must happen directly to the correct memory location
104  bool hasCenterline = false;
105  ar >> hasCenterline;
106  if (hasCenterline) {
107  LineString3d centerline;
108  ar >> centerline;
109  llt->setCenterline(centerline);
110  }
111 }
112 
113 template <typename Archive>
114 void save(Archive& ar, const lanelet::Lanelet& l, unsigned int /*version*/) {
115  auto inv = l.inverted();
116  auto ptr = lanelet::utils::removeConst(l.constData());
117  ar << inv << ptr;
118 }
119 template <typename Archive>
120 void load(Archive& ar, lanelet::Lanelet& l, unsigned int /*version*/) {
121  std::shared_ptr<lanelet::LaneletData> ptr;
122  bool inv = false;
123  ar >> inv >> ptr;
124  l = lanelet::Lanelet(ptr, inv);
125 }
126 template <typename Archive>
127 void save(Archive& ar, const lanelet::ConstLanelet& l, unsigned int /*version*/) {
128  auto inv = l.inverted();
129  auto ptr = lanelet::utils::removeConst(l.constData());
130  ar << inv << ptr;
131 }
132 
133 template <typename Archive>
134 void load(Archive& ar, lanelet::ConstLanelet& l, unsigned int /*version*/) {
135  std::shared_ptr<lanelet::LaneletData> ptr;
136  bool inv = false;
137  ar >> inv >> ptr;
138  l = lanelet::Lanelet(ptr, inv);
139 }
140 
141 template <typename Archive>
142 void save(Archive& ar, const lanelet::WeakLanelet& l, unsigned int /*version*/) {
143  if (l.expired()) {
144  throw lanelet::LaneletError("Can not serialize expired weak pointer!");
145  }
146  auto sp = l.lock();
147  ar& sp;
148 }
149 template <typename Archive>
150 void load(Archive& ar, lanelet::WeakLanelet& l, unsigned int /*version*/) {
152  ar& lanelet;
153  l = lanelet;
154 }
155 
157 template <typename Archive>
158 void serialize(Archive& /*ar*/, lanelet::LineStringData& /*l*/, unsigned int /*version*/) {}
159 template <class Archive>
160 // NOLINTNEXTLINE
161 inline void save_construct_data(Archive& ar, const lanelet::LineStringData* l, unsigned int /*version*/) {
162  auto lnc = const_cast<lanelet::LineStringData*>(l); // NOLINT
163  ar << lnc->id << lnc->attributes << lnc->points();
164 }
165 
166 template <class Archive>
167 // NOLINTNEXTLINE
168 inline void load_construct_data(Archive& ar, lanelet::LineStringData* l, unsigned int /*version*/) {
169  using namespace lanelet;
170  Id id = 0;
171  AttributeMap attr;
172  Points3d points;
173  ar >> id >> attr >> points;
174  new (l) LineStringData(id, points, attr);
175 }
176 
177 template <typename Archive>
178 void save(Archive& ar, const lanelet::LineString3d& l, unsigned int /*version*/) {
179  auto inv = l.inverted();
180  auto ptr = lanelet::utils::removeConst(l.constData());
181  ar << inv << ptr;
182 }
183 template <typename Archive>
184 void load(Archive& ar, lanelet::LineString3d& l, unsigned int /*version*/) {
185  std::shared_ptr<lanelet::LineStringData> ptr;
186  bool inv{};
187  ar >> inv;
188  ar >> ptr;
189  l = lanelet::LineString3d(ptr, inv);
190 }
191 template <typename Archive>
192 void save(Archive& ar, const lanelet::Polygon3d& l, unsigned int /*version*/) {
193  auto inv = l.inverted();
194  auto ptr = lanelet::utils::removeConst(l.constData());
195  ar << inv << ptr;
196 }
197 template <typename Archive>
198 void load(Archive& ar, lanelet::Polygon3d& l, unsigned int /*version*/) {
199  std::shared_ptr<lanelet::LineStringData> ptr;
200  bool inv{};
201  ar >> inv;
202  ar >> ptr;
203  l = lanelet::Polygon3d(ptr, inv);
204 }
205 template <typename Archive>
206 void save(Archive& ar, const lanelet::ConstLineString3d& l, unsigned int /*version*/) {
207  auto inv = l.inverted();
208  auto ptr = lanelet::utils::removeConst(l.constData());
209  ar << inv;
210  ar << ptr;
211 }
212 template <typename Archive>
213 void load(Archive& ar, lanelet::ConstLineString3d& l, unsigned int /*version*/) {
214  std::shared_ptr<lanelet::LineStringData> ptr;
215  bool inv{};
216  ar >> inv;
217  ar >> ptr;
218  l = lanelet::LineString3d(ptr, inv);
219 }
220 
221 template <typename Archive>
222 void serialize(Archive& ar, lanelet::LineString2d& ls, unsigned int /*version*/) {
223  auto ls3d = lanelet::traits::to3D(ls);
224  ar& ls3d;
225  ls = lanelet::traits::to2D(ls3d);
226 }
227 
229 template <typename Archive>
230 void serialize(Archive& /*ar*/, lanelet::PointData& /*l*/, unsigned int /*version*/) {}
231 template <class Archive>
232 // NOLINTNEXTLINE
233 inline void save_construct_data(Archive& ar, const lanelet::PointData* p, unsigned int /*version*/) {
234  ar << p->id << p->attributes << p->point.x() << p->point.y() << p->point.z();
235 }
236 
237 template <class Archive>
238 // NOLINTNEXTLINE
239 inline void load_construct_data(Archive& ar, lanelet::PointData* p, unsigned int /*version*/) {
240  using namespace lanelet;
241  Id id = 0;
242  AttributeMap attrs;
243  BasicPoint3d pt;
244  ar >> id >> attrs >> pt.x() >> pt.y() >> pt.z();
245  new (p) PointData(id, pt, attrs);
246 }
247 
248 template <typename Archive>
249 void save(Archive& ar, const lanelet::Point3d& p, unsigned int /*version*/) {
250  auto ptr = lanelet::utils::removeConst(p.constData());
251  ar << ptr;
252 }
253 template <typename Archive>
254 void load(Archive& ar, lanelet::Point3d& p, unsigned int /*version*/) {
255  std::shared_ptr<lanelet::PointData> ptr;
256  ar >> ptr;
257  p = lanelet::Point3d(ptr);
258 }
259 template <typename Archive>
260 void save(Archive& ar, const lanelet::ConstPoint3d& p, unsigned int /*version*/) {
261  ar << lanelet::utils::removeConst(p.constData());
262 }
263 template <typename Archive>
264 void load(Archive& ar, lanelet::ConstPoint3d& p, unsigned int /*version*/) {
265  std::shared_ptr<lanelet::PointData> ptr;
266  ar >> ptr;
267  p = lanelet::Point3d(ptr);
268 }
269 
271 template <typename Archive>
272 void serialize(Archive& /*ar*/, lanelet::AreaData& /*a*/, unsigned int /*version*/) {}
273 template <class Archive>
274 // NOLINTNEXTLINE
275 inline void save_construct_data(Archive& ar, const lanelet::AreaData* a, unsigned int /*version*/) {
276  auto anc = const_cast<lanelet::AreaData*>(a); // NOLINT
277  ar << anc->id;
278  ar << anc->attributes;
279  ar << anc->innerBounds();
280  ar << anc->outerBound();
281  lanelet::impl::saveRegelems(ar, anc->regulatoryElements());
282 }
283 
284 template <class Archive>
285 // NOLINTNEXTLINE
286 inline void load_construct_data(Archive& ar, lanelet::AreaData* a, unsigned int /*version*/) {
287  using namespace lanelet;
288  Id id = 0;
289  AttributeMap attrs;
290  InnerBounds inner;
291  LineStrings3d outer;
292  ar >> id >> attrs >> inner >> outer;
293  new (a) AreaData(id, outer, inner, attrs);
295 }
296 
297 template <typename Archive>
298 void save(Archive& ar, const lanelet::Area& a, unsigned int /*version*/) {
299  auto ptr = lanelet::utils::removeConst(a.constData());
300  ar << ptr;
301 }
302 template <typename Archive>
303 void load(Archive& ar, lanelet::Area& a, unsigned int /*version*/) {
304  std::shared_ptr<lanelet::AreaData> ptr;
305  ar >> ptr;
306  a = lanelet::Area(ptr);
307 }
308 template <typename Archive>
309 void save(Archive& ar, const lanelet::ConstArea& a, unsigned int /*version*/) {
310  auto ptr = lanelet::utils::removeConst(a.constData());
311  ar << ptr;
312 }
313 template <typename Archive>
314 void load(Archive& ar, lanelet::ConstArea& a, unsigned int /*version*/) {
315  std::shared_ptr<lanelet::AreaData> ptr;
316  ar >> ptr;
317  a = lanelet::Area(ptr);
318 }
319 template <typename Archive>
320 void save(Archive& ar, const lanelet::WeakArea& a, unsigned int /*version*/) {
321  if (a.expired()) {
322  throw lanelet::LaneletError("Can not serialize expired weak pointer!");
323  }
324  auto sp = a.lock();
325  ar& sp;
326 }
327 template <typename Archive>
328 void load(Archive& ar, lanelet::WeakArea& a, unsigned int /*version*/) {
329  lanelet::Area area;
330  ar& area;
331  a = area;
332 }
333 
335 // Regluatory elements can not be directly serialized, because we need the factory function to create regelems of the
336 // correct type (ie child of RegulatoryElement)
338  public:
340  if (serializing_.find(regelem->id()) == serializing_.end()) {
341  serializing_.insert(regelem->id());
342  return false;
343  }
344  return true;
345  } // true if this is already serialized
346  private:
347  std::set<lanelet::Id> serializing_;
348 };
350  struct DeserialInfo {
352  std::vector<lanelet::RegulatoryElementPtr*> toDeserialize;
353  };
354 
355  public:
357  auto res = deserial_.find(id);
358  if (res == deserial_.end()) {
359  deserial_.emplace(id, DeserialInfo{});
360  return false;
361  }
362  if (!res->second.deserialResult) {
363  // wait until done
364  res->second.toDeserialize.push_back(&regelem);
365  } else {
366  regelem = res->second.deserialResult;
367  }
368 
369  return true;
370  }
372  auto& entry = deserial_.find(regelem->id())->second;
373  for (auto& elem : entry.toDeserialize) {
374  *elem = regelem;
375  }
376  entry.deserialResult = regelem;
377  }
378 
379  private:
380  std::map<lanelet::Id, DeserialInfo> deserial_;
381 };
382 
383 template <typename Archive>
384 void serialize(Archive& /*ar*/, lanelet::RegulatoryElementData& /*r*/, unsigned int /*version*/) {}
385 template <class Archive>
386 // NOLINTNEXTLINE
387 inline void save_construct_data(Archive& ar, const lanelet::RegulatoryElementData* r, unsigned int /*version*/) {
388  ar << r->id << r->attributes << r->parameters;
389 }
390 
391 template <class Archive>
392 // NOLINTNEXTLINE
393 inline void load_construct_data(Archive& ar, lanelet::RegulatoryElementData* r, unsigned int /*version*/) {
394  using namespace lanelet;
395  Id id = 0;
396  AttributeMap attr;
397  RuleParameterMap params;
398  ar >> id >> attr >> params;
399  new (r) RegulatoryElementData(id, params, attr);
400 }
401 
402 template <typename Archive>
403 void save(Archive& ar, const lanelet::RegulatoryElementPtr& r, unsigned int /*version*/) {
404  auto id = r->id();
405  ar << id;
406  auto& helper = ar.template get_helper<RegelemSerialization>(&ar);
407  if (helper.currentlySerializing(r)) {
408  return;
409  }
410  auto ptr = lanelet::utils::removeConst(r->constData());
411  ar << ptr;
412 }
413 
414 template <typename Archive>
415 void load(Archive& ar, lanelet::RegulatoryElementPtr& r, unsigned int /*version*/) {
416  auto& helper = ar.template get_helper<RegelemDeserialization>(&ar);
417  lanelet::Id id = 0;
418  ar >> id;
419  if (helper.currentlyDeserializing(id, r)) {
420  return;
421  }
422  std::shared_ptr<lanelet::RegulatoryElementData> ptr;
423  ar >> ptr;
424  auto typeAttr = ptr->attributes.find(lanelet::AttributeName::Subtype);
425  auto regeltype = typeAttr == ptr->attributes.end() ? "" : typeAttr->second.value();
426  r = lanelet::RegulatoryElementFactory::create(regeltype, ptr);
427  helper.deserializationDone(r); // will update all other instances using this regelem
428 }
429 
430 template <typename Archive>
431 void save(Archive& ar, const lanelet::RegulatoryElementConstPtr& r, unsigned int /*version*/) {
432  save(ar, const_pointer_cast<lanelet::RegulatoryElement>(r), 0);
433 }
434 
435 template <typename Archive>
436 void load(Archive& ar, lanelet::RegulatoryElementConstPtr& r, unsigned int /*version*/) {
437  load(ar, const_pointer_cast<lanelet::RegulatoryElement>(r), 0);
438 }
439 
440 template <typename Archive>
441 void save(Archive& ar, const lanelet::LaneletMap& m, unsigned int /*version*/) {
442  auto& mnc = const_cast<lanelet::LaneletMap&>(m); // NOLINT
443  auto storeLayer = [&ar](auto& layer) {
444  size_t size = layer.size();
445  ar << size;
446  for (auto& pt : layer) {
447  ar << pt;
448  }
449  };
450  storeLayer(mnc.pointLayer);
451  storeLayer(mnc.lineStringLayer);
452  storeLayer(mnc.polygonLayer);
453  storeLayer(mnc.areaLayer);
454  storeLayer(mnc.laneletLayer);
455  storeLayer(mnc.regulatoryElementLayer);
456 }
457 
458 template <typename Archive>
459 void load(Archive& ar, lanelet::LaneletMap& m, unsigned int /*version*/) {
460  auto loadLayer = [&ar](auto& layerMap) {
461  using Prim = typename std::decay_t<decltype(layerMap)>::mapped_type;
462  size_t size = 0;
463  ar >> size;
464  for (auto i = 0u; i < size; ++i) {
465  Prim p;
466  ar >> p;
467  layerMap.insert(std::pair<const lanelet::Id, Prim>(lanelet::utils::getId(p), p));
468  }
469  };
476  loadLayer(pMap);
477  loadLayer(lsMap);
478  loadLayer(polyMap);
479  loadLayer(arMap);
480  loadLayer(lltMap);
481  loadLayer(reMap);
482  m = lanelet::LaneletMap(lltMap, arMap, reMap, polyMap, lsMap, pMap);
483 }
484 
485 } // namespace serialization
486 } // namespace boost
487 
488 BOOST_SERIALIZATION_SPLIT_FREE(lanelet::AttributeMap)
489 BOOST_SERIALIZATION_SPLIT_FREE(lanelet::Attribute)
490 BOOST_SERIALIZATION_SPLIT_FREE(lanelet::WeakArea)
491 BOOST_SERIALIZATION_SPLIT_FREE(lanelet::Area)
492 BOOST_SERIALIZATION_SPLIT_FREE(lanelet::WeakLanelet)
493 BOOST_SERIALIZATION_SPLIT_FREE(lanelet::Lanelet)
494 BOOST_SERIALIZATION_SPLIT_FREE(lanelet::Point3d)
495 BOOST_SERIALIZATION_SPLIT_FREE(lanelet::ConstPoint3d) // NOLINT
496 BOOST_SERIALIZATION_SPLIT_FREE(lanelet::LineString3d)
497 BOOST_SERIALIZATION_SPLIT_FREE(lanelet::ConstLineString3d) // NOLINT
498 BOOST_SERIALIZATION_SPLIT_FREE(lanelet::Polygon3d)
499 BOOST_SERIALIZATION_SPLIT_FREE(lanelet::RuleParameterMap)
500 BOOST_SERIALIZATION_SPLIT_FREE(lanelet::RegulatoryElementPtr)
501 BOOST_SERIALIZATION_SPLIT_FREE(lanelet::RegulatoryElementConstPtr)
502 BOOST_SERIALIZATION_SPLIT_FREE(lanelet::LaneletMap)
boost::serialization::serialize
void serialize(Archive &, lanelet::LaneletData &, unsigned int)
lanelet +data
Definition: Serialize.h:75
LineStrings3d
std::vector< LineString3d > LineStrings3d
lanelet::Attribute
lanelet::traits::to2D
BasicPoint2d to2D(const BasicPoint3d &primitive)
lanelet::RegulatoryElementData
lanelet::LaneletData
LaneletMap.h
lanelet
lanelet::RegulatoryElementPtr
std::shared_ptr< RegulatoryElement > RegulatoryElementPtr
BasicPoint3d
Eigen::Vector3d BasicPoint3d
lanelet::ConstArea
boost::serialization::load
void load(Archive &ar, lanelet::Attribute &p, unsigned int)
Definition: Serialize.h:42
p
BasicPoint p
lanelet::ConstLanelet::inverted
bool inverted() const
lanelet::utils::getId
Id getId()
boost::serialization::save
void save(Archive &ar, const lanelet::Attribute &p, unsigned int)
Definition: Serialize.h:49
Id
int64_t Id
InnerBounds
std::vector< LineStrings3d > InnerBounds
boost
lanelet::WeakLanelet::lock
Lanelet lock() const
ConstLineStringImpl< Point3d >::inverted
bool inverted() const noexcept
boost::serialization::RegelemSerialization
Regulatory element.
Definition: Serialize.h:337
boost::serialization::RegelemDeserialization
Definition: Serialize.h:349
boost::serialization::RegelemDeserialization::DeserialInfo
Definition: Serialize.h:350
id
Id id
Definition: OsmHandlerWrite.cpp:243
boost::serialization::RegelemDeserialization::deserializationDone
void deserializationDone(lanelet::RegulatoryElementPtr &regelem)
Definition: Serialize.h:371
boost::serialization::RegelemSerialization::currentlySerializing
bool currentlySerializing(const lanelet::RegulatoryElementPtr &regelem)
Definition: Serialize.h:339
lanelet::LaneletData::hasCustomCenterline
bool hasCustomCenterline() const
lanelet::Area
lanelet::impl::saveRegelems
void saveRegelems(Archive &ar, RegelemsT regelems)
Definition: Serialize.h:19
lanelet::LineString2d
ConstPrimitive< LaneletData >::constData
const std::shared_ptr< const LaneletData > & constData() const
lanelet::ConstPoint3d
lanelet::LaneletMap
lanelet::LineStringData
lanelet::Lanelet
lanelet::ConstWeakLanelet::expired
bool expired() const noexcept
lanelet::WeakLanelet
lanelet::PrimitiveData::attributes
AttributeMap attributes
Points3d
std::vector< Point3d > Points3d
lanelet::WeakArea
lanelet::PrimitiveLayer< Point3d >::Map
std::unordered_map< Id, T > Map
lanelet::AreaData::regulatoryElements
RegulatoryElementPtrs & regulatoryElements()
boost::serialization::RegelemDeserialization::DeserialInfo::toDeserialize
std::vector< lanelet::RegulatoryElementPtr * > toDeserialize
Definition: Serialize.h:352
lanelet::LaneletData::centerline
ConstLineString3d centerline() const
boost::serialization::RegelemSerialization::serializing_
std::set< lanelet::Id > serializing_
Definition: Serialize.h:347
lanelet::AreaData
lanelet::traits::to3D
BasicPoint3d to3D(const BasicPoint2d &primitive)
lanelet::RegulatoryElementConstPtr
std::shared_ptr< const RegulatoryElement > RegulatoryElementConstPtr
lanelet::ConstWeakArea::expired
bool expired() const noexcept
lanelet::Point3d
boost::serialization::RegelemDeserialization::deserial_
std::map< lanelet::Id, DeserialInfo > deserial_
Definition: Serialize.h:380
HybridMap< Attribute, decltype(AttributeNamesString::Map)&, AttributeNamesString::Map >
lanelet::ConstLineString3d
lanelet::PointData
lanelet::Polygon3d
lanelet::LaneletError
lanelet::RegulatoryElementData::parameters
RuleParameterMap parameters
lanelet::utils::removeConst
T & removeConst(const T &t)
lanelet::ConstLanelet
boost::serialization::save_construct_data
void save_construct_data(Archive &ar, const lanelet::LaneletData *llt, unsigned int)
Definition: Serialize.h:78
lanelet::impl::loadRegelems
void loadRegelems(Archive &ar, RegelemsT &regelems)
Definition: Serialize.h:28
lanelet::PrimitiveData::id
Id id
lanelet::RegulatoryElementFactory::create
static RegulatoryElementPtr create(const std::string &ruleName, Id id, const RuleParameterMap &map, const AttributeMap &attributes=AttributeMap())
lanelet::LaneletData::setCenterline
void setCenterline(const LineString3d &centerline)
lanelet::LaneletMapLayers::size
size_t size() const noexcept
lanelet::LineString3d
lanelet::AttributeName::Subtype
@ Subtype
lanelet::WeakArea::lock
Area lock() const
boost::serialization::RegelemDeserialization::currentlyDeserializing
bool currentlyDeserializing(lanelet::Id id, lanelet::RegulatoryElementPtr &regelem)
Definition: Serialize.h:356
boost::serialization::load_construct_data
void load_construct_data(Archive &ar, lanelet::LaneletData *llt, unsigned int)
Definition: Serialize.h:94
lanelet::LaneletData::regulatoryElements
RegulatoryElementPtrs & regulatoryElements()
boost::serialization::RegelemDeserialization::DeserialInfo::deserialResult
lanelet::RegulatoryElementPtr deserialResult
Definition: Serialize.h:351


lanelet2_io
Author(s): Fabian Poggenhans
autogenerated on Thu Mar 6 2025 03:26:03