Main MRPT website > C++ reference for MRPT 1.9.9
List of all members
mrpt::poses::CPose< DERIVEDCLASS > Class Template Referenceabstract

Detailed Description

template<class DERIVEDCLASS>
class mrpt::poses::CPose< DERIVEDCLASS >

A base class for representing a pose 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, CPoint

Definition at line 27 of file CPose.h.

#include <mrpt/poses/CPose.h>

Inheritance diagram for mrpt::poses::CPose< DERIVEDCLASS >:
Inheritance graph
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 >
double sqrDistanceTo (const CPoseOrPoint< OTHERCLASS > &b) const
 Returns the squared euclidean distance to another pose/point: More...
 
template<class OTHERCLASS >
double distanceTo (const CPoseOrPoint< OTHERCLASS > &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...
 
mrpt::math::CVectorDouble getAsVectorVal () const
 Return the pose or point as a 1xN vector with all the components (see derived classes for each implementation) More...
 
mrpt::math::CMatrixDouble44 getHomogeneousMatrixVal () const
 Returns the corresponding 4x4 homogeneous transformation matrix for the point(translation) or pose (translation+orientation). More...
 
void getInverseHomogeneousMatrix (mrpt::math::CMatrixDouble44 &out_HM) const
 Returns the corresponding 4x4 inverse homogeneous transformation matrix for this point or pose. More...
 
mrpt::math::CMatrixDouble44 getInverseHomogeneousMatrix () 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 Function Documentation

◆ distance2DTo()

template<class DERIVEDCLASS>
double mrpt::poses::CPoseOrPoint< DERIVEDCLASS >::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 233 of file CPoseOrPoint.h.

Referenced by mrpt::nav::PlannerRRT_SE2_TPS::solve().

Here is the caller graph for this function:

◆ distance2DToSquare()

template<class DERIVEDCLASS>
double mrpt::poses::CPoseOrPoint< DERIVEDCLASS >::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 213 of file CPoseOrPoint.h.

Referenced by mrpt::poses::CPoseOrPoint< CPoint3D >::distance2DTo().

Here is the caller graph for this function:

◆ distance3DTo()

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

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

Definition at line 239 of file CPoseOrPoint.h.

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

Here is the caller graph for this function:

◆ distance3DToSquare()

template<class DERIVEDCLASS>
double mrpt::poses::CPoseOrPoint< DERIVEDCLASS >::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 220 of file CPoseOrPoint.h.

Referenced by mrpt::poses::CPoseOrPoint< CPoint3D >::distance3DTo().

Here is the caller graph for this function:

◆ distanceTo() [1/2]

template<class DERIVEDCLASS>
template<class OTHERCLASS >
double mrpt::poses::CPoseOrPoint< DERIVEDCLASS >::distanceTo ( const CPoseOrPoint< OTHERCLASS > &  b) const
inlineinherited

◆ distanceTo() [2/2]

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

Returns the euclidean distance to a 3D point:

Definition at line 245 of file CPoseOrPoint.h.

◆ getAsVectorVal()

template<class DERIVEDCLASS>
mrpt::math::CVectorDouble mrpt::poses::CPoseOrPoint< DERIVEDCLASS >::getAsVectorVal ( ) const
inlineinherited

◆ getHomogeneousMatrixVal()

template<class DERIVEDCLASS>
mrpt::math::CMatrixDouble44 mrpt::poses::CPoseOrPoint< DERIVEDCLASS >::getHomogeneousMatrixVal ( ) const
inlineinherited

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

See also
getInverseHomogeneousMatrix

Definition at line 276 of file CPoseOrPoint.h.

Referenced by mrpt::obs::CObservationStereoImagesFeatures::getDescriptionAsText(), mrpt::obs::CObservationStereoImages::getDescriptionAsText(), Pose3DQuatTests::test_copy(), Pose3DQuatTests::test_fromYPRAndBack(), and Pose3DQuatTests::test_unaryInverse().

Here is the caller graph for this function:

◆ getInverseHomogeneousMatrix() [1/2]

template<class DERIVEDCLASS>
void mrpt::poses::CPoseOrPoint< DERIVEDCLASS >::getInverseHomogeneousMatrix ( mrpt::math::CMatrixDouble44 out_HM) const
inlineinherited

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

See also
getHomogeneousMatrix

Definition at line 287 of file CPoseOrPoint.h.

Referenced by mrpt::poses::CPose3DRotVec::inverseComposeFrom(), and Pose3DTests::test_inverse().

Here is the caller graph for this function:

◆ getInverseHomogeneousMatrix() [2/2]

template<class DERIVEDCLASS>
mrpt::math::CMatrixDouble44 mrpt::poses::CPoseOrPoint< DERIVEDCLASS >::getInverseHomogeneousMatrix ( ) 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 295 of file CPoseOrPoint.h.

Referenced by mrpt::poses::CPoseOrPoint< CPoint3D >::getInverseHomogeneousMatrix().

Here is the caller graph for this function:

◆ is3DPoseOrPoint()

template<class DERIVEDCLASS>
static bool mrpt::poses::CPoseOrPoint< DERIVEDCLASS >::is3DPoseOrPoint ( )
inlinestaticinherited

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

Definition at line 172 of file CPoseOrPoint.h.

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

Here is the caller graph for this function:

◆ norm()

template<class DERIVEDCLASS>
double mrpt::poses::CPoseOrPoint< DERIVEDCLASS >::norm ( ) const
inlineinherited

◆ setToNaN()

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

◆ sqrDistanceTo()

template<class DERIVEDCLASS>
template<class OTHERCLASS >
double mrpt::poses::CPoseOrPoint< DERIVEDCLASS >::sqrDistanceTo ( const CPoseOrPoint< OTHERCLASS > &  b) const
inlineinherited

Returns the squared euclidean distance to another pose/point:

Definition at line 179 of file CPoseOrPoint.h.

Referenced by mrpt::poses::CPoseOrPoint< CPoint3D >::distanceTo().

Here is the caller graph for this function:

◆ x() [1/3]

template<class DERIVEDCLASS>
double mrpt::poses::CPoseOrPoint< DERIVEDCLASS >::x ( ) const
inlineinherited

Common members of all points & poses classes.

< Get X coord.

Definition at line 135 of file CPoseOrPoint.h.

Referenced by mrpt::nav::CPTG_RobotShape_Circular::add_robotShape_to_setOfLines(), 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(), mrpt::maps::CMultiMetricMapPDF::prediction_and_update< mrpt::slam::OptimalProposal >(), mrpt::maps::CColouredPointsMap::colourFromObservation(), 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::CPosePDFParticles::copyFrom(), mrpt::poses::CPose3DQuatPDFGaussian::copyFrom(), mrpt::poses::CPose3DPDFGaussian::copyFrom(), mrpt::poses::CPoint3D::CPoint3D(), mrpt::poses::CPose2D::CPose2D(), mrpt::poses::CPose3DRotVec::CPose3DRotVec(), mrpt::hwdrivers::CIbeoLuxETH::dataCollection(), mrpt::maps::CPointsMap::determineMatching2D(), mrpt::nav::PoseDistanceMetric< TNodeSE2_TP >::distance(), mrpt::poses::CPoseOrPoint< CPoint3D >::distance2DToSquare(), mrpt::poses::CPoseOrPoint< CPoint3D >::distance3DToSquare(), 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::poses::CPose3DPDFGaussianInf::drawManySamples(), mrpt::poses::CPosePDFGaussian::drawManySamples(), mrpt::poses::CPose3DPDFGaussian::drawManySamples(), mrpt::poses::CPosePDFGaussianInf::drawManySamples(), 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::SE_traits< 2 >::exp(), mrpt::poses::CPose3D::exp(), mrpt::obs::CActionRobotMovement2D::fastDrawSingleSample_modelGaussian(), mrpt::vision::frameJac(), 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::math::TLine2D::getAsPose2D(), mrpt::poses::CPoint< CPoint3D >::getHomogeneousMatrix(), mrpt::poses::CRobot2DPoseEstimator::getLatestRobotPose(), mrpt::hwdrivers::CImageGrabber_FlyCapture2::getObservation(), mrpt::maps::CLandmark::getPose(), mrpt::opengl::CRenderizable::getPoseX(), mrpt::opengl::graph_tools::graph_visualize(), 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::CColouredOctoMap::internal_insertObservation(), mrpt::maps::CReflectivityGridMap2D::internal_insertObservation(), mrpt::maps::CGasConcentrationGridMap2D::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::slam::KLF_loadBinFromParticle(), mrpt::maps::COccupancyGridMap2D::laserScanSimulator(), mrpt::poses::SE_traits< 2 >::ln(), 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< CPoint3D >::norm(), mrpt::slam::CRangeBearingKFSLAM2D::OnGetAction(), mrpt::slam::CRangeBearingKFSLAM2D::OnObservationModel(), mrpt::slam::CRangeBearingKFSLAM2D::OnTransitionModel(), mrpt::poses::operator!=(), mrpt::poses::CPose2D::operator+(), mrpt::poses::operator+(), mrpt::poses::operator==(), mrpt::topography::path_from_rtk_gps(), mrpt::opengl::CSetOfObjects::posePDF2opengl(), mrpt::poses::CPoint2DPDFGaussian::productIntegralWith(), mrpt::poses::CPointPDFGaussian::productIntegralWith(), mrpt::poses::CPointPDFGaussian::productIntegralWith2D(), mrpt::math::project2D(), mrpt::vision::projectMatchedFeatures(), ransac_data_assoc_run(), mrpt::opengl::CRenderizable::readFromStreamRender(), mrpt::opengl::COpenGLViewport::render(), mrpt::opengl::CPlanarLaserScan::render_dl(), mrpt::slam::CRejectionSamplingRangeOnlyLocalization::RS_drawFromProposal(), mrpt::slam::CRangeBearingKFSLAM2D::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::opengl::CRenderizable::setLocation(), mrpt::maps::CLandmark::setPose(), mrpt::opengl::CRenderizable::setPose(), mrpt::math::slerp(), mrpt::nav::PlannerRRT_SE2_TPS::solve(), mrpt::maps::COccupancyGridMap2D::sonarSimulator(), mrpt::poses::CPoseOrPoint< CPoint3D >::sqrDistanceTo(), mrpt::vision::StereoObs2BRObs(), Pose3DTests::test_composePoint(), Pose3DTests::test_to_from_2d(), mrpt::opengl::CDisk::traceRay(), mrpt::opengl::CSphere::traceRay(), mrpt::nav::PlannerTPS_VirtualBase::transformPointcloudWithSquareClipping(), mrpt::graphs::detail::graph_ops< graph_t >::write_EDGE_line(), mrpt::poses::CPosePDFGaussianInf::writeToStream(), and mrpt::opengl::CRenderizable::writeToStreamRender().

◆ x() [2/3]

template<class DERIVEDCLASS>
double& mrpt::poses::CPoseOrPoint< DERIVEDCLASS >::x ( )
inlineinherited

Definition at line 144 of file CPoseOrPoint.h.

◆ x() [3/3]

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

Definition at line 153 of file CPoseOrPoint.h.

◆ x_incr()

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

Definition at line 162 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:

◆ y() [1/3]

template<class DERIVEDCLASS>
double mrpt::poses::CPoseOrPoint< DERIVEDCLASS >::y ( ) const
inlineinherited

< Get Y coord.

Definition at line 139 of file CPoseOrPoint.h.

Referenced by mrpt::nav::CPTG_RobotShape_Circular::add_robotShape_to_setOfLines(), mrpt::slam::CGridMapAligner::AlignPDF_robustMatch(), mrpt::poses::CPoint< CPoint3D >::asString(), 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(), mrpt::maps::CMultiMetricMapPDF::prediction_and_update< mrpt::slam::OptimalProposal >(), mrpt::maps::CColouredPointsMap::colourFromObservation(), 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::CPosePDFParticles::copyFrom(), mrpt::poses::CPose3DQuatPDFGaussian::copyFrom(), mrpt::poses::CPose3DPDFGaussian::copyFrom(), mrpt::poses::CPose2D::CPose2D(), mrpt::poses::CPose3DRotVec::CPose3DRotVec(), mrpt::hwdrivers::CIbeoLuxETH::dataCollection(), mrpt::maps::CPointsMap::determineMatching2D(), mrpt::nav::PoseDistanceMetric< TNodeSE2_TP >::distance(), mrpt::poses::CPoseOrPoint< CPoint3D >::distance2DToSquare(), mrpt::poses::CPoseOrPoint< CPoint3D >::distance3DToSquare(), 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::poses::CPose3DPDFGaussianInf::drawManySamples(), mrpt::poses::CPosePDFGaussian::drawManySamples(), mrpt::poses::CPose3DPDFGaussian::drawManySamples(), mrpt::poses::CPosePDFGaussianInf::drawManySamples(), 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::SE_traits< 2 >::exp(), mrpt::poses::CPose3D::exp(), mrpt::obs::CActionRobotMovement2D::fastDrawSingleSample_modelGaussian(), mrpt::vision::frameJac(), 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::math::TLine2D::getAsPose2D(), mrpt::poses::CPoint< CPoint3D >::getHomogeneousMatrix(), mrpt::poses::CRobot2DPoseEstimator::getLatestRobotPose(), mrpt::hwdrivers::CImageGrabber_FlyCapture2::getObservation(), mrpt::maps::CLandmark::getPose(), mrpt::opengl::CRenderizable::getPoseY(), mrpt::opengl::graph_tools::graph_visualize(), 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::CColouredOctoMap::internal_insertObservation(), mrpt::maps::CReflectivityGridMap2D::internal_insertObservation(), mrpt::maps::CGasConcentrationGridMap2D::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::slam::KLF_loadBinFromParticle(), mrpt::maps::COccupancyGridMap2D::laserScanSimulator(), mrpt::poses::SE_traits< 2 >::ln(), 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< CPoint3D >::norm(), mrpt::slam::CRangeBearingKFSLAM2D::OnGetAction(), mrpt::slam::CRangeBearingKFSLAM2D::OnObservationModel(), mrpt::slam::CRangeBearingKFSLAM2D::OnTransitionModel(), mrpt::poses::operator!=(), mrpt::poses::CPose2D::operator+(), mrpt::poses::operator+(), mrpt::poses::operator==(), mrpt::topography::path_from_rtk_gps(), mrpt::opengl::CSetOfObjects::posePDF2opengl(), mrpt::poses::CPoint2DPDFGaussian::productIntegralWith(), mrpt::poses::CPointPDFGaussian::productIntegralWith(), mrpt::poses::CPointPDFGaussian::productIntegralWith2D(), mrpt::math::project2D(), ransac_data_assoc_run(), mrpt::opengl::CRenderizable::readFromStreamRender(), mrpt::opengl::COpenGLViewport::render(), mrpt::opengl::CPlanarLaserScan::render_dl(), mrpt::slam::CRejectionSamplingRangeOnlyLocalization::RS_drawFromProposal(), mrpt::slam::CRangeBearingKFSLAM2D::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::opengl::CRenderizable::setLocation(), mrpt::maps::CLandmark::setPose(), mrpt::opengl::CRenderizable::setPose(), mrpt::math::slerp(), mrpt::nav::PlannerRRT_SE2_TPS::solve(), mrpt::maps::COccupancyGridMap2D::sonarSimulator(), mrpt::poses::CPoseOrPoint< CPoint3D >::sqrDistanceTo(), Pose3DTests::test_composePoint(), Pose3DTests::test_to_from_2d(), mrpt::opengl::CDisk::traceRay(), mrpt::opengl::CSphere::traceRay(), mrpt::nav::PlannerTPS_VirtualBase::transformPointcloudWithSquareClipping(), mrpt::graphs::detail::graph_ops< graph_t >::write_EDGE_line(), mrpt::poses::CPosePDFGaussianInf::writeToStream(), and mrpt::opengl::CRenderizable::writeToStreamRender().

◆ y() [2/3]

template<class DERIVEDCLASS>
double& mrpt::poses::CPoseOrPoint< DERIVEDCLASS >::y ( )
inlineinherited

Definition at line 148 of file CPoseOrPoint.h.

◆ y() [3/3]

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

Definition at line 157 of file CPoseOrPoint.h.

◆ y_incr()

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

Definition at line 166 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 1.9.9 Git: ae4571287 Thu Nov 23 00:06:53 2017 +0100 at dom oct 27 23:51:55 CET 2019