MRPT  2.0.1
List of all members | Public Types | Public Member Functions | Static Public Member Functions | Public Attributes
mrpt::math::TPoint3D_< T > Struct Template Reference

Detailed Description

template<typename T>
struct mrpt::math::TPoint3D_< T >

Base template for TPoint3D and TPoint3Df.

[1-byte memory packed, no padding]

Definition at line 37 of file TPoint3D.h.

#include <mrpt/math/TPoint3D.h>

Inheritance diagram for mrpt::math::TPoint3D_< T >:

Public Types

enum  { static_size = 3 }
 

Public Member Functions

constexpr TPoint3D_ ()
 Default constructor. More...
 
constexpr TPoint3D_ (T xx, T yy, T zz)
 Constructor from coordinates. More...
 
template<typename U >
 TPoint3D_ (const TPoint3D_data< U > &p)
 Constructor from coordinates. More...
 
template<typename U >
 TPoint3D_ (const mrpt::math::CMatrixFixed< U, 3, 1 > &m)
 Constructor from column vector. More...
 
 TPoint3D_ (const TPoint2D_< T > &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...
 
template<typename U >
TPoint3D_< U > cast () const
 Return a copy of this object using type U for coordinates. More...
 
T & operator[] (size_t i)
 Coordinate access using operator[]. More...
 
constexpr T operator[] (size_t i) const
 Coordinate access using operator[]. More...
 
distanceTo (const TPoint3D_< T > &p) const
 Point-to-point distance. More...
 
sqrDistanceTo (const TPoint3D_< T > &p) const
 Point-to-point distance, squared. More...
 
sqrNorm () const
 Squared norm: |v|^2 = x^2+y^2+z^2. More...
 
norm () const
 Point norm: |v| = sqrt(x^2+y^2+z^2) More...
 
TPoint3D_< T > unitarize () const
 Returns this vector with unit length: v/norm(v) More...
 
TPoint3D_< T > & operator*= (const T f)
 Scale point/vector. More...
 
template<class VECTORLIKE >
void asVector (VECTORLIKE &v) const
 Transformation into vector. More...
 
TPoint3D_< T > & operator+= (const TPoint3D_< T > &p)
 Translation. More...
 
TPoint3D_< T > & operator-= (const TPoint3D_< T > &p)
 Difference between points. More...
 
constexpr TPoint3D_< T > operator+ (const TPoint3D_< T > &p) const
 Points addition. More...
 
constexpr TPoint3D_< T > operator- (const TPoint3D_< T > &p) const
 Points substraction. More...
 
constexpr TPoint3D_< T > operator* (T d) const
 
constexpr TPoint3D_< T > operator/ (T d) const
 
bool operator< (const TPoint3D_< T > &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...
 
constexpr std::size_t rows () const
 
constexpr std::size_t cols () const
 
constexpr std::size_t size () const
 
void resize (std::size_t n)
 throws if attempted to resize to incorrect length More...
 

Static Public Member Functions

static TPoint3D_< T > FromString (const std::string &s)
 

Public Attributes

x
 X,Y,Z coordinates. More...
 
y
 
z
 

Member Enumeration Documentation

◆ anonymous enum

template<typename T>
anonymous enum
Enumerator
static_size 

Definition at line 41 of file TPoint3D.h.

Constructor & Destructor Documentation

◆ TPoint3D_() [1/7]

template<typename T>
constexpr mrpt::math::TPoint3D_< T >::TPoint3D_ ( )
inline

Default constructor.

Initializes to zeros.

Definition at line 47 of file TPoint3D.h.

◆ TPoint3D_() [2/7]

template<typename T>
constexpr mrpt::math::TPoint3D_< T >::TPoint3D_ ( xx,
yy,
zz 
)
inline

Constructor from coordinates.

Definition at line 49 of file TPoint3D.h.

◆ TPoint3D_() [3/7]

template<typename T>
template<typename U >
mrpt::math::TPoint3D_< T >::TPoint3D_ ( const TPoint3D_data< U > &  p)
inline

Constructor from coordinates.

Definition at line 53 of file TPoint3D.h.

◆ TPoint3D_() [4/7]

template<typename T>
template<typename U >
mrpt::math::TPoint3D_< T >::TPoint3D_ ( const mrpt::math::CMatrixFixed< U, 3, 1 > &  m)
inline

Constructor from column vector.

Definition at line 62 of file TPoint3D.h.

◆ TPoint3D_() [5/7]

template<typename T>
mrpt::math::TPoint3D_< T >::TPoint3D_ ( const TPoint2D_< T > &  p)

Implicit constructor from TPoint2D.

Zeroes the z.

See also
TPoint2D

Definition at line 26 of file TPoint3D.cpp.

◆ TPoint3D_() [6/7]

template<typename T>
mrpt::math::TPoint3D_< T >::TPoint3D_ ( const TPose2D p)
explicit

Constructor from TPose2D, losing information.

Zeroes the z.

See also
TPose2D

Definition at line 31 of file TPoint3D.cpp.

◆ TPoint3D_() [7/7]

template<typename T>
mrpt::math::TPoint3D_< T >::TPoint3D_ ( const TPose3D p)
explicit

Constructor from TPose3D, losing information.

See also
TPose3D

Definition at line 37 of file TPoint3D.cpp.

Member Function Documentation

◆ asString() [1/2]

template<typename T>
void mrpt::math::TPoint3D_< T >::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 236 of file TPoint3D.h.

◆ asString() [2/2]

template<typename T>
std::string mrpt::math::TPoint3D_< T >::asString ( ) const
inline

Definition at line 242 of file TPoint3D.h.

Referenced by mrpt::math::TPoint3D_< float >::asString().

Here is the caller graph for this function:

◆ asVector()

template<typename T>
template<class VECTORLIKE >
void mrpt::math::TPoint3D_< T >::asVector ( VECTORLIKE &  v) const
inline

Transformation into vector.

Definition at line 174 of file TPoint3D.h.

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

Here is the caller graph for this function:

◆ cast()

template<typename T>
template<typename U >
TPoint3D_<U> mrpt::math::TPoint3D_< T >::cast ( ) const
inline

Return a copy of this object using type U for coordinates.

Definition at line 86 of file TPoint3D.h.

◆ cols()

constexpr std::size_t mrpt::math::internal::ProvideStaticResize< TPoint3D_< T > >::cols ( ) const
inlineinherited

Definition at line 66 of file TPoseOrPoint.h.

◆ distanceTo()

template<typename T>
T mrpt::math::TPoint3D_< T >::distanceTo ( const TPoint3D_< T > &  p) const
inline

Point-to-point distance.

Definition at line 126 of file TPoint3D.h.

Referenced by mrpt::detectors::CFaceDetection::checkIfDiagonalSurface(), mrpt::detectors::CFaceDetection::checkIfDiagonalSurface2(), mrpt::detectors::CFaceDetection::checkIfFaceRegions(), and mrpt::topography::path_from_rtk_gps().

Here is the caller graph for this function:

◆ fromString()

template<typename T >
void mrpt::math::TPoint3D_< T >::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 59 of file TPoint3D.cpp.

Referenced by mrpt::math::TPoint3D_< float >::FromString().

Here is the caller graph for this function:

◆ FromString()

template<typename T>
static TPoint3D_<T> mrpt::math::TPoint3D_< T >::FromString ( const std::string &  s)
inlinestatic

Definition at line 256 of file TPoint3D.h.

◆ norm()

template<typename T>
T mrpt::math::TPoint3D_< T >::norm ( ) const
inline

◆ operator*()

template<typename T>
constexpr TPoint3D_<T> mrpt::math::TPoint3D_< T >::operator* ( d) const
inline

Definition at line 218 of file TPoint3D.h.

◆ operator*=()

template<typename T>
TPoint3D_<T>& mrpt::math::TPoint3D_< T >::operator*= ( const T  f)
inline

Scale point/vector.

Definition at line 163 of file TPoint3D.h.

◆ operator+()

template<typename T>
constexpr TPoint3D_<T> mrpt::math::TPoint3D_< T >::operator+ ( const TPoint3D_< T > &  p) const
inline

Points addition.

Definition at line 204 of file TPoint3D.h.

◆ operator+=()

template<typename T>
TPoint3D_<T>& mrpt::math::TPoint3D_< T >::operator+= ( const TPoint3D_< T > &  p)
inline

Translation.

Definition at line 184 of file TPoint3D.h.

◆ operator-()

template<typename T>
constexpr TPoint3D_<T> mrpt::math::TPoint3D_< T >::operator- ( const TPoint3D_< T > &  p) const
inline

Points substraction.

Definition at line 212 of file TPoint3D.h.

◆ operator-=()

template<typename T>
TPoint3D_<T>& mrpt::math::TPoint3D_< T >::operator-= ( const TPoint3D_< T > &  p)
inline

Difference between points.

Definition at line 194 of file TPoint3D.h.

◆ operator/()

template<typename T>
constexpr TPoint3D_<T> mrpt::math::TPoint3D_< T >::operator/ ( d) const
inline

Definition at line 224 of file TPoint3D.h.

◆ operator<()

template<typename T>
bool mrpt::math::TPoint3D_< T >::operator< ( const TPoint3D_< T > &  p) const

Definition at line 44 of file TPoint3D.cpp.

◆ operator[]() [1/2]

template<typename T>
T& mrpt::math::TPoint3D_< T >::operator[] ( size_t  i)
inline

Coordinate access using operator[].

Order: x,y,z

Definition at line 94 of file TPoint3D.h.

◆ operator[]() [2/2]

template<typename T>
constexpr T mrpt::math::TPoint3D_< T >::operator[] ( size_t  i) const
inline

Coordinate access using operator[].

Order: x,y,z

Definition at line 109 of file TPoint3D.h.

◆ resize()

void mrpt::math::internal::ProvideStaticResize< TPoint3D_< T > >::resize ( std::size_t  n)
inlineinherited

throws if attempted to resize to incorrect length

Definition at line 70 of file TPoseOrPoint.h.

◆ rows()

constexpr std::size_t mrpt::math::internal::ProvideStaticResize< TPoint3D_< T > >::rows ( ) const
inlineinherited

Definition at line 65 of file TPoseOrPoint.h.

◆ size()

constexpr std::size_t mrpt::math::internal::ProvideStaticResize< TPoint3D_< T > >::size ( ) const
inlineinherited

Definition at line 67 of file TPoseOrPoint.h.

◆ sqrDistanceTo()

template<typename T>
T mrpt::math::TPoint3D_< T >::sqrDistanceTo ( const TPoint3D_< T > &  p) const
inline

Point-to-point distance, squared.

Definition at line 136 of file TPoint3D.h.

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

Here is the caller graph for this function:

◆ sqrNorm()

template<typename T>
T mrpt::math::TPoint3D_< T >::sqrNorm ( ) const
inline

Squared norm: |v|^2 = x^2+y^2+z^2.

Definition at line 143 of file TPoint3D.h.

Referenced by mrpt::math::TPoint3D_< float >::norm().

Here is the caller graph for this function:

◆ unitarize()

template<typename T>
TPoint3D_<T> mrpt::math::TPoint3D_< T >::unitarize ( ) const
inline

Returns this vector with unit length: v/norm(v)

Definition at line 153 of file TPoint3D.h.

Referenced by mrpt::opengl::CMesh::updateTriangles().

Here is the caller graph for this function:

Member Data Documentation

◆ x

template<typename T>
T mrpt::math::TPoint3D_data< T >::x
inherited

X,Y,Z coordinates.

Definition at line 29 of file TPoint3D.h.

Referenced by mrpt::math::areAligned(), aux_projectPoint_with_distortion(), mrpt::maps::CPointsMap::boundingBox(), mrpt::math::TPoint3D_< float >::cast(), 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::math::TPose3D::composePoint(), mrpt::poses::CPose2D::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::poses::CPoint3D::CPoint3D(), mrpt::opengl::CPolyhedron::CreateCubicPrism(), mrpt::math::TLine3D::distance(), mrpt::math::distance(), mrpt::math::TPoint3D_< float >::distanceTo(), mrpt::poses::CPoseOrPoint< CPose2D, DIM >::distanceTo(), mrpt::apps::MonteCarloLocalization_Base::do_pf_localization(), mrpt::graphs::detail::CVisualizer< CPOSE, MAPS_IMPLEMENTATION, TMRSlamNodeAnnotations, EDGE_ANNOTATIONS >::drawGroundGrid(), mrpt::opengl::enqueForRendering(), mrpt::topography::ENU_axes_from_WGS84(), mrpt::topography::ENUToGeocentric(), mrpt::detectors::CFaceDetection::experimental_viewFacePointsAndEigenVects(), mrpt::maps::CPointsMap::extractPoints(), mrpt::maps::CPointCloudFilterByDistance::filter(), mrpt::vision::frameJac(), mrpt::ros1bridge::fromROS(), 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::CSetOfObjects::getBoundingBox(), mrpt::opengl::COpenGLViewport::getBoundingBox(), mrpt::math::TPolygon3D::getCenter(), mrpt::math::TSegment3D::getCenter(), mrpt::opengl::CPolyhedron::TPolyhedronFace::getCenter(), mrpt::opengl::CPolyhedron::getCenter(), mrpt::opengl::COctreePointRenderer< Derived >::TNode::getCornerX(), mrpt::opengl::CPolyhedron::getDual(), mrpt::opengl::CSetOfLines::getLineByIndex(), mrpt::maps::CPointsMap::getPoint(), mrpt::opengl::PointCloudAdapter< mrpt::opengl::CPointCloudColoured >::getPointXYZ(), mrpt::math::getPrismBounds(), mrpt::math::getSegmentBisector(), mrpt::opengl::graph_tools::graph_visualize(), mrpt::maps::CPointsMap::insertAnotherMap(), mrpt::maps::CRandomFieldGridMap3D::insertIndividualReading(), mrpt::maps::CPointsMap::insertPoint(), mrpt::maps::COccupancyGridMap3D::insertRay(), insertRotunda(), mrpt::maps::COctoMapBase< octomap::OcTree, octomap::OcTreeNode >::internal_build_PointCloud_for_observation(), mrpt::maps::CColouredOctoMap::internal_insertObservation(), mrpt::maps::CPointsMap::internal_insertObservation(), mrpt::maps::detail::pointmap_traits< CColouredPointsMap >::internal_loadFromRangeScan3D_prepareOneRange(), mrpt::opengl::COctreePointRenderer< CPointCloudColoured >::internal_recursive_split(), mrpt::math::intersect(), mrpt::maps::CHeightGridMap2D_Base::intersectLine3D(), mrpt::math::TPose3D::inverseComposePoint(), mrpt::poses::CPose3D::inverseComposePoint(), mrpt::poses::CPose3D::inverseRotateVector(), jacob_dA_eps_D_p_deps(), jacob_db_dp(), jacob_dh_db_and_dh_dc(), mrpt::math::KDTreeCapable< CFeatureList >::kdTreeClosestPoint3D(), mrpt::math::KDTreeCapable< CFeatureList >::kdTreeNClosestPoint3D(), mrpt::math::KDTreeCapable< CFeatureList >::kdTreeNClosestPoint3DIdx(), kfslam_traits< CRangeBearingKFSLAM2D >::landmark_to_3d(), kfslam_traits< CRangeBearingKFSLAM >::landmark_to_3d(), mrpt::maps::CLandmarksMap::loadOccupancyFeaturesFrom2DRangeScan(), mrpt::opengl::CAssimpModel::loadScene(), mrpt::vision::matchFeatures(), mrpt::slam::CRangeBearingKFSLAM::OnInverseObservationModel(), mrpt::opengl::COctoMapVoxels::onUpdateBuffers_Triangles(), mrpt::opengl::COctoMapVoxels::onUpdateBuffers_Wireframe(), mrpt::math::operator!=(), mrpt::math::TPoint3D_< float >::operator+(), mrpt::math::TPoint3D_< float >::operator+=(), mrpt::math::TPoint3D_< float >::operator-(), mrpt::math::operator-(), mrpt::math::TPoint3D_< float >::operator-=(), mrpt::math::TPoint3D_< float >::operator<(), mrpt::math::operator==(), mrpt::topography::path_from_rtk_gps(), mrpt::vision::pixelTo3D(), mrpt::maps::CPointsMapXYZI::PLY_export_get_vertex(), mrpt::maps::CColouredPointsMap::PLY_export_get_vertex(), mrpt::maps::CPointsMap::PLY_export_get_vertex(), mrpt::opengl::CPointCloud::PLY_import_set_vertex(), mrpt::opengl::CPointCloudColoured::PLY_import_set_vertex(), mrpt::maps::CPointsMapXYZI::PLY_import_set_vertex(), mrpt::maps::CColouredPointsMap::PLY_import_set_vertex(), mrpt::maps::CPointsMap::PLY_import_set_vertex(), mrpt::vision::pointJac(), project_point(), mrpt::vision::projectMatchedFeature(), mrpt::vision::projectMatchedFeatures(), mrpt::vision::pinhole::projectPoint_no_distortion(), mrpt::vision::pinhole::projectPoints_with_distortion(), mrpt::maps::CLandmarksMap::TCustomSequenceLandmarks::push_back(), mrpt::obs::detail::range2XYZ_LUT(), mrpt::opengl::CRenderizableShaderTriangles::render(), mrpt::maps::COccupancyGridMap3D::resizeGrid(), mrpt::poses::CPose3D::rotateVector(), mrpt::apps::CGridMapAlignerApp::run(), mrpt::apps::KFSLAMApp::Run_KF_SLAM(), mrpt::opengl::PLY_Exporter::saveToPlyFile(), se3_l2_internal(), mrpt::opengl::COctreePointRenderer< Derived >::TNode::setBBFromOrderInParent(), mrpt::opengl::CBox::setBoxCorners(), mrpt::opengl::CRenderizable::setLocation(), mrpt::slam::CRejectionSamplingRangeOnlyLocalization::setParams(), mrpt::maps::CPointsMap::setPoint(), mrpt::opengl::CCamera::setPointingAt(), mrpt::maps::COccupancyGridMap3D::setSize(), mrpt::poses::CPose3D::sphericalCoordinates(), mrpt::poses::CPose3DQuat::sphericalCoordinates(), mrpt::math::TPoint3D_< float >::sqrDistanceTo(), 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::math::TPoint2D_< double >::TPoint2D_(), mrpt::math::TPoint3D_< float >::TPoint3D_(), 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(), unsafeProjectPoint(), mrpt::opengl::COctreePointRenderer< Derived >::TNode::update_bb(), mrpt::topography::UTMToGeodetic(), and velodyne_scan_to_pointcloud().

◆ y

template<typename T>
T mrpt::math::TPoint3D_data< T >::y
inherited

Definition at line 29 of file TPoint3D.h.

Referenced by mrpt::math::areAligned(), aux_projectPoint_with_distortion(), mrpt::maps::CPointsMap::boundingBox(), mrpt::math::TPoint3D_< float >::cast(), mrpt::maps::COctoMapBase< octomap::OcTree, octomap::OcTreeNode >::castRay(), mrpt::poses::CPointPDFParticles::changeCoordinatesReference(), mrpt::maps::CLandmarksMap::changeCoordinatesReference(), mrpt::detectors::CFaceDetection::checkRelativePosition(), mrpt::math::TPose3D::composePoint(), mrpt::poses::CPose2D::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::poses::CPoint3D::CPoint3D(), mrpt::opengl::CPolyhedron::CreateCubicPrism(), mrpt::math::TLine3D::distance(), mrpt::math::distance(), mrpt::math::TPoint3D_< float >::distanceTo(), mrpt::poses::CPoseOrPoint< CPose2D, DIM >::distanceTo(), mrpt::apps::MonteCarloLocalization_Base::do_pf_localization(), mrpt::graphs::detail::CVisualizer< CPOSE, MAPS_IMPLEMENTATION, TMRSlamNodeAnnotations, EDGE_ANNOTATIONS >::drawGroundGrid(), mrpt::opengl::enqueForRendering(), mrpt::topography::ENU_axes_from_WGS84(), mrpt::topography::ENUToGeocentric(), mrpt::detectors::CFaceDetection::experimental_viewFacePointsAndEigenVects(), mrpt::maps::CPointsMap::extractPoints(), mrpt::maps::CPointCloudFilterByDistance::filter(), mrpt::vision::frameJac(), mrpt::ros1bridge::fromROS(), 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::CFrustum::getBoundingBox(), mrpt::opengl::CSetOfObjects::getBoundingBox(), mrpt::opengl::COpenGLViewport::getBoundingBox(), mrpt::math::TPolygon3D::getCenter(), mrpt::math::TSegment3D::getCenter(), mrpt::opengl::CPolyhedron::TPolyhedronFace::getCenter(), mrpt::opengl::CPolyhedron::getCenter(), mrpt::opengl::COctreePointRenderer< Derived >::TNode::getCornerY(), mrpt::opengl::CPolyhedron::getDual(), mrpt::opengl::CSetOfLines::getLineByIndex(), mrpt::maps::CPointsMap::getPoint(), mrpt::math::getPrismBounds(), mrpt::math::getSegmentBisector(), mrpt::opengl::graph_tools::graph_visualize(), mrpt::maps::CPointsMap::insertAnotherMap(), mrpt::maps::CRandomFieldGridMap3D::insertIndividualReading(), mrpt::maps::CPointsMap::insertPoint(), mrpt::maps::COccupancyGridMap3D::insertRay(), insertRotunda(), mrpt::maps::COctoMapBase< octomap::OcTree, octomap::OcTreeNode >::internal_build_PointCloud_for_observation(), mrpt::maps::CColouredOctoMap::internal_insertObservation(), mrpt::maps::CPointsMap::internal_insertObservation(), mrpt::maps::detail::pointmap_traits< CColouredPointsMap >::internal_loadFromRangeScan3D_prepareOneRange(), mrpt::opengl::COctreePointRenderer< CPointCloudColoured >::internal_recursive_split(), mrpt::math::intersect(), mrpt::maps::CHeightGridMap2D_Base::intersectLine3D(), mrpt::math::TPose3D::inverseComposePoint(), mrpt::poses::CPose3D::inverseComposePoint(), mrpt::poses::CPose3D::inverseRotateVector(), jacob_dA_eps_D_p_deps(), jacob_db_dp(), jacob_dh_db_and_dh_dc(), mrpt::math::KDTreeCapable< CFeatureList >::kdTreeClosestPoint3D(), mrpt::math::KDTreeCapable< CFeatureList >::kdTreeNClosestPoint3D(), mrpt::math::KDTreeCapable< CFeatureList >::kdTreeNClosestPoint3DIdx(), kfslam_traits< CRangeBearingKFSLAM2D >::landmark_to_3d(), kfslam_traits< CRangeBearingKFSLAM >::landmark_to_3d(), mrpt::maps::CLandmarksMap::loadOccupancyFeaturesFrom2DRangeScan(), mrpt::opengl::CAssimpModel::loadScene(), mrpt::vision::matchFeatures(), mrpt::slam::CRangeBearingKFSLAM::OnInverseObservationModel(), mrpt::opengl::COctoMapVoxels::onUpdateBuffers_Triangles(), mrpt::opengl::COctoMapVoxels::onUpdateBuffers_Wireframe(), mrpt::math::operator!=(), mrpt::math::TPoint3D_< float >::operator+(), mrpt::math::TPoint3D_< float >::operator+=(), mrpt::math::TPoint3D_< float >::operator-(), mrpt::math::operator-(), mrpt::math::TPoint3D_< float >::operator-=(), mrpt::math::TPoint3D_< float >::operator<(), mrpt::math::operator==(), mrpt::topography::path_from_rtk_gps(), mrpt::vision::pixelTo3D(), mrpt::maps::CPointsMapXYZI::PLY_export_get_vertex(), mrpt::maps::CColouredPointsMap::PLY_export_get_vertex(), mrpt::maps::CPointsMap::PLY_export_get_vertex(), mrpt::opengl::CPointCloud::PLY_import_set_vertex(), mrpt::opengl::CPointCloudColoured::PLY_import_set_vertex(), mrpt::maps::CPointsMapXYZI::PLY_import_set_vertex(), mrpt::maps::CColouredPointsMap::PLY_import_set_vertex(), mrpt::maps::CPointsMap::PLY_import_set_vertex(), mrpt::vision::pointJac(), project_point(), mrpt::vision::projectMatchedFeature(), mrpt::vision::projectMatchedFeatures(), mrpt::vision::pinhole::projectPoint_no_distortion(), mrpt::vision::pinhole::projectPoints_with_distortion(), mrpt::maps::CLandmarksMap::TCustomSequenceLandmarks::push_back(), mrpt::obs::detail::range2XYZ_LUT(), mrpt::maps::COccupancyGridMap3D::resizeGrid(), mrpt::poses::CPose3D::rotateVector(), mrpt::apps::CGridMapAlignerApp::run(), mrpt::apps::KFSLAMApp::Run_KF_SLAM(), mrpt::opengl::PLY_Exporter::saveToPlyFile(), se3_l2_internal(), mrpt::opengl::COctreePointRenderer< Derived >::TNode::setBBFromOrderInParent(), mrpt::opengl::CBox::setBoxCorners(), mrpt::opengl::CRenderizable::setLocation(), mrpt::slam::CRejectionSamplingRangeOnlyLocalization::setParams(), mrpt::maps::CPointsMap::setPoint(), mrpt::opengl::CCamera::setPointingAt(), mrpt::maps::COccupancyGridMap3D::setSize(), mrpt::poses::CPose3D::sphericalCoordinates(), mrpt::poses::CPose3DQuat::sphericalCoordinates(), mrpt::math::TPoint3D_< float >::sqrDistanceTo(), 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::math::TPoint2D_< double >::TPoint2D_(), mrpt::math::TPoint3D_< float >::TPoint3D_(), 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(), unsafeProjectPoint(), mrpt::opengl::COctreePointRenderer< Derived >::TNode::update_bb(), mrpt::topography::UTMToGeodetic(), and velodyne_scan_to_pointcloud().

◆ z

template<typename T>
T mrpt::math::TPoint3D_data< T >::z
inherited

Definition at line 29 of file TPoint3D.h.

Referenced by mrpt::math::areAligned(), aux_projectPoint_with_distortion(), mrpt::maps::CPointsMap::boundingBox(), mrpt::math::TPoint3D_< float >::cast(), mrpt::maps::COctoMapBase< octomap::OcTree, octomap::OcTreeNode >::castRay(), mrpt::poses::CPointPDFParticles::changeCoordinatesReference(), mrpt::maps::CLandmarksMap::changeCoordinatesReference(), mrpt::math::TPose3D::composePoint(), mrpt::poses::CPose2D::composePoint(), mrpt::poses::CPose3D::composePoint(), mrpt::maps::CLandmarksMap::computeLikelihood_SIFT_LandmarkMap(), mrpt::maps::CLandmarksMap::computeMatchingWith3DLandmarks(), mrpt::vision::computeMsd(), mrpt::math::conformAPlane(), mrpt::math::TPolygon3D::contains(), mrpt::math::TLine3D::contains(), mrpt::obs::detail::cost_func(), mrpt::poses::CPoint3D::CPoint3D(), mrpt::opengl::CPolyhedron::CreateCubicPrism(), mrpt::math::TPolygon3D::distance(), mrpt::math::TLine3D::distance(), mrpt::math::distance(), mrpt::math::TPoint3D_< float >::distanceTo(), mrpt::poses::CPoseOrPoint< CPose2D, DIM >::distanceTo(), mrpt::graphs::detail::CVisualizer< CPOSE, MAPS_IMPLEMENTATION, TMRSlamNodeAnnotations, EDGE_ANNOTATIONS >::drawGroundGrid(), mrpt::opengl::enqueForRendering(), mrpt::topography::ENU_axes_from_WGS84(), mrpt::topography::ENUToGeocentric(), mrpt::detectors::CFaceDetection::experimental_viewFacePointsAndEigenVects(), mrpt::maps::CPointsMap::extractPoints(), mrpt::maps::CPointCloudFilterByDistance::filter(), 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::CPointsMap::getAs3DObject(), mrpt::maps::COctoMap::getAsOctoMapVoxels(), mrpt::maps::CColouredOctoMap::getAsOctoMapVoxels(), mrpt::opengl::CFrustum::getBoundingBox(), mrpt::opengl::CSetOfObjects::getBoundingBox(), mrpt::opengl::COpenGLViewport::getBoundingBox(), mrpt::math::TPolygon3D::getCenter(), mrpt::math::TSegment3D::getCenter(), mrpt::opengl::CPolyhedron::TPolyhedronFace::getCenter(), mrpt::opengl::CPolyhedron::getCenter(), mrpt::opengl::COctreePointRenderer< Derived >::TNode::getCornerZ(), mrpt::opengl::CPolyhedron::getDual(), mrpt::opengl::CSetOfLines::getLineByIndex(), mrpt::maps::CPointsMap::getPoint(), mrpt::math::getPrismBounds(), mrpt::math::getSegmentBisector(), mrpt::opengl::graph_tools::graph_visualize(), mrpt::maps::CPointsMap::insertAnotherMap(), mrpt::maps::CRandomFieldGridMap3D::insertIndividualReading(), mrpt::maps::CPointsMap::insertPoint(), mrpt::maps::COccupancyGridMap3D::insertRay(), insertRotunda(), mrpt::maps::COctoMapBase< octomap::OcTree, octomap::OcTreeNode >::internal_build_PointCloud_for_observation(), mrpt::maps::CColouredOctoMap::internal_insertObservation(), mrpt::maps::CPointsMap::internal_insertObservation(), mrpt::maps::detail::pointmap_traits< CColouredPointsMap >::internal_loadFromRangeScan3D_prepareOneRange(), mrpt::opengl::COctreePointRenderer< CPointCloudColoured >::internal_recursive_split(), mrpt::math::intersect(), mrpt::maps::CHeightGridMap2D_Base::intersectLine3D(), mrpt::math::TPose3D::inverseComposePoint(), mrpt::poses::CPose3D::inverseComposePoint(), mrpt::poses::CPose3D::inverseRotateVector(), jacob_dA_eps_D_p_deps(), jacob_db_dp(), jacob_dh_db_and_dh_dc(), mrpt::math::KDTreeCapable< CFeatureList >::kdTreeClosestPoint3D(), mrpt::math::KDTreeCapable< CFeatureList >::kdTreeNClosestPoint3D(), mrpt::math::KDTreeCapable< CFeatureList >::kdTreeNClosestPoint3DIdx(), kfslam_traits< CRangeBearingKFSLAM2D >::landmark_to_3d(), kfslam_traits< CRangeBearingKFSLAM >::landmark_to_3d(), mrpt::maps::CLandmarksMap::loadOccupancyFeaturesFrom2DRangeScan(), mrpt::opengl::CAssimpModel::loadScene(), mrpt::vision::matchFeatures(), mrpt::slam::CRangeBearingKFSLAM::OnInverseObservationModel(), mrpt::opengl::COctoMapVoxels::onUpdateBuffers_Triangles(), mrpt::opengl::COctoMapVoxels::onUpdateBuffers_Wireframe(), mrpt::math::operator!=(), mrpt::math::TPoint3D_< float >::operator+(), mrpt::math::TPoint3D_< float >::operator+=(), mrpt::math::TPoint3D_< float >::operator-(), mrpt::math::operator-(), mrpt::math::TPoint3D_< float >::operator-=(), mrpt::math::TPoint3D_< float >::operator<(), mrpt::math::operator==(), mrpt::topography::path_from_rtk_gps(), mrpt::vision::pixelTo3D(), mrpt::maps::CPointsMapXYZI::PLY_export_get_vertex(), mrpt::maps::CColouredPointsMap::PLY_export_get_vertex(), mrpt::maps::CPointsMap::PLY_export_get_vertex(), mrpt::opengl::CPointCloud::PLY_import_set_vertex(), mrpt::opengl::CPointCloudColoured::PLY_import_set_vertex(), mrpt::maps::CPointsMapXYZI::PLY_import_set_vertex(), mrpt::maps::CColouredPointsMap::PLY_import_set_vertex(), mrpt::maps::CPointsMap::PLY_import_set_vertex(), mrpt::vision::pointJac(), project_point(), mrpt::vision::projectMatchedFeature(), mrpt::vision::projectMatchedFeatures(), mrpt::vision::pinhole::projectPoint_no_distortion(), mrpt::vision::pinhole::projectPoints_with_distortion(), mrpt::obs::detail::range2XYZ_LUT(), mrpt::maps::COccupancyGridMap3D::resizeGrid(), mrpt::poses::CPose3D::rotateVector(), mrpt::apps::CGridMapAlignerApp::run(), mrpt::apps::KFSLAMApp::Run_KF_SLAM(), mrpt::opengl::PLY_Exporter::saveToPlyFile(), se3_l2_internal(), mrpt::opengl::COctreePointRenderer< Derived >::TNode::setBBFromOrderInParent(), mrpt::opengl::CBox::setBoxCorners(), mrpt::opengl::CRenderizable::setLocation(), mrpt::slam::CRejectionSamplingRangeOnlyLocalization::setParams(), mrpt::maps::CPointsMap::setPoint(), mrpt::opengl::CCamera::setPointingAt(), mrpt::maps::COccupancyGridMap3D::setSize(), sort_voxels_z(), mrpt::poses::CPose3D::sphericalCoordinates(), mrpt::poses::CPose3DQuat::sphericalCoordinates(), mrpt::math::TPoint3D_< float >::sqrDistanceTo(), 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::math::TPoint3D_< float >::TPoint3D_(), 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::opengl::COctreePointRenderer< Derived >::TNode::update_bb(), mrpt::topography::UTMToGeodetic(), and velodyne_scan_to_pointcloud().




Page generated by Doxygen 1.8.14 for MRPT 2.0.1 Git: 0fef1a6d7 Fri Apr 3 23:00:21 2020 +0200 at vie abr 3 23:20:28 CEST 2020