#include <Lanelet.h>
Public Types | |
using | ConstType = ConstWeakLanelet |
using | MutableType = WeakLanelet |
using | ThreeDType = ConstWeakLanelet |
using | TwoDType = ConstWeakLanelet |
Public Member Functions | |
ConstWeakLanelet ()=default | |
ConstWeakLanelet (const ConstLanelet &llet) | |
bool | expired () const noexcept |
tests whether the WeakLanelet is still valid More... | |
ConstLanelet | lock () const |
Obtains the original ConstLanelet. More... | |
Protected Attributes | |
bool | inverted_ {false} |
std::weak_ptr< const LaneletData > | laneletData_ |
Used internally by RegulatoryElements to avoid cyclic dependencies. Conceptually similar to a std::weak_ptr.
Definition at line 316 of file primitives/Lanelet.h.
Definition at line 318 of file primitives/Lanelet.h.
Definition at line 319 of file primitives/Lanelet.h.
Definition at line 321 of file primitives/Lanelet.h.
Definition at line 320 of file primitives/Lanelet.h.
|
default |
|
inline |
Definition at line 323 of file primitives/Lanelet.h.
|
inlinenoexcept |
tests whether the WeakLanelet is still valid
Definition at line 333 of file primitives/Lanelet.h.
|
inline |
Obtains the original ConstLanelet.
NullptrError | if the managed lanelet expired. |
Definition at line 330 of file primitives/Lanelet.h.
|
protected |
Definition at line 337 of file primitives/Lanelet.h.
|
protected |
Definition at line 336 of file primitives/Lanelet.h.