Main MRPT website > C++ reference for MRPT 1.5.7
List of all members | Public Types | 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 246 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...
 
TPoint3Doperator*= (const double f)
 Point scale. More...
 
template<class VECTORLIKE >
void getAsVector (VECTORLIKE &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
 
double y
 
double z
 X,Y,Z coordinates. More...
 

Member Enumeration Documentation

◆ anonymous enum

anonymous enum
Enumerator
static_size 

Definition at line 247 of file lightweight_geom_data.h.

Constructor & Destructor Documentation

◆ TPoint3D() [1/8]

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

Constructor from coordinates.

Definition at line 251 of file lightweight_geom_data.h.

◆ TPoint3D() [2/8]

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

Default fast constructor.

Initializes to garbage.

Definition at line 253 of file lightweight_geom_data.h.

◆ TPoint3D() [3/8]

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

Explicit constructor from coordinates.

Definition at line 255 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

Definition at line 165 of file lightweight_geom_data.cpp.

◆ TPoint3D() [5/8]

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

Constructor from TPose2D, losing information.

Zeroes the z.

See also
TPose2D

Definition at line 166 of file lightweight_geom_data.cpp.

◆ TPoint3D() [6/8]

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

Constructor from TPose3D, losing information.

See also
TPose3D

Definition at line 167 of file lightweight_geom_data.cpp.

◆ TPoint3D() [7/8]

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

Implicit constructor from heavyweight type.

See also
mrpt::poses::CPoint3D

Definition at line 168 of file lightweight_geom_data.cpp.

◆ TPoint3D() [8/8]

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

Constructor from heavyweight 3D pose.

See also
mrpt::poses::CPose3D.

Definition at line 169 of file lightweight_geom_data.cpp.

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 362 of file lightweight_geom_data.h.

References mrpt::mrpt::format().

◆ asString() [2/2]

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

Definition at line 363 of file lightweight_geom_data.h.

References asString().

Referenced by asString().

◆ distanceTo()

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

◆ 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

Definition at line 177 of file lightweight_geom_data.cpp.

References ASSERTMSG_, mrpt::mrpt::math::size(), and THROW_EXCEPTION.

◆ getAsVector()

template<class VECTORLIKE >
void mrpt::math::TPoint3D::getAsVector ( VECTORLIKE &  v) const
inline

Transformation into vector.

Definition at line 314 of file lightweight_geom_data.h.

Referenced by mrpt::math::TSegment3D::distance().

◆ norm()

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

◆ operator*()

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

Definition at line 349 of file lightweight_geom_data.h.

◆ operator*=()

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

Point scale.

Definition at line 306 of file lightweight_geom_data.h.

◆ operator+()

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

Points addition.

Definition at line 339 of file lightweight_geom_data.h.

◆ operator+=()

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

Translation.

Definition at line 321 of file lightweight_geom_data.h.

References x.

◆ operator-()

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

Points substraction.

Definition at line 345 of file lightweight_geom_data.h.

◆ operator-=()

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

Difference between points.

Definition at line 330 of file lightweight_geom_data.h.

References x.

◆ operator/()

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

Definition at line 353 of file lightweight_geom_data.h.

◆ operator<()

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

Definition at line 170 of file lightweight_geom_data.cpp.

◆ operator[]() [1/2]

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

Coordinate access using operator[].

Order: x,y,z

Definition at line 282 of file lightweight_geom_data.h.

◆ operator[]() [2/2]

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

Coordinate access using operator[].

Order: x,y,z

Definition at line 284 of file lightweight_geom_data.h.

◆ size()

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

Definition at line 370 of file lightweight_geom_data.h.

Referenced by mrpt::math::TPolygon3D::TPolygon3D().

◆ sqrDistanceTo()

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

Point-to-point distance, squared.

Definition at line 294 of file lightweight_geom_data.h.

References mrpt::math::square().

Referenced by mrpt::topography::path_from_rtk_gps().

Member Data Documentation

◆ x

double mrpt::math::TPoint3D::x

Definition at line 248 of file lightweight_geom_data.h.

Referenced by mrpt::opengl::CAngularObservationMesh::addTriangle(), mrpt::math::areAligned(), aux_projectPoint_with_distortion(), mrpt::maps::CPointsMap::boundingBox(), mrpt::maps::COctoMapBase< octomap::OcTree, octomap::OcTreeNode >::castRay(), mrpt::poses::CPointPDFParticles::changeCoordinatesReference(), mrpt::maps::CLandmarksMap::changeCoordinatesReference(), mrpt::detectors::CFaceDetection::checkIfFaceRegions(), mrpt::detectors::CFaceDetection::checkRelativePosition(), mrpt::poses::CPose2D::composePoint(), mrpt::poses::CPose3DRotVec::composePoint(), mrpt::poses::CPose3D::composePoint(), mrpt::maps::CLandmarksMap::computeLikelihood_RSLC_2007(), mrpt::maps::CLandmarksMap::computeLikelihood_SIFT_LandmarkMap(), mrpt::maps::CLandmarksMap::computeMatchingWith3DLandmarks(), mrpt::vision::computeMsd(), mrpt::math::conformAPlane(), mrpt::math::TLine3D::contains(), mrpt::math::TPolygon3D::contains(), mrpt::obs::detail::cost_func(), mrpt::poses::CPoint2D::CPoint2D(), mrpt::opengl::CPolyhedron::CreateCubicPrism(), mrpt::math::distance(), mrpt::math::TLine3D::distance(), mrpt::graphs::detail::CVisualizer< CPOSE, MAPS_IMPLEMENTATION, TMRSlamNodeAnnotations, EDGE_ANNOTATIONS >::drawGroundGrid(), mrpt::topography::ENU_axes_from_WGS84(), mrpt::topography::ENUToGeocentric(), mrpt::detectors::CFaceDetection::experimental_viewFacePointsAndEigenVects(), mrpt::maps::CPointsMap::extractPoints(), mrpt::vision::frameJac(), mrpt::maps::CPointsMap::fuseWith(), mrpt::topography::geocentricToENU_WGS84(), mrpt::topography::geocentricToGeodetic(), mrpt::topography::geodeticToGeocentric(), mrpt::topography::geodeticToGeocentric_WGS84(), mrpt::topography::geodeticToUTM(), mrpt::topography::GeodeticToUTM(), mrpt::opengl::COpenGLViewport::get3DRayForPixelCoord(), mrpt::maps::COctoMap::getAsOctoMapVoxels(), mrpt::maps::CColouredOctoMap::getAsOctoMapVoxels(), mrpt::opengl::COpenGLStandardObject::getBoundingBox(), mrpt::opengl::CDisk::getBoundingBox(), mrpt::opengl::CSetOfTexturedTriangles::getBoundingBox(), mrpt::opengl::CText::getBoundingBox(), mrpt::opengl::CSphere::getBoundingBox(), mrpt::opengl::CArrow::getBoundingBox(), mrpt::opengl::CColorBar::getBoundingBox(), mrpt::opengl::CSimpleLine::getBoundingBox(), mrpt::opengl::CAxis::getBoundingBox(), mrpt::opengl::CTexturedPlane::getBoundingBox(), mrpt::opengl::CGridPlaneXY::getBoundingBox(), mrpt::opengl::CGridPlaneXZ::getBoundingBox(), mrpt::opengl::CText3D::getBoundingBox(), mrpt::opengl::CFrustum::getBoundingBox(), mrpt::opengl::CSetOfObjects::getBoundingBox(), mrpt::opengl::CMesh3D::getBoundingBox(), mrpt::opengl::CPlanarLaserScan::getBoundingBox(), mrpt::opengl::CPolyhedron::getBoundingBox(), mrpt::opengl::CCylinder::getBoundingBox(), mrpt::opengl::CMeshFast::getBoundingBox(), mrpt::opengl::CMesh::getBoundingBox(), mrpt::opengl::CSetOfTriangles::getBoundingBox(), mrpt::opengl::CAngularObservationMesh::getBoundingBox(), mrpt::opengl::CVectorField2D::getBoundingBox(), mrpt::opengl::CVectorField3D::getBoundingBox(), mrpt::opengl::COpenGLViewport::getBoundingBox(), mrpt::opengl::CPolyhedron::getCenter(), mrpt::math::TSegment3D::getCenter(), mrpt::maps::CLandmark::getPose(), mrpt::math::getPrismBounds(), mrpt::math::getSegmentBisector(), mrpt::opengl::graph_tools::graph_visualize(), mrpt::maps::CRandomFieldGridMap3D::insertIndividualReading(), insertRotunda(), mrpt::maps::CPointsMap::internal_insertObservation(), mrpt::maps::detail::pointmap_traits< CColouredPointsMap >::internal_loadFromRangeScan3D_prepareOneRange(), mrpt::math::intersect(), mrpt::maps::CHeightGridMap2D_Base::intersectLine3D(), mrpt::poses::CPose3D::inverseComposePoint(), jacob_dh_db_and_dh_dc(), mrpt::vision::CCamModel::jacobian_project_with_distortion(), mrpt::math::KDTreeCapable< CFeatureList >::kdTreeClosestPoint3D(), mrpt::math::KDTreeCapable< CFeatureList >::kdTreeNClosestPoint3D(), mrpt::math::KDTreeCapable< CFeatureList >::kdTreeNClosestPoint3DIdx(), mrpt::maps::CLandmarksMap::loadOccupancyFeaturesFrom2DRangeScan(), mrpt::opengl::CAssimpModel::loadScene(), mrpt::maps::CLandmarksMap::loadSiftFeaturesFromImageObservation(), mrpt::vision::matchFeatures(), mrpt::slam::CRangeBearingKFSLAM::OnInverseObservationModel(), mrpt::math::operator!=(), operator+=(), mrpt::math::operator-(), operator-=(), mrpt::math::operator<<(), mrpt::math::operator==(), mrpt::math::operator>>(), mrpt::topography::path_from_rtk_gps(), mrpt::vision::pointJac(), mrpt::math::project3D(), mrpt::vision::CCamModel::project_3D_point(), project_point(), mrpt::vision::projectMatchedFeature(), mrpt::vision::projectMatchedFeatures(), mrpt::vision::pinhole::projectPoint_no_distortion(), mrpt::vision::pinhole::projectPoint_with_distortion(), mrpt::vision::pinhole::projectPoints_with_distortion(), mrpt::maps::CLandmarksMap::TCustomSequenceLandmarks::push_back(), mrpt::opengl::CBox::readFromStream(), mrpt::vision::recompute_errors_and_Jacobians(), mrpt::opengl::COpenGLViewport::render(), mrpt::opengl::CBox::render_dl(), mrpt::opengl::CColorBar::render_dl(), mrpt::opengl::COctoMapVoxels::render_dl(), mrpt::opengl::gl_utils::renderTriangleWithNormal(), se3_l2_internal(), mrpt::opengl::CBox::setBoxCorners(), mrpt::slam::CRejectionSamplingRangeOnlyLocalization::setParams(), mrpt::maps::CLandmark::setPose(), mrpt::poses::CPose3DRotVec::sphericalCoordinates(), mrpt::poses::CPose3D::sphericalCoordinates(), mrpt::poses::CPose3DQuat::sphericalCoordinates(), TEST(), Pose3DQuatTests::test_composeAndInvComposePoint(), Pose3DQuatTests::test_composePoint_vs_CPose3D(), Pose3DQuatTests::test_composePointJacob(), Pose3DTests::test_composePointJacob(), Pose3DTests::test_composePointJacob_se3(), Pose3DQuatTests::test_invComposePoint_vs_CPose3D(), Pose3DQuatTests::test_invComposePointJacob(), Pose3DTests::test_invComposePointJacob(), Pose3DTests::test_invComposePointJacob_se3(), mrpt::math::TLine2D::TLine2D(), mrpt::math::TLine3D::TLine3D(), mrpt::math::TPlane::TPlane(), mrpt::opengl::CCylinder::traceRay(), mrpt::topography::transfInterpolation(), mrpt::topography::transform10params(), mrpt::topography::transform1D(), mrpt::topography::transform7params(), mrpt::topography::transform7params_TOPCON(), mrpt::topography::transformHelmert3D_TOPCON(), mrpt::slam::COccupancyGridMapFeatureExtractor::uncached_extractFeatures(), mrpt::vision::CCamModel::unproject_3D_point(), unsafeProjectPoint(), mrpt::topography::UTMToGeodetic(), and mrpt::opengl::CBox::writeToStream().

◆ y

double mrpt::math::TPoint3D::y

Definition at line 248 of file lightweight_geom_data.h.

Referenced by mrpt::opengl::CAngularObservationMesh::addTriangle(), mrpt::math::areAligned(), aux_projectPoint_with_distortion(), mrpt::maps::CPointsMap::boundingBox(), mrpt::maps::COctoMapBase< octomap::OcTree, octomap::OcTreeNode >::castRay(), mrpt::poses::CPointPDFParticles::changeCoordinatesReference(), mrpt::maps::CLandmarksMap::changeCoordinatesReference(), mrpt::detectors::CFaceDetection::checkRelativePosition(), mrpt::poses::CPose2D::composePoint(), mrpt::poses::CPose3DRotVec::composePoint(), mrpt::poses::CPose3D::composePoint(), mrpt::maps::CLandmarksMap::computeLikelihood_RSLC_2007(), mrpt::maps::CLandmarksMap::computeLikelihood_SIFT_LandmarkMap(), mrpt::maps::CLandmarksMap::computeMatchingWith3DLandmarks(), mrpt::vision::computeMsd(), mrpt::math::conformAPlane(), mrpt::math::TLine3D::contains(), mrpt::math::TPolygon3D::contains(), mrpt::obs::detail::cost_func(), mrpt::poses::CPoint2D::CPoint2D(), mrpt::opengl::CPolyhedron::CreateCubicPrism(), mrpt::math::distance(), mrpt::math::TLine3D::distance(), mrpt::graphs::detail::CVisualizer< CPOSE, MAPS_IMPLEMENTATION, TMRSlamNodeAnnotations, EDGE_ANNOTATIONS >::drawGroundGrid(), mrpt::topography::ENU_axes_from_WGS84(), mrpt::topography::ENUToGeocentric(), mrpt::detectors::CFaceDetection::experimental_viewFacePointsAndEigenVects(), mrpt::maps::CPointsMap::extractPoints(), mrpt::vision::frameJac(), mrpt::topography::geocentricToENU_WGS84(), mrpt::topography::geocentricToGeodetic(), mrpt::topography::geodeticToGeocentric(), mrpt::topography::geodeticToGeocentric_WGS84(), mrpt::topography::geodeticToUTM(), mrpt::topography::GeodeticToUTM(), mrpt::opengl::COpenGLViewport::get3DRayForPixelCoord(), mrpt::maps::COctoMap::getAsOctoMapVoxels(), mrpt::maps::CColouredOctoMap::getAsOctoMapVoxels(), mrpt::opengl::COpenGLStandardObject::getBoundingBox(), mrpt::opengl::CDisk::getBoundingBox(), mrpt::opengl::CSetOfTexturedTriangles::getBoundingBox(), mrpt::opengl::CText::getBoundingBox(), mrpt::opengl::CSphere::getBoundingBox(), mrpt::opengl::CArrow::getBoundingBox(), mrpt::opengl::CColorBar::getBoundingBox(), mrpt::opengl::CSimpleLine::getBoundingBox(), mrpt::opengl::CAxis::getBoundingBox(), mrpt::opengl::CTexturedPlane::getBoundingBox(), mrpt::opengl::CGridPlaneXY::getBoundingBox(), mrpt::opengl::CGridPlaneXZ::getBoundingBox(), mrpt::opengl::CText3D::getBoundingBox(), mrpt::opengl::CFrustum::getBoundingBox(), mrpt::opengl::CSetOfObjects::getBoundingBox(), mrpt::opengl::CMesh3D::getBoundingBox(), mrpt::opengl::CPlanarLaserScan::getBoundingBox(), mrpt::opengl::CPolyhedron::getBoundingBox(), mrpt::opengl::CCylinder::getBoundingBox(), mrpt::opengl::CMeshFast::getBoundingBox(), mrpt::opengl::CMesh::getBoundingBox(), mrpt::opengl::CSetOfTriangles::getBoundingBox(), mrpt::opengl::CAngularObservationMesh::getBoundingBox(), mrpt::opengl::CVectorField2D::getBoundingBox(), mrpt::opengl::CVectorField3D::getBoundingBox(), mrpt::opengl::COpenGLViewport::getBoundingBox(), mrpt::opengl::CPolyhedron::getCenter(), mrpt::math::TSegment3D::getCenter(), mrpt::maps::CLandmark::getPose(), mrpt::math::getPrismBounds(), mrpt::math::getSegmentBisector(), mrpt::opengl::graph_tools::graph_visualize(), mrpt::maps::CRandomFieldGridMap3D::insertIndividualReading(), insertRotunda(), mrpt::maps::CPointsMap::internal_insertObservation(), mrpt::maps::detail::pointmap_traits< CColouredPointsMap >::internal_loadFromRangeScan3D_prepareOneRange(), mrpt::math::intersect(), mrpt::maps::CHeightGridMap2D_Base::intersectLine3D(), mrpt::poses::CPose3D::inverseComposePoint(), jacob_dh_db_and_dh_dc(), mrpt::vision::CCamModel::jacobian_project_with_distortion(), mrpt::math::KDTreeCapable< CFeatureList >::kdTreeClosestPoint3D(), mrpt::math::KDTreeCapable< CFeatureList >::kdTreeNClosestPoint3D(), mrpt::math::KDTreeCapable< CFeatureList >::kdTreeNClosestPoint3DIdx(), mrpt::maps::CLandmarksMap::loadOccupancyFeaturesFrom2DRangeScan(), mrpt::opengl::CAssimpModel::loadScene(), mrpt::maps::CLandmarksMap::loadSiftFeaturesFromImageObservation(), mrpt::vision::matchFeatures(), mrpt::slam::CRangeBearingKFSLAM::OnInverseObservationModel(), mrpt::math::operator!=(), mrpt::math::operator-(), mrpt::math::operator<<(), mrpt::math::operator==(), mrpt::math::operator>>(), mrpt::topography::path_from_rtk_gps(), mrpt::vision::pointJac(), mrpt::math::project3D(), mrpt::vision::CCamModel::project_3D_point(), project_point(), mrpt::vision::projectMatchedFeature(), mrpt::vision::projectMatchedFeatures(), mrpt::vision::pinhole::projectPoint_no_distortion(), mrpt::vision::pinhole::projectPoint_with_distortion(), mrpt::vision::pinhole::projectPoints_with_distortion(), mrpt::maps::CLandmarksMap::TCustomSequenceLandmarks::push_back(), mrpt::opengl::CBox::readFromStream(), mrpt::vision::recompute_errors_and_Jacobians(), mrpt::opengl::COpenGLViewport::render(), mrpt::opengl::CBox::render_dl(), mrpt::opengl::CColorBar::render_dl(), mrpt::opengl::gl_utils::renderTriangleWithNormal(), se3_l2_internal(), mrpt::opengl::CBox::setBoxCorners(), mrpt::slam::CRejectionSamplingRangeOnlyLocalization::setParams(), mrpt::maps::CLandmark::setPose(), mrpt::poses::CPose3DRotVec::sphericalCoordinates(), mrpt::poses::CPose3D::sphericalCoordinates(), mrpt::poses::CPose3DQuat::sphericalCoordinates(), TEST(), Pose3DQuatTests::test_composeAndInvComposePoint(), Pose3DQuatTests::test_composePoint_vs_CPose3D(), Pose3DQuatTests::test_composePointJacob(), Pose3DTests::test_composePointJacob(), Pose3DTests::test_composePointJacob_se3(), Pose3DQuatTests::test_invComposePoint_vs_CPose3D(), Pose3DQuatTests::test_invComposePointJacob(), Pose3DTests::test_invComposePointJacob(), Pose3DTests::test_invComposePointJacob_se3(), mrpt::math::TLine2D::TLine2D(), mrpt::math::TLine3D::TLine3D(), mrpt::math::TPlane::TPlane(), mrpt::opengl::CCylinder::traceRay(), mrpt::topography::transfInterpolation(), mrpt::topography::transform10params(), mrpt::topography::transform1D(), mrpt::topography::transform7params(), mrpt::topography::transform7params_TOPCON(), mrpt::topography::transformHelmert3D_TOPCON(), mrpt::slam::COccupancyGridMapFeatureExtractor::uncached_extractFeatures(), mrpt::vision::CCamModel::unproject_3D_point(), unsafeProjectPoint(), mrpt::topography::UTMToGeodetic(), and mrpt::opengl::CBox::writeToStream().

◆ z

double mrpt::math::TPoint3D::z

X,Y,Z coordinates.

Definition at line 248 of file lightweight_geom_data.h.

Referenced by mrpt::opengl::CAngularObservationMesh::addTriangle(), mrpt::math::areAligned(), aux_projectPoint_with_distortion(), mrpt::maps::CPointsMap::boundingBox(), mrpt::maps::COctoMapBase< octomap::OcTree, octomap::OcTreeNode >::castRay(), mrpt::poses::CPointPDFParticles::changeCoordinatesReference(), mrpt::maps::CLandmarksMap::changeCoordinatesReference(), mrpt::poses::CPose2D::composePoint(), mrpt::poses::CPose3DRotVec::composePoint(), mrpt::poses::CPose3D::composePoint(), mrpt::maps::CLandmarksMap::computeLikelihood_SIFT_LandmarkMap(), mrpt::maps::CLandmarksMap::computeMatchingWith3DLandmarks(), mrpt::vision::computeMsd(), mrpt::math::conformAPlane(), mrpt::math::TLine3D::contains(), mrpt::math::TPolygon3D::contains(), mrpt::obs::detail::cost_func(), mrpt::opengl::CPolyhedron::CreateCubicPrism(), mrpt::math::distance(), mrpt::math::TLine3D::distance(), mrpt::math::TPolygon3D::distance(), mrpt::graphs::detail::CVisualizer< CPOSE, MAPS_IMPLEMENTATION, TMRSlamNodeAnnotations, EDGE_ANNOTATIONS >::drawGroundGrid(), mrpt::topography::ENU_axes_from_WGS84(), mrpt::topography::ENUToGeocentric(), mrpt::detectors::CFaceDetection::experimental_viewFacePointsAndEigenVects(), mrpt::maps::CPointsMap::extractPoints(), mrpt::vision::frameJac(), mrpt::topography::geocentricToENU_WGS84(), mrpt::topography::geocentricToGeodetic(), mrpt::topography::geodeticToGeocentric(), mrpt::topography::geodeticToGeocentric_WGS84(), mrpt::topography::geodeticToUTM(), mrpt::topography::GeodeticToUTM(), mrpt::opengl::COpenGLViewport::get3DRayForPixelCoord(), mrpt::maps::COctoMap::getAsOctoMapVoxels(), mrpt::maps::CColouredOctoMap::getAsOctoMapVoxels(), mrpt::opengl::COpenGLStandardObject::getBoundingBox(), mrpt::opengl::CDisk::getBoundingBox(), mrpt::opengl::CSetOfTexturedTriangles::getBoundingBox(), mrpt::opengl::CText::getBoundingBox(), mrpt::opengl::CSphere::getBoundingBox(), mrpt::opengl::CArrow::getBoundingBox(), mrpt::opengl::CColorBar::getBoundingBox(), mrpt::opengl::CSimpleLine::getBoundingBox(), mrpt::opengl::CAxis::getBoundingBox(), mrpt::opengl::CTexturedPlane::getBoundingBox(), mrpt::opengl::CGridPlaneXY::getBoundingBox(), mrpt::opengl::CGridPlaneXZ::getBoundingBox(), mrpt::opengl::CText3D::getBoundingBox(), mrpt::opengl::CFrustum::getBoundingBox(), mrpt::opengl::CSetOfObjects::getBoundingBox(), mrpt::opengl::CMesh3D::getBoundingBox(), mrpt::opengl::CPlanarLaserScan::getBoundingBox(), mrpt::opengl::CPolyhedron::getBoundingBox(), mrpt::opengl::CCylinder::getBoundingBox(), mrpt::opengl::CMeshFast::getBoundingBox(), mrpt::opengl::CMesh::getBoundingBox(), mrpt::opengl::CSetOfTriangles::getBoundingBox(), mrpt::opengl::CAngularObservationMesh::getBoundingBox(), mrpt::opengl::CVectorField2D::getBoundingBox(), mrpt::opengl::CVectorField3D::getBoundingBox(), mrpt::opengl::COpenGLViewport::getBoundingBox(), mrpt::opengl::CPolyhedron::getCenter(), mrpt::math::TSegment3D::getCenter(), mrpt::maps::CLandmark::getPose(), mrpt::math::getPrismBounds(), mrpt::math::getSegmentBisector(), mrpt::opengl::graph_tools::graph_visualize(), mrpt::maps::CRandomFieldGridMap3D::insertIndividualReading(), insertRotunda(), mrpt::maps::CPointsMap::internal_insertObservation(), mrpt::maps::detail::pointmap_traits< CColouredPointsMap >::internal_loadFromRangeScan3D_prepareOneRange(), mrpt::math::intersect(), mrpt::maps::CHeightGridMap2D_Base::intersectLine3D(), mrpt::poses::CPose3D::inverseComposePoint(), jacob_dh_db_and_dh_dc(), mrpt::vision::CCamModel::jacobian_project_with_distortion(), mrpt::math::KDTreeCapable< CFeatureList >::kdTreeClosestPoint3D(), mrpt::math::KDTreeCapable< CFeatureList >::kdTreeNClosestPoint3D(), mrpt::math::KDTreeCapable< CFeatureList >::kdTreeNClosestPoint3DIdx(), mrpt::maps::CLandmarksMap::loadOccupancyFeaturesFrom2DRangeScan(), mrpt::opengl::CAssimpModel::loadScene(), mrpt::maps::CLandmarksMap::loadSiftFeaturesFromImageObservation(), mrpt::vision::matchFeatures(), mrpt::slam::CRangeBearingKFSLAM::OnInverseObservationModel(), mrpt::math::operator!=(), mrpt::math::operator-(), mrpt::math::operator<<(), mrpt::math::operator==(), mrpt::math::operator>>(), mrpt::topography::path_from_rtk_gps(), mrpt::vision::pointJac(), mrpt::math::project3D(), mrpt::vision::CCamModel::project_3D_point(), project_point(), mrpt::vision::projectMatchedFeature(), mrpt::vision::projectMatchedFeatures(), mrpt::vision::pinhole::projectPoint_no_distortion(), mrpt::vision::pinhole::projectPoint_with_distortion(), mrpt::vision::pinhole::projectPoints_with_distortion(), mrpt::opengl::CBox::readFromStream(), mrpt::vision::recompute_errors_and_Jacobians(), mrpt::opengl::COpenGLViewport::render(), mrpt::opengl::CBox::render_dl(), mrpt::opengl::CColorBar::render_dl(), mrpt::opengl::gl_utils::renderTriangleWithNormal(), se3_l2_internal(), mrpt::opengl::CBox::setBoxCorners(), mrpt::slam::CRejectionSamplingRangeOnlyLocalization::setParams(), mrpt::maps::CLandmark::setPose(), mrpt::poses::CPose3DRotVec::sphericalCoordinates(), mrpt::poses::CPose3D::sphericalCoordinates(), mrpt::poses::CPose3DQuat::sphericalCoordinates(), TEST(), Pose3DQuatTests::test_composeAndInvComposePoint(), Pose3DQuatTests::test_composePoint_vs_CPose3D(), Pose3DQuatTests::test_composePointJacob(), Pose3DTests::test_composePointJacob(), Pose3DTests::test_composePointJacob_se3(), Pose3DQuatTests::test_invComposePoint_vs_CPose3D(), Pose3DQuatTests::test_invComposePointJacob(), Pose3DTests::test_invComposePointJacob(), Pose3DTests::test_invComposePointJacob_se3(), mrpt::math::TLine3D::TLine3D(), mrpt::math::TPlane::TPlane(), mrpt::opengl::CCylinder::traceRay(), mrpt::topography::transfInterpolation(), mrpt::topography::transform10params(), mrpt::topography::transform1D(), mrpt::topography::transform7params(), mrpt::topography::transform7params_TOPCON(), mrpt::topography::transformHelmert3D_TOPCON(), mrpt::slam::COccupancyGridMapFeatureExtractor::uncached_extractFeatures(), mrpt::vision::CCamModel::unproject_3D_point(), unsafeProjectPoint(), mrpt::topography::UTMToGeodetic(), and mrpt::opengl::CBox::writeToStream().




Page generated by Doxygen 1.8.14 for MRPT 1.5.7 Git: 5902e14cc Wed Apr 24 15:04:01 2019 +0200 at lun oct 28 01:39:17 CET 2019