A base class for representing a point in 2D or 3D.
For more information refer to the 2D/3D Geometry tutorial online.
#include <mrpt/poses/CPoint.h>
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... | |
void | getAsVector (mrpt::math::CVectorDouble &v) const |
Return the pose or point as a 1x2 or 1x3 vector [x y] or [x y z]. More... | |
mrpt::math::CVectorDouble | getAsVector () const |
void | getHomogeneousMatrix (mrpt::math::CMatrixDouble44 &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... | |
const double & | operator[] (unsigned int i) const |
double & | operator[] (unsigned int i) |
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: . 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... | |
|
inline |
|
inline |
Returns a human-readable textual representation of the object (eg: "[0.02 1.04]" )
|
inline |
Definition at line 81 of file CPoint.h.
Referenced by mrpt::poses::CPoint< CPoint3D >::asString().
|
inlineinherited |
Returns the 2D distance from this pose/point to a 2D point (ignores Z, if it exists).
Definition at line 165 of file CPoseOrPoint.h.
Referenced by mrpt::nav::PlannerRRT_SE2_TPS::solve().
|
inlineinherited |
Returns the squared 2D distance from this pose/point to a 2D point (ignores Z, if it exists).
Definition at line 156 of file CPoseOrPoint.h.
Referenced by mrpt::poses::CPoseOrPoint< CPoint3D >::distance2DTo().
|
inlineinherited |
Returns the 3D distance from this pose/point to a 3D point.
Definition at line 168 of file CPoseOrPoint.h.
Referenced by mrpt::poses::CPoseOrPoint< CPoint3D >::distanceTo(), mrpt::maps::CBeaconMap::internal_computeObservationLikelihood(), and mrpt::maps::CBeaconMap::internal_insertObservation().
|
inlineinherited |
Returns the squared 3D distance from this pose/point to a 3D point.
Definition at line 159 of file CPoseOrPoint.h.
Referenced by mrpt::poses::CPoseOrPoint< CPoint3D >::distance3DTo().
|
inlineinherited |
Returns the Euclidean distance to another pose/point:
Definition at line 150 of file CPoseOrPoint.h.
Referenced by ICPTests::align2scans(), mrpt::slam::CGridMapAligner::AlignPDF_robustMatch(), mrpt::graphslam::deciders::CFixedIntervalsNRD< GRAPH_T >::checkRegistrationCondition(), mrpt::maps::CBeacon::generateRingSOG(), mrpt::maps::CBeaconMap::internal_computeObservationLikelihood(), mrpt::maps::CLandmarksMap::internal_computeObservationLikelihood(), mrpt::maps::CBeaconMap::internal_insertObservation(), mrpt::hmtslam::CHMTSLAM::LSLAM_process_message_from_AA(), mrpt::hmtslam::CLSLAM_RBPF_2DLASER::processOneLMH(), ransac_data_assoc_run(), mrpt::slam::CRejectionSamplingRangeOnlyLocalization::RS_observationLikelihood(), mrpt::tfest::se2_l2_robust(), mrpt::maps::CBeaconMap::simulateBeaconReadings(), and mrpt::maps::CLandmarksMap::simulateBeaconReadings().
|
inlineinherited |
Returns the euclidean distance to a 3D point:
Definition at line 171 of file CPoseOrPoint.h.
|
inline |
|
inline |
|
inline |
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 58 of file CPoint.h.
Referenced by mrpt::poses::CPoint< CPoint3D >::getAsVector().
|
inlineinherited |
Return the pose or point as a 1xN vector with all the components (see derived classes for each implementation)
Definition at line 181 of file CPoseOrPoint.h.
Referenced by mrpt::maps::COccupancyGridMap2D::laserScanSimulatorWithUncertainty(), Pose3DQuatTests::test_compose(), Pose3DTests::test_compose(), Pose3DRotVecTests::test_compose(), Pose3DTests::test_composeFrom(), Pose3DQuatTests::test_composePoint(), Pose3DTests::test_composePoint(), Pose3DRotVecTests::test_conversions(), Pose3DTests::test_ExpLnEqual(), TEST_F(), Pose3DQuatTests::test_fromYPRAndBack(), Pose3DQuatTests::test_invComposePoint(), Pose3DTests::test_inverse(), Pose3DQuatPDFGaussTests::testChangeCoordsRef(), Pose3DPDFGaussTests::testChangeCoordsRef(), Pose3DPDFGaussTests::testPoseComposition(), Pose3DPDFGaussTests::testPoseInverse(), Pose3DPDFGaussTests::testPoseInverseComposition(), and Pose3DPDFGaussTests::testToQuatPDFAndBack().
|
inline |
Returns the corresponding 4x4 homogeneous transformation matrix for the point(translation) or pose (translation+orientation).
|
inlineinherited |
Returns the corresponding 4x4 homogeneous transformation matrix for the point(translation) or pose (translation+orientation).
Definition at line 191 of file CPoseOrPoint.h.
Referenced by mrpt::obs::CObservationStereoImages::getDescriptionAsText(), Pose3DQuatTests::test_copy(), Pose3DQuatTests::test_fromYPRAndBack(), and Pose3DQuatTests::test_unaryInverse().
|
inlineinherited |
Returns the corresponding 4x4 inverse homogeneous transformation matrix for this point or pose.
Definition at line 201 of file CPoseOrPoint.h.
Referenced by mrpt::poses::CPose3DRotVec::inverseComposeFrom(), and Pose3DTests::test_inverse().
|
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 208 of file CPoseOrPoint.h.
Referenced by mrpt::poses::CPoseOrPoint< CPoint3D >::getInverseHomogeneousMatrix().
|
inlinestaticinherited |
Return true for poses or points with a Z component, false otherwise.
Definition at line 127 of file CPoseOrPoint.h.
Referenced by mrpt::poses::CPoseOrPoint< CPoint3D >::distance3DToSquare(), mrpt::poses::CPoseOrPoint< CPoint3D >::norm(), and mrpt::poses::CPoseOrPoint< CPoint3D >::sqrDistanceTo().
|
inlineinherited |
Returns the euclidean norm of vector: .
Definition at line 174 of file CPoseOrPoint.h.
Referenced by mrpt::obs::CActionRobotMovement3D::computeFromOdometry_model6DOF(), mrpt::obs::CActionRobotMovement2D::computeFromOdometry_modelGaussian(), mrpt::obs::CActionRobotMovement2D::computeFromOdometry_modelThrun(), mrpt::obs::CActionRobotMovement2D::drawSingleSample_modelThrun(), mrpt::maps::detail::pointmap_traits< CColouredPointsMap >::internal_loadFromRangeScan3D_init(), mrpt::maps::CLandmarksMap::loadSiftFeaturesFromImageObservation(), mrpt::maps::CMultiMetricMapPDF::prediction_and_update_pfOptimalProposal(), mrpt::hmtslam::CLSLAM_RBPF_2DLASER::prediction_and_update_pfOptimalProposal(), mrpt::slam::CMetricMapBuilderRBPF::processActionObservation(), and mrpt::slam::CMetricMapBuilderICP::TDist::updateDistances().
|
inline |
|
inline |
|
inline |
|
pure virtualinherited |
Set all data fields to quiet NaN.
Implemented in mrpt::poses::CPose3D, mrpt::poses::CPose3DQuat, mrpt::poses::CPose3DRotVec, mrpt::poses::CPose2D, mrpt::poses::CPoint3D, and mrpt::poses::CPoint2D.
|
inlineinherited |
Returns the squared euclidean distance to another pose/point:
Definition at line 130 of file CPoseOrPoint.h.
Referenced by mrpt::poses::CPoseOrPoint< CPoint3D >::distanceTo().
|
inlineinherited |
Common members of all points & poses classes.
< Get X coord.
Definition at line 113 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::CPosePDFGaussianInf::bayesianFusion(), mrpt::poses::CPosePDFGaussian::bayesianFusion(), mrpt::poses::CPointPDFSOG::bayesianFusion(), 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::CPosePDFGaussianInf::drawManySamples(), mrpt::poses::CPosePDFGaussian::drawManySamples(), mrpt::poses::CPose3DPDFGaussian::drawManySamples(), mrpt::poses::CPoint2DPDFGaussian::drawSingleSample(), mrpt::poses::CPointPDFGaussian::drawSingleSample(), mrpt::poses::CPose3DPDFGaussianInf::drawSingleSample(), mrpt::poses::CPosePDFGaussianInf::drawSingleSample(), mrpt::poses::CPosePDFGaussian::drawSingleSample(), mrpt::poses::CPose3DPDFGaussian::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::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::CLandmarksMap::internal_computeObservationLikelihood(), mrpt::maps::CReflectivityGridMap2D::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::CPosePDFGaussianInf::inverse(), mrpt::poses::CPosePDFGaussian::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::maps::CMultiMetricMapPDF::prediction_and_update_pfOptimalProposal(), mrpt::hwdrivers::CSkeletonTracker::processPreviewNone(), 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::slam::CRejectionSamplingRangeOnlyLocalization::RS_drawFromProposal(), mrpt::slam::CRangeBearingKFSLAM2D::saveMapAndPath2DRepresentationAsMATLABFile(), mrpt::poses::CPoint2DPDFGaussian::saveToTextFile(), mrpt::poses::CPointPDFGaussian::saveToTextFile(), mrpt::poses::CPose3DQuatPDFGaussian::saveToTextFile(), mrpt::poses::CPose3DQuatPDFGaussianInf::saveToTextFile(), mrpt::poses::CPosePDFGaussian::saveToTextFile(), mrpt::poses::CPosePDFGaussianInf::saveToTextFile(), mrpt::poses::CPose3DPDFGaussianInf::saveToTextFile(), mrpt::poses::CPose3DPDFGaussian::saveToTextFile(), se3_l2_internal(), mrpt::tfest::se3_l2_robust(), 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(), TEST(), 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().
|
inlineinherited |
Definition at line 116 of file CPoseOrPoint.h.
|
inlineinherited |
v | Set X coord. |
Definition at line 119 of file CPoseOrPoint.h.
|
inlineinherited |
v | X+=v |
Definition at line 122 of file CPoseOrPoint.h.
Referenced by mrpt::slam::CICP::ICP_Method_Classic(), mrpt::maps::CBeaconMap::internal_insertObservation(), and TEST().
|
inlineinherited |
< Get Y coord.
Definition at line 114 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::CPosePDFGaussianInf::bayesianFusion(), mrpt::poses::CPosePDFGaussian::bayesianFusion(), mrpt::poses::CPointPDFSOG::bayesianFusion(), 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::CPosePDFGaussianInf::drawManySamples(), mrpt::poses::CPosePDFGaussian::drawManySamples(), mrpt::poses::CPose3DPDFGaussian::drawManySamples(), mrpt::poses::CPoint2DPDFGaussian::drawSingleSample(), mrpt::poses::CPointPDFGaussian::drawSingleSample(), mrpt::poses::CPose3DPDFGaussianInf::drawSingleSample(), mrpt::poses::CPosePDFGaussianInf::drawSingleSample(), mrpt::poses::CPosePDFGaussian::drawSingleSample(), mrpt::poses::CPose3DPDFGaussian::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::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::CLandmarksMap::internal_computeObservationLikelihood(), mrpt::maps::CReflectivityGridMap2D::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::CPosePDFGaussianInf::inverse(), mrpt::poses::CPosePDFGaussian::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::maps::CMultiMetricMapPDF::prediction_and_update_pfOptimalProposal(), mrpt::hwdrivers::CSkeletonTracker::processPreviewNone(), 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::slam::CRejectionSamplingRangeOnlyLocalization::RS_drawFromProposal(), mrpt::slam::CRangeBearingKFSLAM2D::saveMapAndPath2DRepresentationAsMATLABFile(), mrpt::poses::CPoint2DPDFGaussian::saveToTextFile(), mrpt::poses::CPointPDFGaussian::saveToTextFile(), mrpt::poses::CPose3DQuatPDFGaussian::saveToTextFile(), mrpt::poses::CPose3DQuatPDFGaussianInf::saveToTextFile(), mrpt::poses::CPosePDFGaussian::saveToTextFile(), mrpt::poses::CPosePDFGaussianInf::saveToTextFile(), mrpt::poses::CPose3DPDFGaussianInf::saveToTextFile(), mrpt::poses::CPose3DPDFGaussian::saveToTextFile(), se3_l2_internal(), mrpt::tfest::se3_l2_robust(), 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().
|
inlineinherited |
Definition at line 117 of file CPoseOrPoint.h.
|
inlineinherited |
v | Set Y coord. |
Definition at line 120 of file CPoseOrPoint.h.
|
inlineinherited |
v | Y+=v |
Definition at line 123 of file CPoseOrPoint.h.
Referenced by mrpt::slam::CICP::ICP_Method_Classic(), and mrpt::maps::CBeaconMap::internal_insertObservation().
Page generated by Doxygen 1.8.14 for MRPT 1.5.9 Git: 690a4699f Wed Apr 15 19:29:53 2020 +0200 at miƩ abr 15 19:30:12 CEST 2020 |