Lightweight 3D point.
Allows coordinate access using [] operator.
Definition at line 229 of file lightweight_geom_data.h.
#include <mrpt/math/lightweight_geom_data.h>
Public Types | |
enum | { static_size = 3 } |
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) |
Coordinate access using operator[]. More... | |
const double & | operator[] (size_t i) const |
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... | |
TPoint3D & | operator*= (const double f) |
Point scale. More... | |
template<class VECTORLIKE > | |
void | getAsVector (VECTORLIKE &v) const |
Transformation into vector. More... | |
TPoint3D & | operator+= (const TPoint3D &p) |
Translation. More... | |
TPoint3D & | operator-= (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 |
double | y |
double | z |
X,Y,Z coordinates. More... | |
anonymous enum |
Enumerator | |
---|---|
static_size |
Definition at line 230 of file lightweight_geom_data.h.
|
inline |
|
inline |
Default fast constructor.
Initializes to garbage.
Definition at line 236 of file lightweight_geom_data.h.
|
inlineexplicit |
mrpt::math::TPoint3D::TPoint3D | ( | const TPoint2D & | p | ) |
|
explicit |
|
explicit |
mrpt::math::TPoint3D::TPoint3D | ( | const mrpt::poses::CPoint3D & | p | ) |
Implicit constructor from heavyweight type.
|
explicit |
Constructor from heavyweight 3D pose.
|
inline |
Definition at line 346 of file lightweight_geom_data.h.
References asString().
Referenced by asString().
|
inline |
Returns a human-readable textual representation of the object (eg: "[0.02 1.04 -0.8]" )
Definition at line 345 of file lightweight_geom_data.h.
References mrpt::format().
|
inline |
Point-to-point distance.
Definition at line 271 of file lightweight_geom_data.h.
References mrpt::utils::square(), x, y, and z.
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]" )
std::exception | On invalid format |
|
inline |
Transformation into vector.
Definition at line 297 of file lightweight_geom_data.h.
|
inline |
Point norm.
Definition at line 283 of file lightweight_geom_data.h.
References mrpt::utils::square().
|
inline |
Definition at line 332 of file lightweight_geom_data.h.
|
inline |
Point scale.
Definition at line 289 of file lightweight_geom_data.h.
Points substraction.
Definition at line 328 of file lightweight_geom_data.h.
Difference between points.
Definition at line 313 of file lightweight_geom_data.h.
|
inline |
Definition at line 336 of file lightweight_geom_data.h.
bool mrpt::math::TPoint3D::operator< | ( | const TPoint3D & | p | ) | const |
|
inline |
Coordinate access using operator[].
Order: x,y,z
Definition at line 265 of file lightweight_geom_data.h.
|
inline |
Coordinate access using operator[].
Order: x,y,z
Definition at line 267 of file lightweight_geom_data.h.
|
inlinestatic |
Definition at line 353 of file lightweight_geom_data.h.
|
inline |
Point-to-point distance, squared.
Definition at line 277 of file lightweight_geom_data.h.
References mrpt::utils::square(), x, y, and z.
double mrpt::math::TPoint3D::x |
Definition at line 231 of file lightweight_geom_data.h.
Referenced by mrpt::maps::CPointsMap::boundingBox(), mrpt::maps::COctoMapBase< OCTREE, OCTREE_NODE >::castRay(), mrpt::poses::CPose3D::composePoint(), mrpt::poses::CPose3DRotVec::composePoint(), mrpt::poses::CPoint2D::CPoint2D(), mrpt::poses::CPoint3D::CPoint3D(), mrpt::poses::CPoseOrPoint< DERIVEDCLASS >::distanceTo(), distanceTo(), mrpt::topography::GeodeticToUTM(), mrpt::math::TSegment3D::getCenter(), mrpt::maps::CPointsMap::getPoint(), mrpt::opengl::graph_tools::graph_visualize(), mrpt::maps::CColouredPointsMap::insertPoint(), mrpt::maps::CPointsMap::insertPoint(), mrpt::poses::CPose3D::inverseComposePoint(), mrpt::math::KDTreeCapable< Derived, num_t, metric_t >::kdTreeClosestPoint3D(), mrpt::math::KDTreeCapable< Derived, num_t, metric_t >::kdTreeNClosestPoint3D(), mrpt::math::KDTreeCapable< Derived, num_t, metric_t >::kdTreeNClosestPoint3DIdx(), mrpt::math::operator!=(), operator+(), operator+=(), operator-(), mrpt::math::operator-(), operator-=(), mrpt::math::operator==(), mrpt::math::project3D(), mrpt::vision::pinhole::projectPoint_no_distortion(), mrpt::opengl::CRenderizable::setLocation(), mrpt::maps::CPointsMap::setPoint(), mrpt::opengl::CCamera::setPointingAt(), sqrDistanceTo(), and mrpt::topography::UTMToGeodetic().
double mrpt::math::TPoint3D::y |
Definition at line 231 of file lightweight_geom_data.h.
Referenced by mrpt::maps::CPointsMap::boundingBox(), mrpt::maps::COctoMapBase< OCTREE, OCTREE_NODE >::castRay(), mrpt::poses::CPose3D::composePoint(), mrpt::poses::CPose3DRotVec::composePoint(), mrpt::poses::CPoint2D::CPoint2D(), mrpt::poses::CPoint3D::CPoint3D(), mrpt::poses::CPoseOrPoint< DERIVEDCLASS >::distanceTo(), distanceTo(), mrpt::topography::GeodeticToUTM(), mrpt::math::TSegment3D::getCenter(), mrpt::maps::CPointsMap::getPoint(), mrpt::opengl::graph_tools::graph_visualize(), mrpt::maps::CColouredPointsMap::insertPoint(), mrpt::maps::CPointsMap::insertPoint(), mrpt::poses::CPose3D::inverseComposePoint(), mrpt::math::KDTreeCapable< Derived, num_t, metric_t >::kdTreeClosestPoint3D(), mrpt::math::KDTreeCapable< Derived, num_t, metric_t >::kdTreeNClosestPoint3D(), mrpt::math::KDTreeCapable< Derived, num_t, metric_t >::kdTreeNClosestPoint3DIdx(), mrpt::math::operator!=(), operator+(), operator+=(), operator-(), mrpt::math::operator-(), operator-=(), mrpt::math::operator==(), mrpt::math::project3D(), mrpt::vision::pinhole::projectPoint_no_distortion(), mrpt::opengl::CRenderizable::setLocation(), mrpt::maps::CPointsMap::setPoint(), mrpt::opengl::CCamera::setPointingAt(), sqrDistanceTo(), and mrpt::topography::UTMToGeodetic().
double mrpt::math::TPoint3D::z |
X,Y,Z coordinates.
Definition at line 231 of file lightweight_geom_data.h.
Referenced by mrpt::maps::CPointsMap::boundingBox(), mrpt::maps::COctoMapBase< OCTREE, OCTREE_NODE >::castRay(), mrpt::poses::CPose3D::composePoint(), mrpt::poses::CPose3DRotVec::composePoint(), mrpt::poses::CPoint3D::CPoint3D(), mrpt::poses::CPoseOrPoint< DERIVEDCLASS >::distanceTo(), distanceTo(), mrpt::topography::GeodeticToUTM(), mrpt::math::TSegment3D::getCenter(), mrpt::maps::CPointsMap::getPoint(), mrpt::opengl::graph_tools::graph_visualize(), mrpt::maps::CColouredPointsMap::insertPoint(), mrpt::maps::CPointsMap::insertPoint(), mrpt::poses::CPose3D::inverseComposePoint(), mrpt::math::KDTreeCapable< Derived, num_t, metric_t >::kdTreeClosestPoint3D(), mrpt::math::KDTreeCapable< Derived, num_t, metric_t >::kdTreeNClosestPoint3D(), mrpt::math::KDTreeCapable< Derived, num_t, metric_t >::kdTreeNClosestPoint3DIdx(), mrpt::math::operator!=(), operator+(), operator+=(), operator-(), mrpt::math::operator-(), operator-=(), mrpt::math::operator==(), mrpt::math::project3D(), mrpt::vision::pinhole::projectPoint_no_distortion(), mrpt::opengl::CRenderizable::setLocation(), mrpt::maps::CPointsMap::setPoint(), mrpt::opengl::CCamera::setPointingAt(), sqrDistanceTo(), and mrpt::topography::UTMToGeodetic().
Page generated by Doxygen 1.9.1 for MRPT 1.4.0 SVN: at Sun Mar 7 18:43:46 UTC 2021 |