Main MRPT website > C++ reference
MRPT logo
List of all members | Public Member Functions | Static Public Member Functions | Public Attributes

Detailed Description

Lightweight 3D point.

Allows coordinate access using [] operator.

See also
mrpt::poses::CPoint3D, mrpt::math::TPoint3Df

Definition at line 302 of file lightweight_geom_data.h.

#include <mrpt/math/lightweight_geom_data.h>

Public Member Functions

 TPoint3D (double xx, double yy, double zz)
 Constructor from coordinates. More...
 
 TPoint3D ()
 Default fast constructor. More...
 
 TPoint3D (const TPoint3Df &p)
 Explicit constructor from coordinates. More...
 
 TPoint3D (const TPoint2D &p)
 Implicit constructor from TPoint2D. More...
 
 TPoint3D (const TPose2D &p)
 Constructor from TPose2D, losing information. More...
 
 TPoint3D (const TPose3D &p)
 Constructor from TPose3D, losing information. More...
 
 TPoint3D (const mrpt::poses::CPoint3D &p)
 Implicit constructor from heavyweight type. More...
 
 TPoint3D (const mrpt::poses::CPose3D &p)
 Constructor from heavyweight 3D pose. More...
 
double & operator[] (size_t i)
 Unsafe coordinate access using operator[]. More...
 
const double & operator[] (size_t i) const
 Unsafe coordinate access using operator[]. More...
 
double distanceTo (const TPoint3D &p) const
 Point-to-point distance. More...
 
double sqrDistanceTo (const TPoint3D &p) const
 Point-to-point distance, squared. More...
 
double norm () const
 Point norm. More...
 
TPoint3Doperator*= (const double f)
 Point scale. More...
 
void getAsVector (vector_double &v) const
 Transformation into vector. More...
 
TPoint3Doperator+= (const TPoint3D &p)
 Translation. More...
 
TPoint3Doperator-= (const TPoint3D &p)
 Difference between points. More...
 
TPoint3D operator+ (const TPoint3D &p) const
 Points addition. More...
 
TPoint3D operator- (const TPoint3D &p) const
 Points substraction. More...
 
TPoint3D operator* (double d) const
 
TPoint3D operator/ (double d) const
 
bool operator< (const TPoint3D &p) const
 
void asString (std::string &s) const
 Returns a human-readable textual representation of the object (eg: "[0.02 1.04 -0.8]" ) More...
 
std::string asString () const
 
void fromString (const std::string &s)
 Set the current object value from a string generated by 'asString' (eg: "[0.02 1.04 -0.8]" ) More...
 

Static Public Member Functions

static size_t size ()
 

Public Attributes

double x
 X coordinate. More...
 
double y
 Y coordinate. More...
 
double z
 Z coordinate. More...
 

Constructor & Destructor Documentation

◆ TPoint3D() [1/8]

mrpt::math::TPoint3D::TPoint3D ( double  xx,
double  yy,
double  zz 
)
inline

Constructor from coordinates.

Definition at line 308 of file lightweight_geom_data.h.

◆ TPoint3D() [2/8]

mrpt::math::TPoint3D::TPoint3D ( )
inline

Default fast constructor.

Initializes to garbage.

Definition at line 310 of file lightweight_geom_data.h.

◆ TPoint3D() [3/8]

mrpt::math::TPoint3D::TPoint3D ( const TPoint3Df p)
inlineexplicit

Explicit constructor from coordinates.

Definition at line 312 of file lightweight_geom_data.h.

◆ TPoint3D() [4/8]

mrpt::math::TPoint3D::TPoint3D ( const TPoint2D p)

Implicit constructor from TPoint2D.

Zeroes the z.

See also
TPoint2D

◆ TPoint3D() [5/8]

mrpt::math::TPoint3D::TPoint3D ( const TPose2D p)
explicit

Constructor from TPose2D, losing information.

Zeroes the z.

See also
TPose2D

◆ TPoint3D() [6/8]

mrpt::math::TPoint3D::TPoint3D ( const TPose3D p)
explicit

Constructor from TPose3D, losing information.

See also
TPose3D

◆ TPoint3D() [7/8]

mrpt::math::TPoint3D::TPoint3D ( const mrpt::poses::CPoint3D p)

Implicit constructor from heavyweight type.

See also
mrpt::poses::CPoint3D

◆ TPoint3D() [8/8]

mrpt::math::TPoint3D::TPoint3D ( const mrpt::poses::CPose3D p)
explicit

Constructor from heavyweight 3D pose.

See also
mrpt::poses::CPose3D.

Member Function Documentation

◆ asString() [1/2]

void mrpt::math::TPoint3D::asString ( std::string &  s) const
inline

Returns a human-readable textual representation of the object (eg: "[0.02 1.04 -0.8]" )

See also
fromString

Definition at line 426 of file lightweight_geom_data.h.

References mrpt::mrpt::format().

◆ asString() [2/2]

std::string mrpt::math::TPoint3D::asString ( ) const
inline

Definition at line 427 of file lightweight_geom_data.h.

References asString().

Referenced by asString().

◆ distanceTo()

double mrpt::math::TPoint3D::distanceTo ( const TPoint3D p) const
inline

Point-to-point distance.

Definition at line 353 of file lightweight_geom_data.h.

References mrpt::utils::square(), x, y, and z.

◆ fromString()

void mrpt::math::TPoint3D::fromString ( const std::string &  s)

Set the current object value from a string generated by 'asString' (eg: "[0.02 1.04 -0.8]" )

See also
asString
Exceptions
std::exceptionOn invalid format

◆ getAsVector()

void mrpt::math::TPoint3D::getAsVector ( vector_double v) const
inline

Transformation into vector.

Definition at line 378 of file lightweight_geom_data.h.

References mrpt::dynamicsize_vector< T >::resize().

◆ norm()

double mrpt::math::TPoint3D::norm ( ) const
inline

Point norm.

Definition at line 365 of file lightweight_geom_data.h.

References mrpt::utils::square().

◆ operator*()

TPoint3D mrpt::math::TPoint3D::operator* ( double  d) const
inline

Definition at line 413 of file lightweight_geom_data.h.

◆ operator*=()

TPoint3D& mrpt::math::TPoint3D::operator*= ( const double  f)
inline

Point scale.

Definition at line 371 of file lightweight_geom_data.h.

◆ operator+()

TPoint3D mrpt::math::TPoint3D::operator+ ( const TPoint3D p) const
inline

Points addition.

Definition at line 403 of file lightweight_geom_data.h.

References x, y, and z.

◆ operator+=()

TPoint3D& mrpt::math::TPoint3D::operator+= ( const TPoint3D p)
inline

Translation.

Definition at line 385 of file lightweight_geom_data.h.

References x, y, and z.

◆ operator-()

TPoint3D mrpt::math::TPoint3D::operator- ( const TPoint3D p) const
inline

Points substraction.

Definition at line 409 of file lightweight_geom_data.h.

References x, y, and z.

◆ operator-=()

TPoint3D& mrpt::math::TPoint3D::operator-= ( const TPoint3D p)
inline

Difference between points.

Definition at line 394 of file lightweight_geom_data.h.

References x, y, and z.

◆ operator/()

TPoint3D mrpt::math::TPoint3D::operator/ ( double  d) const
inline

Definition at line 417 of file lightweight_geom_data.h.

◆ operator<()

bool mrpt::math::TPoint3D::operator< ( const TPoint3D p) const

◆ operator[]() [1/2]

double& mrpt::math::TPoint3D::operator[] ( size_t  i)
inline

Unsafe coordinate access using operator[].

Intended for loops.

Definition at line 341 of file lightweight_geom_data.h.

◆ operator[]() [2/2]

const double& mrpt::math::TPoint3D::operator[] ( size_t  i) const
inline

Unsafe coordinate access using operator[].

Intended for loops.

Definition at line 347 of file lightweight_geom_data.h.

◆ size()

static size_t mrpt::math::TPoint3D::size ( )
inlinestatic

Definition at line 434 of file lightweight_geom_data.h.

◆ sqrDistanceTo()

double mrpt::math::TPoint3D::sqrDistanceTo ( const TPoint3D p) const
inline

Point-to-point distance, squared.

Definition at line 359 of file lightweight_geom_data.h.

References mrpt::utils::square(), x, y, and z.

Member Data Documentation

◆ x

double mrpt::math::TPoint3D::x

X coordinate.

Definition at line 303 of file lightweight_geom_data.h.

Referenced by mrpt::slam::CPointsMap::boundingBox(), mrpt::poses::CPose3DRotVec::composePoint(), mrpt::poses::CPose3D::composePoint(), mrpt::poses::CPoint2D::CPoint2D(), mrpt::poses::CPoint3D::CPoint3D(), mrpt::opengl::CPolyhedron::CreateCubicPrism(), mrpt::poses::CPoseOrPoint< CPoint3D >::distanceTo(), distanceTo(), mrpt::topography::GeodeticToUTM(), mrpt::srba::observations::Cartesian_3D::obs_data_t::getAsArray(), mrpt::math::TSegment3D::getCenter(), mrpt::slam::CPointsMap::getPoint(), mrpt::opengl::graph_tools::graph_visualize(), mrpt::slam::CColouredPointsMap::insertPoint(), mrpt::slam::CPointsMap::insertPoint(), mrpt::poses::CPose3D::inverseComposePoint(), mrpt::math::KDTreeCapable< CFeatureList >::kdTreeClosestPoint3D(), mrpt::math::KDTreeCapable< CFeatureList >::kdTreeNClosestPoint3D(), mrpt::math::KDTreeCapable< CFeatureList >::kdTreeNClosestPoint3DIdx(), mrpt::srba::sensor_model< landmarks::Euclidean3D, observations::RangeBearing_3D >::observe_error(), mrpt::math::operator!=(), operator+(), operator+=(), operator-(), mrpt::math::operator-(), operator-=(), mrpt::math::operator==(), mrpt::math::project3D(), mrpt::vision::pinhole::projectPoint_no_distortion(), mrpt::srba::landmarks::Euclidean3D::relativeEuclideanLocation(), mrpt::srba::landmarks::Euclidean2D::relativeEuclideanLocation(), mrpt::srba::LandmarkRendererBase< landmark_rendering_as_point >::render(), mrpt::opengl::CRenderizable::setLocation(), mrpt::opengl::CCamera::setPointingAt(), sqrDistanceTo(), and mrpt::topography::UTMToGeodetic().

◆ y

double mrpt::math::TPoint3D::y

Y coordinate.

Definition at line 304 of file lightweight_geom_data.h.

Referenced by mrpt::slam::CPointsMap::boundingBox(), mrpt::poses::CPose3DRotVec::composePoint(), mrpt::poses::CPose3D::composePoint(), mrpt::poses::CPoint2D::CPoint2D(), mrpt::poses::CPoint3D::CPoint3D(), mrpt::opengl::CPolyhedron::CreateCubicPrism(), mrpt::poses::CPoseOrPoint< CPoint3D >::distanceTo(), distanceTo(), mrpt::topography::GeodeticToUTM(), mrpt::srba::observations::Cartesian_3D::obs_data_t::getAsArray(), mrpt::math::TSegment3D::getCenter(), mrpt::slam::CPointsMap::getPoint(), mrpt::opengl::graph_tools::graph_visualize(), mrpt::slam::CColouredPointsMap::insertPoint(), mrpt::slam::CPointsMap::insertPoint(), mrpt::poses::CPose3D::inverseComposePoint(), mrpt::math::KDTreeCapable< CFeatureList >::kdTreeClosestPoint3D(), mrpt::math::KDTreeCapable< CFeatureList >::kdTreeNClosestPoint3D(), mrpt::math::KDTreeCapable< CFeatureList >::kdTreeNClosestPoint3DIdx(), mrpt::srba::sensor_model< landmarks::Euclidean3D, observations::RangeBearing_3D >::observe_error(), mrpt::math::operator!=(), operator+(), operator+=(), operator-(), mrpt::math::operator-(), operator-=(), mrpt::math::operator==(), mrpt::math::project3D(), mrpt::vision::pinhole::projectPoint_no_distortion(), mrpt::srba::landmarks::Euclidean3D::relativeEuclideanLocation(), mrpt::srba::landmarks::Euclidean2D::relativeEuclideanLocation(), mrpt::srba::LandmarkRendererBase< landmark_rendering_as_point >::render(), mrpt::opengl::CRenderizable::setLocation(), mrpt::opengl::CCamera::setPointingAt(), sqrDistanceTo(), and mrpt::topography::UTMToGeodetic().

◆ z

double mrpt::math::TPoint3D::z

Z coordinate.

Definition at line 305 of file lightweight_geom_data.h.

Referenced by mrpt::slam::CPointsMap::boundingBox(), mrpt::poses::CPose3DRotVec::composePoint(), mrpt::poses::CPose3D::composePoint(), mrpt::poses::CPoint3D::CPoint3D(), mrpt::opengl::CPolyhedron::CreateCubicPrism(), mrpt::poses::CPoseOrPoint< CPoint3D >::distanceTo(), distanceTo(), mrpt::topography::GeodeticToUTM(), mrpt::srba::observations::Cartesian_3D::obs_data_t::getAsArray(), mrpt::math::TSegment3D::getCenter(), mrpt::slam::CPointsMap::getPoint(), mrpt::opengl::graph_tools::graph_visualize(), mrpt::slam::CColouredPointsMap::insertPoint(), mrpt::slam::CPointsMap::insertPoint(), mrpt::poses::CPose3D::inverseComposePoint(), mrpt::math::KDTreeCapable< CFeatureList >::kdTreeClosestPoint3D(), mrpt::math::KDTreeCapable< CFeatureList >::kdTreeNClosestPoint3D(), mrpt::math::KDTreeCapable< CFeatureList >::kdTreeNClosestPoint3DIdx(), mrpt::srba::sensor_model< landmarks::Euclidean3D, observations::RangeBearing_3D >::observe_error(), mrpt::math::operator!=(), operator+(), operator+=(), operator-(), mrpt::math::operator-(), operator-=(), mrpt::math::operator==(), mrpt::math::project3D(), mrpt::vision::pinhole::projectPoint_no_distortion(), mrpt::srba::landmarks::Euclidean3D::relativeEuclideanLocation(), mrpt::srba::landmarks::Euclidean2D::relativeEuclideanLocation(), mrpt::srba::LandmarkRendererBase< landmark_rendering_as_point >::render(), mrpt::opengl::CRenderizable::setLocation(), mrpt::opengl::CCamera::setPointingAt(), sqrDistanceTo(), and mrpt::topography::UTMToGeodetic().




Page generated by Doxygen 1.8.14 for MRPT 1.0.2 SVN: at lun oct 28 00:52:41 CET 2019 Hosted on:
SourceForge.net Logo