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

An immutable 3d point. More...

#include <Point.h>

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

Public Types

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

const BasicPointbasicPoint () const noexcept
 get a basic 3d point More...
 
 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...
 
 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
const BasicPointbasicPoint () const noexcept
 Get an Eigen point for faster calculations. More...
 
const BasicPoint2dbasicPoint2d () 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 Attributeattribute (AttributeName name) const
 retrieve an attribute (enum version) More...
 
const Attributeattribute (const std::string &name) const
 retrieve an attribute More...
 
attributeOr (AttributeName name, T defaultVal) const
 retrieve an attribute (enum version) More...
 
attributeOr (const std::string &name, T defaultVal) const noexcept
 retrieve an attribute (string 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 (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::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
 

Additional Inherited Members

- Protected Member Functions inherited from lanelet::ConstPoint2d
const BasicPoint3dpoint () const
 
const BasicPoint2dpoint2d () const
 
- Protected Member Functions inherited from lanelet::ConstPrimitive< PointData >
 ConstPrimitive (const ConstPrimitive &rhs)=default
 
 ConstPrimitive (ConstPrimitive &&rhs) noexcept=default
 
ConstPrimitiveoperator= (const ConstPrimitive &rhs)=default
 
ConstPrimitiveoperator= (ConstPrimitive &&rhs) noexcept=default
 
 ~ConstPrimitive () noexcept=default
 

Detailed Description

An immutable 3d point.

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

Member Typedef Documentation

◆ BasicPoint

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

◆ ConstType

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

◆ MutableType

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

Constructor & Destructor Documentation

◆ ConstPoint3d() [1/2]

lanelet::ConstPoint3d::ConstPoint3d ( )
default

◆ ConstPoint3d() [2/2]

lanelet::ConstPoint3d::ConstPoint3d ( const ConstPoint2d other)
inlineexplicit

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

Member Function Documentation

◆ basicPoint()

const BasicPoint& lanelet::ConstPoint3d::basicPoint ( ) const
inlinenoexcept

get a basic 3d point

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

◆ ConstPoint2d() [1/2]

lanelet::ConstPoint2d::ConstPoint2d
inline

Construct from an id and a point.

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

◆ ConstPoint2d() [2/2]

lanelet::ConstPoint2d::ConstPoint2d
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.

◆ operator BasicPoint2d()

lanelet::ConstPoint3d::operator BasicPoint2d ( ) const
deletenoexcept

◆ operator const BasicPoint3d &()

lanelet::ConstPoint3d::operator const BasicPoint3d & ( ) const
inlinenoexcept

Implicit cast to a basic 3d point.

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

◆ z()

double lanelet::ConstPoint3d::z ( ) const
inlinenoexcept

get the z coordinate

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

Member Data Documentation

◆ Dimension

constexpr traits::Dimensions lanelet::ConstPoint3d::Dimension = traits::Dimensions::Three
staticconstexpr

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


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


lanelet2_core
Author(s): Fabian Poggenhans
autogenerated on Thu Mar 6 2025 03:25:52