Public Types | Public Member Functions | Static Public Attributes | Protected Member Functions | List of all members
lanelet::Point2d Class Reference

A mutable 2d point. More...

#include <Point.h>

Inheritance diagram for lanelet::Point2d:
Inheritance graph
[legend]

Public Types

using BasicPoint = BasicPoint2d
 
using ConstType = ConstPoint2d
 
using MutableType = Point2d
 
using ThreeDType = Point3d
 
using TwoDType = Point2d
 
- Public Types inherited from lanelet::Primitive< ConstPoint3d >
using DataType = typename ConstPoint3d ::DataType
 
- Public Types inherited from lanelet::ConstPoint3d
using BasicPoint = BasicPoint3d
 
using ConstType = ConstPoint3d
 
using MutableType = Point3d
 
- Public Types inherited from lanelet::ConstPoint2d
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

auto basicPoint () noexcept
 get a mutable reference to the 2d point data More...
 
const BasicPoint2dbasicPoint () const noexcept
 get a basic 2d point More...
 
 operator BasicPoint2d () const noexcept
 Cast to a basic 2d point. More...
 
 operator const BasicPoint3d & () const =delete
 
 Point2d ()=default
 
double & x () noexcept
 gets a mutable reference to the x coordinate More...
 
double & y () noexcept
 gets a mutable reference to the y coordinate More...
 
double z () const noexcept=delete
 
- Public Member Functions inherited from lanelet::Primitive< ConstPoint3d >
AttributeMapattributes () noexcept
 get the attributes in a mutable way More...
 
 Primitive ()=default
 
 Primitive (const std::shared_ptr< const DataType > &)=delete
 
 Primitive (const std::shared_ptr< DataType > &data)
 Construct a new primitive from shared_ptr to its data. More...
 
 Primitive (const Primitive< OtherT > &rhs)
 Construct from another primitive. Only works if both share the same. More...
 
void setAttribute (const std::string &name, const Attribute &attribute)
 set or overwrite an attribute More...
 
void setAttribute (AttributeName name, const Attribute &attribute)
 set or overwrite an attribute (enum version) More...
 
void setId (Id id) noexcept
 set a new id for this primitive More...
 
- Public Member Functions inherited from lanelet::ConstPoint3d
const BasicPointbasicPoint () const noexcept
 get a basic 3d point More...
 
 ConstPoint3d ()=default
 
 ConstPoint3d (const ConstPoint2d &other)
 
 operator BasicPoint2d () const noexcept=delete
 
 operator const BasicPoint3d & () const noexcept
 Implicit cast to a basic 3d point. More...
 
double z () const noexcept
 get the z coordinate More...
 
- Public Member Functions inherited from lanelet::ConstPoint2d
 ConstPoint2d (Id id, const BasicPoint3d &point, const AttributeMap &attributes=AttributeMap())
 Construct from an id and a point. More...
 
- Public Member Functions inherited from lanelet::ConstPrimitive< PointData >
const Attributeattribute (const std::string &name) const
 retrieve an attribute More...
 
const Attributeattribute (AttributeName name) const
 retrieve an attribute (enum version) More...
 
attributeOr (const std::string &name, T defaultVal) const noexcept
 retrieve an attribute (string version) More...
 
attributeOr (AttributeName name, T defaultVal) const
 retrieve an attribute (enum version) More...
 
const AttributeMapattributes () 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 (const std::string &name) const noexcept
 check whether this primitive has a specific attribute More...
 
bool hasAttribute (AttributeName name) const noexcept
 check for an attribute (enum version) 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::Primitive< ConstPoint3d >
static constexpr bool IsConst
 
- Static Public Attributes inherited from lanelet::ConstPoint3d
static constexpr traits::Dimensions Dimension = traits::Dimensions::Three
 
- Static Public Attributes inherited from lanelet::ConstPoint2d
static constexpr traits::Dimensions Dimension = traits::Dimensions::Two
 
- Static Public Attributes inherited from lanelet::ConstPrimitive< PointData >
static constexpr bool IsConst
 

Protected Member Functions

BasicPoint3dpoint ()
 
- Protected Member Functions inherited from lanelet::Primitive< ConstPoint3d >
std::shared_ptr< DataTypedata () const
 
Primitiveoperator= (Primitive &&rhs) noexcept
 
Primitiveoperator= (const Primitive &rhs) noexcept
 
 Primitive (Primitive &&rhs) noexcept
 
 Primitive (const Primitive &rhs) noexcept
 
 ~Primitive () noexcept=default
 
- Protected Member Functions inherited from lanelet::ConstPrimitive< PointData >
 ConstPrimitive (ConstPrimitive &&rhs) noexcept=default
 
 ConstPrimitive (const ConstPrimitive &rhs)=default
 
ConstPrimitiveoperator= (ConstPrimitive &&rhs) noexcept=default
 
ConstPrimitiveoperator= (const ConstPrimitive &rhs)=default
 
 ~ConstPrimitive () noexcept=default
 

Detailed Description

A mutable 2d point.

Definition at line 230 of file primitives/Point.h.

Member Typedef Documentation

◆ BasicPoint

Definition at line 232 of file primitives/Point.h.

◆ ConstType

Definition at line 233 of file primitives/Point.h.

◆ MutableType

Definition at line 234 of file primitives/Point.h.

◆ ThreeDType

Definition at line 236 of file primitives/Point.h.

◆ TwoDType

Definition at line 235 of file primitives/Point.h.

Constructor & Destructor Documentation

◆ Point2d()

lanelet::Point2d::Point2d ( )
default

Member Function Documentation

◆ basicPoint() [1/2]

auto lanelet::Point2d::basicPoint ( )
inlinenoexcept

get a mutable reference to the 2d point data

Definition at line 251 of file primitives/Point.h.

◆ basicPoint() [2/2]

const BasicPoint2d& lanelet::Point2d::basicPoint ( ) const
inlinenoexcept

get a basic 2d point

Definition at line 254 of file primitives/Point.h.

◆ operator BasicPoint2d()

lanelet::Point2d::operator BasicPoint2d ( ) const
inlinenoexcept

Cast to a basic 2d point.

Definition at line 246 of file primitives/Point.h.

◆ operator const BasicPoint3d &()

lanelet::Point2d::operator const BasicPoint3d & ( ) const
delete

◆ point()

BasicPoint3d& lanelet::Point2d::point ( )
inlineprotected

Definition at line 265 of file primitives/Point.h.

◆ x()

double& lanelet::Point2d::x ( )
inlinenoexcept

gets a mutable reference to the x coordinate

Definition at line 257 of file primitives/Point.h.

◆ y()

double& lanelet::Point2d::y ( )
inlinenoexcept

gets a mutable reference to the y coordinate

Definition at line 260 of file primitives/Point.h.

◆ z()

double lanelet::Point2d::z ( ) const
deletenoexcept

Member Data Documentation

◆ Dimension

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

Definition at line 237 of file primitives/Point.h.


The documentation for this class was generated from the following file:


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