An immutable 2d point. More...
#include <Point.h>

Public Types | |
| using | BasicPoint = BasicPoint2d |
| returned basic point type More... | |
| using | Category = traits::PointTag |
| using | ConstType = ConstPoint2d |
| using | MutableType = Point2d |
| using | ThreeDType = ConstPoint3d |
| using | TwoDType = ConstPoint2d |
Public Types inherited from lanelet::ConstPrimitive< PointData > | |
| using | DataType = PointData |
Public Member Functions | |
| const BasicPoint & | basicPoint () const noexcept |
| Get an Eigen point for faster calculations. More... | |
| const BasicPoint2d & | basicPoint2d () const noexcept |
| ConstPoint2d (Id id, const BasicPoint3d &point, const AttributeMap &attributes=AttributeMap()) | |
| Construct from an id and a point. More... | |
| ConstPoint2d (Id id=InvalId, double x=0., double y=0., double z=0., const AttributeMap &attributes=AttributeMap()) | |
| Construct from an id and coordinates. More... | |
| ConstPrimitive (const ConstPrimitive &rhs)=default | |
| ConstPrimitive (const std::shared_ptr< const Data > &data) | |
| Construct from a pointer to the data. More... | |
| ConstPrimitive (ConstPrimitive &&rhs) noexcept=default | |
| operator BasicPoint2d () const noexcept | |
| A ConstPoint 2d is implicitly convertible to a normal 2d point. More... | |
| double | x () const noexcept |
| gets x coordinate More... | |
| double | y () const noexcept |
| gets y coordinate More... | |
Public Member Functions inherited from lanelet::ConstPrimitive< PointData > | |
| const Attribute & | attribute (AttributeName name) const |
| retrieve an attribute (enum version) More... | |
| const Attribute & | attribute (const std::string &name) const |
| retrieve an attribute More... | |
| T | attributeOr (AttributeName name, T defaultVal) const |
| retrieve an attribute (enum version) More... | |
| T | attributeOr (const std::string &name, T defaultVal) const noexcept |
| retrieve an attribute (string version) More... | |
| const AttributeMap & | attributes () const |
| get the attributes of this primitive More... | |
| const std::shared_ptr< const PointData > & | constData () const |
| get the internal data of this primitive More... | |
| ConstPrimitive (const std::shared_ptr< const PointData > &data) | |
| Construct from a pointer to the data. More... | |
| bool | hasAttribute (AttributeName name) const noexcept |
| check for an attribute (enum version) More... | |
| bool | hasAttribute (const std::string &name) const noexcept |
| check whether this primitive has a specific attribute More... | |
| Id | id () const noexcept |
| get the unique id of this primitive More... | |
| bool | operator!= (const ConstPrimitive &rhs) const |
| bool | operator== (const ConstPrimitive &rhs) const |
Static Public Attributes | |
| static constexpr traits::Dimensions | Dimension = traits::Dimensions::Two |
Static Public Attributes inherited from lanelet::ConstPrimitive< PointData > | |
| static constexpr bool | IsConst |
Protected Member Functions | |
| const BasicPoint3d & | point () const |
| const BasicPoint2d & | point2d () const |
Protected Member Functions inherited from lanelet::ConstPrimitive< PointData > | |
| ConstPrimitive (const ConstPrimitive &rhs)=default | |
| ConstPrimitive (ConstPrimitive &&rhs) noexcept=default | |
| ConstPrimitive & | operator= (const ConstPrimitive &rhs)=default |
| ConstPrimitive & | operator= (ConstPrimitive &&rhs) noexcept=default |
| ~ConstPrimitive () noexcept=default | |
An immutable 2d point.
Definition at line 150 of file primitives/Point.h.
returned basic point type
Definition at line 152 of file primitives/Point.h.
Definition at line 157 of file primitives/Point.h.
Definition at line 153 of file primitives/Point.h.
Definition at line 154 of file primitives/Point.h.
Definition at line 156 of file primitives/Point.h.
Definition at line 155 of file primitives/Point.h.
|
inline |
Construct from an id and a point.
Definition at line 163 of file primitives/Point.h.
|
inlineexplicit |
Construct from an id and coordinates.
The z coordinate is required because this point can be converted to a 3d point, where z matters.
Definition at line 171 of file primitives/Point.h.
|
inlinenoexcept |
Get an Eigen point for faster calculations.
Definition at line 182 of file primitives/Point.h.
|
inlinenoexcept |
Get a 2d Eigen point. Does not make sense for this particular class, but for its children.
Definition at line 186 of file primitives/Point.h.
|
default |
|
inlineexplicit |
Construct from a pointer to the data.
| data | internal data for this primitive. Must not be null. |
Definition at line 78 of file Primitive.h.
|
defaultnoexcept |
|
inlinenoexcept |
A ConstPoint 2d is implicitly convertible to a normal 2d point.
Definition at line 177 of file primitives/Point.h.
|
inlineprotected |
Definition at line 195 of file primitives/Point.h.
|
inlineprotected |
Definition at line 196 of file primitives/Point.h.
|
inlinenoexcept |
gets x coordinate
Definition at line 189 of file primitives/Point.h.
|
inlinenoexcept |
gets y coordinate
Definition at line 192 of file primitives/Point.h.
|
staticconstexpr |
Definition at line 158 of file primitives/Point.h.