Class ConstPoint2d

Inheritance Relationships

Base Type

Derived Type

Class Documentation

class ConstPoint2d : public lanelet::ConstPrimitive<PointData>

An immutable 2d point.

Subclassed by lanelet::ConstPoint3d

Public Types

using BasicPoint = BasicPoint2d

returned basic point type

using ConstType = ConstPoint2d
using MutableType = Point2d
using TwoDType = ConstPoint2d
using ThreeDType = ConstPoint3d
using Category = traits::PointTag

Public Functions

inline ConstPoint2d(Id id, const BasicPoint3d &point, const AttributeMap &attributes = AttributeMap())

Construct from an id and a point.

inline explicit ConstPoint2d(Id id = InvalId, double x = 0., double y = 0., double z = 0., const AttributeMap &attributes = AttributeMap())

Construct from an id and coordinates.

The z coordinate is required because this point can be converted to a 3d point, where z matters.

inline operator BasicPoint2d() const noexcept

A ConstPoint 2d is implicitly convertible to a normal 2d point.

inline const BasicPoint &basicPoint() const noexcept

Get an Eigen point for faster calculations.

inline const BasicPoint2d &basicPoint2d() const noexcept

Get a 2d Eigen point. Does not make sense for this particular class, but for its children.

inline double x() const noexcept

gets x coordinate

inline double y() const noexcept

gets y coordinate

inline explicit ConstPrimitive(const std::shared_ptr<const Data> &data)

Construct from a pointer to the data.

Parameters:

data – internal data for this primitive. Must not be null.

ConstPrimitive(ConstPrimitive &&rhs) noexcept = default
ConstPrimitive(const ConstPrimitive &rhs) = default

Public Static Attributes

static constexpr traits::Dimensions Dimension = traits::Dimensions::Two

Protected Functions

inline const BasicPoint3d &point() const
inline const BasicPoint2d &point2d() const