MRPT  2.0.0
List of all members | Public Types | Private Member Functions
mrpt::poses::CPoint< DERIVEDCLASS, DIM > Class Template Referenceabstract

Detailed Description

template<class DERIVEDCLASS, std::size_t DIM>
class mrpt::poses::CPoint< DERIVEDCLASS, DIM >

A base class for representing a point in 2D or 3D.

For more information refer to the 2D/3D Geometry tutorial online.

Note
This class is based on the CRTP design pattern
See also
CPoseOrPoint, CPose

Definition at line 24 of file CPoint.h.

#include <mrpt/poses/CPoint.h>

Inheritance diagram for mrpt::poses::CPoint< DERIVEDCLASS, DIM >:

Public Types

using vector_t = mrpt::math::CVectorFixedDouble< DIM >
 Fixed-size vector of the correct size to hold all the coordinates of the point/pose. More...
 

Public Member Functions

Methods common to all 2D or 3D points
template<class OTHERCLASS >
void AddComponents (const OTHERCLASS &b)
 Scalar addition of all coordinates. More...
 
void operator*= (const double s)
 Scalar multiplication. More...
 
template<class MATRIX44 >
void getHomogeneousMatrix (MATRIX44 &out_HM) const
 Returns the corresponding 4x4 homogeneous transformation matrix for the point(translation) or pose (translation+orientation). More...
 
void asString (std::string &s) const
 Returns a human-readable textual representation of the object (eg: "[0.02 1.04]" ) 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]" ) More...
 
double operator[] (unsigned int i) const
 
double & operator[] (unsigned int i)
 

Private Member Functions

DERIVEDCLASS & derived ()
 
const DERIVEDCLASS & derived () const
 
double x () const
 Common members of all points & poses classes. More...
 
double & x ()
 
void x (const double v)
 
double y () const
 
double & y ()
 
void y (const double v)
 
void x_incr (const double v)
 
void y_incr (const double v)
 
template<class OTHERCLASS , std::size_t DIM2>
double sqrDistanceTo (const CPoseOrPoint< OTHERCLASS, DIM2 > &b) const
 Returns the squared euclidean distance to another pose/point: More...
 
template<class OTHERCLASS , std::size_t DIM2>
double distanceTo (const CPoseOrPoint< OTHERCLASS, DIM2 > &b) const
 Returns the Euclidean distance to another pose/point: More...
 
double distanceTo (const mrpt::math::TPoint3D &b) const
 Returns the euclidean distance to a 3D point: More...
 
double distance2DToSquare (double ax, double ay) const
 Returns the squared 2D distance from this pose/point to a 2D point (ignores Z, if it exists). More...
 
double distance3DToSquare (double ax, double ay, double az) const
 Returns the squared 3D distance from this pose/point to a 3D point. More...
 
double distance2DTo (double ax, double ay) const
 Returns the 2D distance from this pose/point to a 2D point (ignores Z, if it exists). More...
 
double distance3DTo (double ax, double ay, double az) const
 Returns the 3D distance from this pose/point to a 3D point. More...
 
double norm () const
 Returns the euclidean norm of vector: $ ||\mathbf{x}|| = \sqrt{x^2+y^2+z^2} $. More...
 
vector_t asVectorVal () const
 Return the pose or point as a 1xN vector with all the components (see derived classes for each implementation) More...
 
template<class MATRIX44 >
MATRIX44 getHomogeneousMatrixVal () const
 Returns the corresponding 4x4 homogeneous transformation matrix for the point(translation) or pose (translation+orientation). More...
 
template<class MATRIX44 >
void getInverseHomogeneousMatrix (MATRIX44 &out_HM) const
 Returns the corresponding 4x4 inverse homogeneous transformation matrix for this point or pose. More...
 
template<class MATRIX44 >
MATRIX44 getInverseHomogeneousMatrixVal () const
 
virtual void setToNaN ()=0
 Set all data fields to quiet NaN. More...
 
static bool is3DPoseOrPoint ()
 Return true for poses or points with a Z component, false otherwise. More...
 

Member Typedef Documentation

◆ vector_t

template<class DERIVEDCLASS, std::size_t DIM>
using mrpt::poses::CPoseOrPoint< DERIVEDCLASS, DIM >::vector_t = mrpt::math::CVectorFixedDouble<DIM>
inherited

Fixed-size vector of the correct size to hold all the coordinates of the point/pose.

Definition at line 137 of file CPoseOrPoint.h.

Member Function Documentation

◆ AddComponents()

template<class DERIVEDCLASS, std::size_t DIM>
template<class OTHERCLASS >
void mrpt::poses::CPoint< DERIVEDCLASS, DIM >::AddComponents ( const OTHERCLASS &  b)
inline

Scalar addition of all coordinates.

This is diferent from poses/point composition, which is implemented as "+" operators in classes derived from "CPose"

Definition at line 41 of file CPoint.h.

◆ asString() [1/2]

template<class DERIVEDCLASS , std::size_t DIM>
void CPoint::asString ( std::string &  s) const

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

See also
fromString

Definition at line 32 of file CPoint.cpp.

Referenced by TEST().

Here is the caller graph for this function:

◆ asString() [2/2]

template<class DERIVEDCLASS, std::size_t DIM>
std::string mrpt::poses::CPoint< DERIVEDCLASS, DIM >::asString ( ) const
inline

Definition at line 77 of file CPoint.h.

Referenced by mrpt::poses::CPoint< CPoint3D, 3 >::asString().

Here is the caller graph for this function:

◆ asVectorVal()

template<class DERIVEDCLASS, std::size_t DIM>
vector_t mrpt::poses::CPoseOrPoint< DERIVEDCLASS, DIM >::asVectorVal ( ) const
inlineinherited

◆ derived() [1/2]

template<class DERIVEDCLASS, std::size_t DIM>
DERIVEDCLASS& mrpt::poses::CPoint< DERIVEDCLASS, DIM >::derived ( )
inlineprivate

Definition at line 26 of file CPoint.h.

Referenced by mrpt::poses::CPoint< CPoint3D, 3 >::AddComponents(), mrpt::poses::CPoint< CPoint3D, 3 >::operator*=(), and mrpt::poses::CPoint< CPoint3D, 3 >::operator[]().

Here is the caller graph for this function:

◆ derived() [2/2]

template<class DERIVEDCLASS, std::size_t DIM>
const DERIVEDCLASS& mrpt::poses::CPoint< DERIVEDCLASS, DIM >::derived ( ) const
inlineprivate

Definition at line 27 of file CPoint.h.

◆ distance2DTo()

template<class DERIVEDCLASS, std::size_t DIM>
double mrpt::poses::CPoseOrPoint< DERIVEDCLASS, DIM >::distance2DTo ( double  ax,
double  ay 
) const
inlineinherited

Returns the 2D distance from this pose/point to a 2D point (ignores Z, if it exists).

Definition at line 237 of file CPoseOrPoint.h.

Referenced by mrpt::apps::CGridMapAlignerApp::run(), and mrpt::nav::PlannerRRT_SE2_TPS::solve().

Here is the caller graph for this function:

◆ distance2DToSquare()

template<class DERIVEDCLASS, std::size_t DIM>
double mrpt::poses::CPoseOrPoint< DERIVEDCLASS, DIM >::distance2DToSquare ( double  ax,
double  ay 
) const
inlineinherited

Returns the squared 2D distance from this pose/point to a 2D point (ignores Z, if it exists).

Definition at line 221 of file CPoseOrPoint.h.

Referenced by mrpt::poses::CPoseOrPoint< CPose2D, DIM >::distance2DTo().

Here is the caller graph for this function:

◆ distance3DTo()

template<class DERIVEDCLASS, std::size_t DIM>
double mrpt::poses::CPoseOrPoint< DERIVEDCLASS, DIM >::distance3DTo ( double  ax,
double  ay,
double  az 
) const
inlineinherited

Returns the 3D distance from this pose/point to a 3D point.

Definition at line 243 of file CPoseOrPoint.h.

Referenced by mrpt::poses::CPoseOrPoint< CPose2D, DIM >::distanceTo(), mrpt::maps::CBeaconMap::internal_computeObservationLikelihood(), and mrpt::maps::CBeaconMap::internal_insertObservation().

Here is the caller graph for this function:

◆ distance3DToSquare()

template<class DERIVEDCLASS, std::size_t DIM>
double mrpt::poses::CPoseOrPoint< DERIVEDCLASS, DIM >::distance3DToSquare ( double  ax,
double  ay,
double  az 
) const
inlineinherited

Returns the squared 3D distance from this pose/point to a 3D point.

Definition at line 228 of file CPoseOrPoint.h.

Referenced by mrpt::poses::CPoseOrPoint< CPose2D, DIM >::distance3DTo().

Here is the caller graph for this function:

◆ distanceTo() [1/2]

template<class DERIVEDCLASS, std::size_t DIM>
template<class OTHERCLASS , std::size_t DIM2>
double mrpt::poses::CPoseOrPoint< DERIVEDCLASS, DIM >::distanceTo ( const CPoseOrPoint< OTHERCLASS, DIM2 > &  b) const
inlineinherited

◆ distanceTo() [2/2]

template<class DERIVEDCLASS, std::size_t DIM>
double mrpt::poses::CPoseOrPoint< DERIVEDCLASS, DIM >::distanceTo ( const mrpt::math::TPoint3D b) const
inlineinherited

Returns the euclidean distance to a 3D point:

Definition at line 249 of file CPoseOrPoint.h.

◆ fromString()

template<class DERIVEDCLASS , std::size_t DIM>
void CPoint::fromString ( const std::string &  s)

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

See also
asString
Exceptions
std::exceptionOn invalid format

Definition at line 20 of file CPoint.cpp.

Referenced by TEST().

Here is the caller graph for this function:

◆ getHomogeneousMatrix()

template<class DERIVEDCLASS, std::size_t DIM>
template<class MATRIX44 >
void mrpt::poses::CPoint< DERIVEDCLASS, DIM >::getHomogeneousMatrix ( MATRIX44 &  out_HM) const
inline

Returns the corresponding 4x4 homogeneous transformation matrix for the point(translation) or pose (translation+orientation).

See also
getInverseHomogeneousMatrix

Definition at line 63 of file CPoint.h.

◆ getHomogeneousMatrixVal()

template<class DERIVEDCLASS, std::size_t DIM>
template<class MATRIX44 >
MATRIX44 mrpt::poses::CPoseOrPoint< DERIVEDCLASS, DIM >::getHomogeneousMatrixVal ( ) const
inlineinherited

Returns the corresponding 4x4 homogeneous transformation matrix for the point(translation) or pose (translation+orientation).

See also
getInverseHomogeneousMatrix

Definition at line 278 of file CPoseOrPoint.h.

Referenced by Pose3DTests::check_jacob_LnT_T(), mrpt::opengl::enqueForRendering(), mrpt::obs::CObservationPointCloud::getDescriptionAsText(), mrpt::maps::COccupancyGridMap2D::internal_insertObservation(), Pose3DQuatTests::test_copy(), Pose3DTests::test_default_values(), Pose3DQuatTests::test_fromYPRAndBack(), Pose3DTests::test_inverse(), Pose3DTests::test_Jacob_dDexpe_de(), Pose3DTests::test_Jacob_dexpeD_de(), Pose3DQuatTests::test_unaryInverse(), and mrpt::obs::detail::unprojectInto().

Here is the caller graph for this function:

◆ getInverseHomogeneousMatrix()

template<class DERIVEDCLASS, std::size_t DIM>
template<class MATRIX44 >
void mrpt::poses::CPoseOrPoint< DERIVEDCLASS, DIM >::getInverseHomogeneousMatrix ( MATRIX44 &  out_HM) const
inlineinherited

Returns the corresponding 4x4 inverse homogeneous transformation matrix for this point or pose.

See also
getHomogeneousMatrix

Definition at line 290 of file CPoseOrPoint.h.

Referenced by mrpt::poses::CPoseOrPoint< CPose2D, DIM >::getInverseHomogeneousMatrixVal(), mrpt::poses::CPoint3D::operator-(), mrpt::poses::operator-(), mrpt::vision::CStereoRectifyMap::setFromCamParams(), and Pose3DTests::test_inverse().

Here is the caller graph for this function:

◆ getInverseHomogeneousMatrixVal()

template<class DERIVEDCLASS, std::size_t DIM>
template<class MATRIX44 >
MATRIX44 mrpt::poses::CPoseOrPoint< DERIVEDCLASS, DIM >::getInverseHomogeneousMatrixVal ( ) const
inlineinherited

This is an overloaded member function, provided for convenience. It differs from the above function only in what argument(s) it accepts.

Definition at line 298 of file CPoseOrPoint.h.

Referenced by mrpt::poses::CPose2D::operator-().

Here is the caller graph for this function:

◆ is3DPoseOrPoint()

template<class DERIVEDCLASS, std::size_t DIM>
static bool mrpt::poses::CPoseOrPoint< DERIVEDCLASS, DIM >::is3DPoseOrPoint ( )
inlinestaticinherited

Return true for poses or points with a Z component, false otherwise.

Definition at line 180 of file CPoseOrPoint.h.

Referenced by mrpt::poses::CPoseOrPoint< CPose2D, DIM >::distance3DToSquare(), mrpt::poses::CPoseOrPoint< CPose2D, DIM >::norm(), mrpt::poses::operator<(), and mrpt::poses::CPoseOrPoint< CPose2D, DIM >::sqrDistanceTo().

Here is the caller graph for this function:

◆ norm()

template<class DERIVEDCLASS, std::size_t DIM>
double mrpt::poses::CPoseOrPoint< DERIVEDCLASS, DIM >::norm ( ) const
inlineinherited

◆ operator*=()

template<class DERIVEDCLASS, std::size_t DIM>
void mrpt::poses::CPoint< DERIVEDCLASS, DIM >::operator*= ( const double  s)
inline

Scalar multiplication.

Definition at line 52 of file CPoint.h.

◆ operator[]() [1/2]

template<class DERIVEDCLASS, std::size_t DIM>
double mrpt::poses::CPoint< DERIVEDCLASS, DIM >::operator[] ( unsigned int  i) const
inline

Definition at line 91 of file CPoint.h.

◆ operator[]() [2/2]

template<class DERIVEDCLASS, std::size_t DIM>
double& mrpt::poses::CPoint< DERIVEDCLASS, DIM >::operator[] ( unsigned int  i)
inline

Definition at line 95 of file CPoint.h.

◆ setToNaN()

template<class DERIVEDCLASS, std::size_t DIM>
virtual void mrpt::poses::CPoseOrPoint< DERIVEDCLASS, DIM >::setToNaN ( )
pure virtualinherited

◆ sqrDistanceTo()

template<class DERIVEDCLASS, std::size_t DIM>
template<class OTHERCLASS , std::size_t DIM2>
double mrpt::poses::CPoseOrPoint< DERIVEDCLASS, DIM >::sqrDistanceTo ( const CPoseOrPoint< OTHERCLASS, DIM2 > &  b) const
inlineinherited

Returns the squared euclidean distance to another pose/point:

Definition at line 187 of file CPoseOrPoint.h.

Referenced by mrpt::poses::CPoseOrPoint< CPose2D, DIM >::distanceTo().

Here is the caller graph for this function:

◆ x() [1/3]

template<class DERIVEDCLASS, std::size_t DIM>
double mrpt::poses::CPoseOrPoint< DERIVEDCLASS, DIM >::x ( ) const
inlineinherited

Common members of all points & poses classes.

< Get X coord.

Definition at line 143 of file CPoseOrPoint.h.

Referenced by mrpt::nav::CPTG_RobotShape_Circular::add_robotShape_to_setOfLines(), mrpt::slam::CGridMapAligner::AlignPDF_correlation(), mrpt::slam::CGridMapAligner::AlignPDF_robustMatch(), mrpt::graphs::detail::graph_ops< graph_t >::auxEuclid2Dist(), mrpt::poses::CPoint2DPDFGaussian::bayesianFusion(), mrpt::poses::CPointPDFGaussian::bayesianFusion(), mrpt::poses::CPosePDFGaussian::bayesianFusion(), mrpt::poses::CPosePDFGaussianInf::bayesianFusion(), mrpt::poses::CPointPDFSOG::bayesianFusion(), check_CPose3D_tofrom_ROS(), mrpt::maps::CColouredPointsMap::colourFromObservation(), mrpt::poses::CPosePDFGaussian::composePoint(), mrpt::obs::CActionRobotMovement3D::computeFromOdometry_model6DOF(), mrpt::obs::CActionRobotMovement2D::computeFromOdometry_modelThrun(), mrpt::maps::COccupancyGridMap2D::computeLikelihoodField_Thrun(), mrpt::maps::CBeaconMap::computeMatchingWith3DLandmarks(), mrpt::maps::CLandmarksMap::computeMatchingWith3DLandmarks(), mrpt::vision::computeMsd(), mrpt::maps::COccupancyGridMap2D::computeObservationLikelihood_CellsDifference(), mrpt::poses::CPose3DQuatPDFGaussian::copyFrom(), mrpt::poses::CPose3DPDFGaussian::copyFrom(), mrpt::poses::CPoint2D::CPoint2D(), mrpt::poses::CPoint3D::CPoint3D(), mrpt::poses::CPose2D::CPose2D(), mrpt::poses::CPose3D::CPose3D(), mrpt::poses::CPose3DQuat::CPose3DQuat(), mrpt::hwdrivers::CIbeoLuxETH::dataCollection(), mrpt::maps::CPointsMap::determineMatching2D(), mrpt::nav::PoseDistanceMetric< TNodeSE2_TP >::distance(), mrpt::poses::CPose2D::distance2DFrobeniusTo(), mrpt::poses::CPoseOrPoint< CPose2D, DIM >::distance2DToSquare(), mrpt::poses::CPoseOrPoint< CPose2D, DIM >::distance3DToSquare(), mrpt::apps::MonteCarloLocalization_Base::do_pf_localization(), mrpt::poses::CPoseRandomSampler::do_sample_2D(), mrpt::poses::CPoseRandomSampler::do_sample_3D(), mrpt::graphs::detail::CVisualizer< CPOSE, MAPS_IMPLEMENTATION, TMRSlamNodeAnnotations, EDGE_ANNOTATIONS >::drawEdgeRelPoses(), mrpt::graphs::detail::CVisualizer< CPOSE, MAPS_IMPLEMENTATION, TMRSlamNodeAnnotations, EDGE_ANNOTATIONS >::drawEdges(), mrpt::graphs::detail::CMRVisualizer< CPOSE, MAPS_IMPLEMENTATION, TMRSlamNodeAnnotations, EDGE_ANNOTATIONS >::drawEdges(), mrpt::graphs::detail::CVisualizer< CPOSE, MAPS_IMPLEMENTATION, TMRSlamNodeAnnotations, EDGE_ANNOTATIONS >::drawGroundGrid(), mrpt::poses::CPose3DPDFGaussianInf::drawManySamples(), mrpt::poses::CPosePDFGaussian::drawManySamples(), mrpt::poses::CPose3DPDFGaussian::drawManySamples(), mrpt::poses::CPosePDFGaussianInf::drawManySamples(), mrpt::graphs::detail::CVisualizer< CPOSE, MAPS_IMPLEMENTATION, TMRSlamNodeAnnotations, EDGE_ANNOTATIONS >::drawNodePoints(), mrpt::graphs::detail::CMRVisualizer< CPOSE, MAPS_IMPLEMENTATION, TMRSlamNodeAnnotations, EDGE_ANNOTATIONS >::drawNodePoints(), mrpt::poses::CPoseRandomSampler::drawSample(), mrpt::poses::CPoint2DPDFGaussian::drawSingleSample(), mrpt::poses::CPose3DPDFGaussianInf::drawSingleSample(), mrpt::poses::CPosePDFGaussian::drawSingleSample(), mrpt::poses::CPointPDFGaussian::drawSingleSample(), mrpt::poses::CPose3DPDFGaussian::drawSingleSample(), mrpt::poses::CPosePDFGaussianInf::drawSingleSample(), mrpt::poses::CPointPDFSOG::drawSingleSample(), mrpt::obs::CActionRobotMovement2D::drawSingleSample_modelThrun(), mrpt::hmtslam::CHierarchicalMapMHPartition::dumpAsText(), mrpt::poses::CPointPDFSOG::evaluatePDF(), mrpt::poses::CPosePDFSOG::evaluatePDF(), mrpt::vision::frameJac(), mrpt::ros1bridge::fromROS(), Pose3DQuatTests::func_inv_compose_point(), Pose3DTests::func_inv_compose_point(), func_laserSimul_callback(), mrpt::maps::CBeacon::generateObservationModelDistribution(), mrpt::maps::CBeacon::generateRingSOG(), mrpt::slam::CRangeBearingKFSLAM2D::getAs3DObject(), mrpt::maps::CBeacon::getAs3DObject(), mrpt::slam::CRangeBearingKFSLAM::getAs3DObject(), mrpt::hmtslam::CLocalMetricHypothesis::getAs3DScene(), mrpt::slam::CIncrementalMapPartitioner::getAs3DScene(), mrpt::hmtslam::CHierarchicalMapMHPartition::getAs3DScene(), mrpt::maps::CBeacon::getAsMatlabDrawCommands(), mrpt::apps::MonteCarloLocalization_Base::getGroundTruth(), mrpt::poses::CPoint< CPoint3D, 3 >::getHomogeneousMatrix(), mrpt::poses::CRobot2DPoseEstimator::getLatestRobotPose(), mrpt::poses::CPointPDFParticles::getMean(), mrpt::poses::CPointPDFSOG::getMean(), mrpt::hwdrivers::CImageGrabber_FlyCapture2::getObservation(), mrpt::maps::CLandmark::getPose(), mrpt::opengl::CRenderizable::getPoseX(), mrpt::slam::CICP::ICP3D_Method_Classic(), mrpt::slam::CICP::ICP_Method_Classic(), mrpt::slam::CICP::ICP_Method_LM(), mrpt::maps::COctoMapBase< octomap::OcTree, octomap::OcTreeNode >::internal_build_PointCloud_for_observation(), mrpt::maps::CBeaconMap::internal_computeObservationLikelihood(), mrpt::maps::CReflectivityGridMap2D::internal_computeObservationLikelihood(), mrpt::maps::CLandmarksMap::internal_computeObservationLikelihood(), mrpt::maps::CPointsMap::internal_computeObservationLikelihood(), mrpt::maps::CBeaconMap::internal_insertObservation(), mrpt::maps::CWirelessPowerGridMap2D::internal_insertObservation(), mrpt::maps::CReflectivityGridMap2D::internal_insertObservation(), mrpt::maps::CGasConcentrationGridMap2D::internal_insertObservation(), mrpt::maps::CColouredOctoMap::internal_insertObservation(), mrpt::maps::COccupancyGridMap2D::internal_insertObservation(), mrpt::poses::CPosePDFGaussian::inverse(), mrpt::poses::CPosePDFGaussianInf::inverse(), mrpt::poses::CPosePDFGaussian::inverseComposition(), jacob_dA_eps_D_p_deps(), mrpt::poses::CPose3DQuatPDF::jacobiansPoseComposition(), mrpt::poses::CPosePDF::jacobiansPoseComposition(), mrpt::maps::COccupancyGridMap2D::laserScanSimulator(), mrpt::maps::CLandmarksMap::loadSiftFeaturesFromStereoImageObservation(), mrpt::hmtslam::CLSLAM_RBPF_2DLASER::loadTPathBinFromPath(), mrpt::hmtslam::CHMTSLAM::LSLAM_process_message_from_AA(), mrpt::poses::CPoint2DPDFGaussian::mahalanobisDistanceTo(), mrpt::poses::CPointPDFGaussian::mahalanobisDistanceTo(), mrpt::poses::CPoint2DPDFGaussian::mahalanobisDistanceToPoint(), mrpt::poses::CPosePDFSOG::mergeModes(), mrpt::poses::CPoseOrPoint< CPose2D, DIM >::norm(), mrpt::slam::CRangeBearingKFSLAM2D::OnGetAction(), mrpt::slam::CRangeBearingKFSLAM2D::OnInverseObservationModel(), mrpt::slam::CRangeBearingKFSLAM2D::OnObservationJacobians(), mrpt::slam::CRangeBearingKFSLAM2D::OnObservationModel(), mrpt::slam::CRangeBearingKFSLAM2D::OnTransitionModel(), mrpt::poses::operator!=(), mrpt::poses::CPoint3D::operator+(), mrpt::poses::CPose2D::operator+(), mrpt::poses::CPose3D::operator+(), mrpt::poses::operator+(), mrpt::poses::CPoint2D::operator-(), mrpt::poses::operator<(), mrpt::poses::operator<<(), mrpt::poses::operator==(), mrpt::topography::path_from_rtk_gps(), mrpt::maps::CMultiMetricMapPDF::prediction_and_update_pfOptimalProposal(), mrpt::poses::CPoint2DPDFGaussian::productIntegralWith(), mrpt::poses::CPointPDFGaussian::productIntegralWith(), mrpt::poses::CPointPDFGaussian::productIntegralWith2D(), mrpt::obs::detail::range2XYZ_LUT(), ransac_data_assoc_run(), mrpt::opengl::COpenGLViewport::renderNormalSceneMode(), mrpt::slam::CRejectionSamplingRangeOnlyLocalization::RS_drawFromProposal(), mrpt::apps::CGridMapAlignerApp::run(), mrpt::apps::ICP_SLAM_App_Base::run(), mrpt::apps::RBPF_SLAM_App_Base::run(), mrpt::apps::KFSLAMApp::Run_KF_SLAM(), mrpt::vision::TSequenceFeatureObservations::saveAsSBAFiles(), mrpt::slam::CRangeBearingKFSLAM2D::saveMapAndPath2DRepresentationAsMATLABFile(), mrpt::slam::CRangeBearingKFSLAM::saveMapAndPath2DRepresentationAsMATLABFile(), mrpt::poses::CPoint2DPDFGaussian::saveToTextFile(), mrpt::poses::CPointPDFGaussian::saveToTextFile(), mrpt::poses::CPosePDFGaussian::saveToTextFile(), mrpt::poses::CPose3DQuatPDFGaussianInf::saveToTextFile(), mrpt::poses::CPosePDFGaussianInf::saveToTextFile(), mrpt::poses::CPose3DQuatPDFGaussian::saveToTextFile(), mrpt::poses::CPose3DPDFGaussianInf::saveToTextFile(), mrpt::poses::CPose3DPDFGaussian::saveToTextFile(), se3_l2_internal(), mrpt::tfest::se3_l2_robust(), mrpt::poses::CPosePDFGaussianInf::serializeTo(), mrpt::opengl::CRenderizable::setLocation(), mrpt::maps::CLandmark::setPose(), mrpt::opengl::CRenderizable::setPose(), mrpt::nav::PlannerRRT_SE2_TPS::solve(), mrpt::maps::COccupancyGridMap2D::sonarSimulator(), mrpt::poses::CPoseOrPoint< CPose2D, DIM >::sqrDistanceTo(), mrpt::tfest::TMatchingPairList::squareErrorVector(), mrpt::vision::StereoObs2BRObs(), TEST(), Pose3DTests::test_composePoint(), Pose3DTests::test_default_values(), TEST_F(), Pose3DTests::test_to_from_2d(), mrpt::ros1bridge::toROS_Pose(), mrpt::ros1bridge::toROS_tfTransform(), mrpt::opengl::CSphere::traceRay(), mrpt::opengl::CDisk::traceRay(), mrpt::nav::PlannerTPS_VirtualBase::transformPointcloudWithSquareClipping(), mrpt::graphs::detail::graph_ops< graph_t >::write_EDGE_line(), and mrpt::graphs::detail::graph_ops< graph_t >::write_VERTEX_line().

◆ x() [2/3]

template<class DERIVEDCLASS, std::size_t DIM>
double& mrpt::poses::CPoseOrPoint< DERIVEDCLASS, DIM >::x ( )
inlineinherited

Definition at line 152 of file CPoseOrPoint.h.

◆ x() [3/3]

template<class DERIVEDCLASS, std::size_t DIM>
void mrpt::poses::CPoseOrPoint< DERIVEDCLASS, DIM >::x ( const double  v)
inlineinherited
Parameters
vSet X coord.

Definition at line 161 of file CPoseOrPoint.h.

◆ x_incr()

template<class DERIVEDCLASS, std::size_t DIM>
void mrpt::poses::CPoseOrPoint< DERIVEDCLASS, DIM >::x_incr ( const double  v)
inlineinherited
Parameters
vX+=v

Definition at line 170 of file CPoseOrPoint.h.

Referenced by mrpt::slam::CICP::ICP_Method_Classic(), mrpt::maps::CBeaconMap::internal_insertObservation(), and TEST().

Here is the caller graph for this function:

◆ y() [1/3]

template<class DERIVEDCLASS, std::size_t DIM>
double mrpt::poses::CPoseOrPoint< DERIVEDCLASS, DIM >::y ( ) const
inlineinherited

< Get Y coord.

Definition at line 147 of file CPoseOrPoint.h.

Referenced by mrpt::nav::CPTG_RobotShape_Circular::add_robotShape_to_setOfLines(), mrpt::slam::CGridMapAligner::AlignPDF_correlation(), mrpt::slam::CGridMapAligner::AlignPDF_robustMatch(), mrpt::graphs::detail::graph_ops< graph_t >::auxEuclid2Dist(), mrpt::poses::CPoint2DPDFGaussian::bayesianFusion(), mrpt::poses::CPointPDFGaussian::bayesianFusion(), mrpt::poses::CPosePDFGaussian::bayesianFusion(), mrpt::poses::CPosePDFGaussianInf::bayesianFusion(), mrpt::poses::CPointPDFSOG::bayesianFusion(), check_CPose3D_tofrom_ROS(), mrpt::maps::CColouredPointsMap::colourFromObservation(), mrpt::poses::CPosePDFGaussian::composePoint(), mrpt::obs::CActionRobotMovement3D::computeFromOdometry_model6DOF(), mrpt::obs::CActionRobotMovement2D::computeFromOdometry_modelThrun(), mrpt::maps::COccupancyGridMap2D::computeLikelihoodField_Thrun(), mrpt::maps::CBeaconMap::computeMatchingWith3DLandmarks(), mrpt::maps::CLandmarksMap::computeMatchingWith3DLandmarks(), mrpt::vision::computeMsd(), mrpt::maps::COccupancyGridMap2D::computeObservationLikelihood_CellsDifference(), mrpt::poses::CPose3DQuatPDFGaussian::copyFrom(), mrpt::poses::CPose3DPDFGaussian::copyFrom(), mrpt::poses::CPoint2D::CPoint2D(), mrpt::poses::CPoint3D::CPoint3D(), mrpt::poses::CPose2D::CPose2D(), mrpt::poses::CPose3D::CPose3D(), mrpt::hwdrivers::CIbeoLuxETH::dataCollection(), mrpt::maps::CPointsMap::determineMatching2D(), mrpt::nav::PoseDistanceMetric< TNodeSE2_TP >::distance(), mrpt::poses::CPose2D::distance2DFrobeniusTo(), mrpt::poses::CPoseOrPoint< CPose2D, DIM >::distance2DToSquare(), mrpt::poses::CPoseOrPoint< CPose2D, DIM >::distance3DToSquare(), mrpt::apps::MonteCarloLocalization_Base::do_pf_localization(), mrpt::poses::CPoseRandomSampler::do_sample_2D(), mrpt::poses::CPoseRandomSampler::do_sample_3D(), mrpt::graphs::detail::CVisualizer< CPOSE, MAPS_IMPLEMENTATION, TMRSlamNodeAnnotations, EDGE_ANNOTATIONS >::drawEdgeRelPoses(), mrpt::graphs::detail::CVisualizer< CPOSE, MAPS_IMPLEMENTATION, TMRSlamNodeAnnotations, EDGE_ANNOTATIONS >::drawEdges(), mrpt::graphs::detail::CMRVisualizer< CPOSE, MAPS_IMPLEMENTATION, TMRSlamNodeAnnotations, EDGE_ANNOTATIONS >::drawEdges(), mrpt::graphs::detail::CVisualizer< CPOSE, MAPS_IMPLEMENTATION, TMRSlamNodeAnnotations, EDGE_ANNOTATIONS >::drawGroundGrid(), mrpt::poses::CPose3DPDFGaussianInf::drawManySamples(), mrpt::poses::CPosePDFGaussian::drawManySamples(), mrpt::poses::CPose3DPDFGaussian::drawManySamples(), mrpt::poses::CPosePDFGaussianInf::drawManySamples(), mrpt::graphs::detail::CVisualizer< CPOSE, MAPS_IMPLEMENTATION, TMRSlamNodeAnnotations, EDGE_ANNOTATIONS >::drawNodePoints(), mrpt::graphs::detail::CMRVisualizer< CPOSE, MAPS_IMPLEMENTATION, TMRSlamNodeAnnotations, EDGE_ANNOTATIONS >::drawNodePoints(), mrpt::poses::CPoseRandomSampler::drawSample(), mrpt::poses::CPoint2DPDFGaussian::drawSingleSample(), mrpt::poses::CPose3DPDFGaussianInf::drawSingleSample(), mrpt::poses::CPosePDFGaussian::drawSingleSample(), mrpt::poses::CPointPDFGaussian::drawSingleSample(), mrpt::poses::CPose3DPDFGaussian::drawSingleSample(), mrpt::poses::CPosePDFGaussianInf::drawSingleSample(), mrpt::poses::CPointPDFSOG::drawSingleSample(), mrpt::obs::CActionRobotMovement2D::drawSingleSample_modelThrun(), mrpt::hmtslam::CHierarchicalMapMHPartition::dumpAsText(), mrpt::poses::CPointPDFSOG::evaluatePDF(), mrpt::poses::CPosePDFSOG::evaluatePDF(), mrpt::vision::frameJac(), mrpt::ros1bridge::fromROS(), Pose3DQuatTests::func_inv_compose_point(), Pose3DTests::func_inv_compose_point(), func_laserSimul_callback(), mrpt::maps::CBeacon::generateObservationModelDistribution(), mrpt::maps::CBeacon::generateRingSOG(), mrpt::slam::CRangeBearingKFSLAM2D::getAs3DObject(), mrpt::maps::CBeacon::getAs3DObject(), mrpt::slam::CRangeBearingKFSLAM::getAs3DObject(), mrpt::hmtslam::CLocalMetricHypothesis::getAs3DScene(), mrpt::slam::CIncrementalMapPartitioner::getAs3DScene(), mrpt::hmtslam::CHierarchicalMapMHPartition::getAs3DScene(), mrpt::maps::CBeacon::getAsMatlabDrawCommands(), mrpt::apps::MonteCarloLocalization_Base::getGroundTruth(), mrpt::poses::CPoint< CPoint3D, 3 >::getHomogeneousMatrix(), mrpt::poses::CRobot2DPoseEstimator::getLatestRobotPose(), mrpt::poses::CPointPDFParticles::getMean(), mrpt::poses::CPointPDFSOG::getMean(), mrpt::hwdrivers::CImageGrabber_FlyCapture2::getObservation(), mrpt::maps::CLandmark::getPose(), mrpt::opengl::CRenderizable::getPoseY(), mrpt::slam::CICP::ICP3D_Method_Classic(), mrpt::slam::CICP::ICP_Method_Classic(), mrpt::slam::CICP::ICP_Method_LM(), mrpt::maps::COctoMapBase< octomap::OcTree, octomap::OcTreeNode >::internal_build_PointCloud_for_observation(), mrpt::maps::CBeaconMap::internal_computeObservationLikelihood(), mrpt::maps::CReflectivityGridMap2D::internal_computeObservationLikelihood(), mrpt::maps::CLandmarksMap::internal_computeObservationLikelihood(), mrpt::maps::CBeaconMap::internal_insertObservation(), mrpt::maps::CWirelessPowerGridMap2D::internal_insertObservation(), mrpt::maps::CReflectivityGridMap2D::internal_insertObservation(), mrpt::maps::CGasConcentrationGridMap2D::internal_insertObservation(), mrpt::maps::CColouredOctoMap::internal_insertObservation(), mrpt::maps::COccupancyGridMap2D::internal_insertObservation(), mrpt::poses::CPosePDFGaussian::inverse(), mrpt::poses::CPosePDFGaussianInf::inverse(), mrpt::poses::CPosePDFGaussian::inverseComposition(), jacob_dA_eps_D_p_deps(), mrpt::poses::CPose3DQuatPDF::jacobiansPoseComposition(), mrpt::poses::CPosePDF::jacobiansPoseComposition(), mrpt::maps::COccupancyGridMap2D::laserScanSimulator(), mrpt::hmtslam::CLSLAM_RBPF_2DLASER::loadTPathBinFromPath(), mrpt::hmtslam::CHMTSLAM::LSLAM_process_message_from_AA(), mrpt::poses::CPoint2DPDFGaussian::mahalanobisDistanceTo(), mrpt::poses::CPointPDFGaussian::mahalanobisDistanceTo(), mrpt::poses::CPoint2DPDFGaussian::mahalanobisDistanceToPoint(), mrpt::poses::CPosePDFSOG::mergeModes(), mrpt::poses::CPoseOrPoint< CPose2D, DIM >::norm(), mrpt::slam::CRangeBearingKFSLAM2D::OnGetAction(), mrpt::slam::CRangeBearingKFSLAM2D::OnInverseObservationModel(), mrpt::slam::CRangeBearingKFSLAM2D::OnObservationJacobians(), mrpt::slam::CRangeBearingKFSLAM2D::OnObservationModel(), mrpt::slam::CRangeBearingKFSLAM2D::OnTransitionModel(), mrpt::poses::operator!=(), mrpt::poses::CPoint3D::operator+(), mrpt::poses::CPose2D::operator+(), mrpt::poses::CPose3D::operator+(), mrpt::poses::operator+(), mrpt::poses::CPoint2D::operator-(), mrpt::poses::operator<(), mrpt::poses::operator<<(), mrpt::poses::operator==(), mrpt::topography::path_from_rtk_gps(), mrpt::maps::CMultiMetricMapPDF::prediction_and_update_pfOptimalProposal(), mrpt::poses::CPoint2DPDFGaussian::productIntegralWith(), mrpt::poses::CPointPDFGaussian::productIntegralWith(), mrpt::poses::CPointPDFGaussian::productIntegralWith2D(), mrpt::obs::detail::range2XYZ_LUT(), ransac_data_assoc_run(), mrpt::opengl::COpenGLViewport::renderNormalSceneMode(), mrpt::slam::CRejectionSamplingRangeOnlyLocalization::RS_drawFromProposal(), mrpt::apps::CGridMapAlignerApp::run(), mrpt::apps::ICP_SLAM_App_Base::run(), mrpt::apps::RBPF_SLAM_App_Base::run(), mrpt::apps::KFSLAMApp::Run_KF_SLAM(), mrpt::vision::TSequenceFeatureObservations::saveAsSBAFiles(), mrpt::slam::CRangeBearingKFSLAM2D::saveMapAndPath2DRepresentationAsMATLABFile(), mrpt::slam::CRangeBearingKFSLAM::saveMapAndPath2DRepresentationAsMATLABFile(), mrpt::poses::CPoint2DPDFGaussian::saveToTextFile(), mrpt::poses::CPointPDFGaussian::saveToTextFile(), mrpt::poses::CPosePDFGaussian::saveToTextFile(), mrpt::poses::CPose3DQuatPDFGaussianInf::saveToTextFile(), mrpt::poses::CPose3DQuatPDFGaussian::saveToTextFile(), mrpt::poses::CPosePDFGaussianInf::saveToTextFile(), mrpt::poses::CPose3DPDFGaussianInf::saveToTextFile(), mrpt::poses::CPose3DPDFGaussian::saveToTextFile(), se3_l2_internal(), mrpt::tfest::se3_l2_robust(), mrpt::poses::CPosePDFGaussianInf::serializeTo(), mrpt::opengl::CRenderizable::setLocation(), mrpt::maps::CLandmark::setPose(), mrpt::opengl::CRenderizable::setPose(), mrpt::nav::PlannerRRT_SE2_TPS::solve(), mrpt::maps::COccupancyGridMap2D::sonarSimulator(), mrpt::poses::CPoseOrPoint< CPose2D, DIM >::sqrDistanceTo(), mrpt::tfest::TMatchingPairList::squareErrorVector(), TEST(), Pose3DTests::test_composePoint(), Pose3DTests::test_default_values(), TEST_F(), Pose3DTests::test_to_from_2d(), mrpt::ros1bridge::toROS_Pose(), mrpt::ros1bridge::toROS_tfTransform(), mrpt::opengl::CSphere::traceRay(), mrpt::opengl::CDisk::traceRay(), mrpt::nav::PlannerTPS_VirtualBase::transformPointcloudWithSquareClipping(), mrpt::graphs::detail::graph_ops< graph_t >::write_EDGE_line(), and mrpt::graphs::detail::graph_ops< graph_t >::write_VERTEX_line().

◆ y() [2/3]

template<class DERIVEDCLASS, std::size_t DIM>
double& mrpt::poses::CPoseOrPoint< DERIVEDCLASS, DIM >::y ( )
inlineinherited

Definition at line 156 of file CPoseOrPoint.h.

◆ y() [3/3]

template<class DERIVEDCLASS, std::size_t DIM>
void mrpt::poses::CPoseOrPoint< DERIVEDCLASS, DIM >::y ( const double  v)
inlineinherited
Parameters
vSet Y coord.

Definition at line 165 of file CPoseOrPoint.h.

◆ y_incr()

template<class DERIVEDCLASS, std::size_t DIM>
void mrpt::poses::CPoseOrPoint< DERIVEDCLASS, DIM >::y_incr ( const double  v)
inlineinherited
Parameters
vY+=v

Definition at line 174 of file CPoseOrPoint.h.

Referenced by mrpt::slam::CICP::ICP_Method_Classic(), and mrpt::maps::CBeaconMap::internal_insertObservation().

Here is the caller graph for this function:



Page generated by Doxygen 1.8.14 for MRPT 2.0.0 Git: b38439d21 Tue Mar 31 19:58:06 2020 +0200 at miƩ abr 1 00:50:30 CEST 2020