| 
    MRPT
    2.0.0
    
   | 
 
Namespaces | |
| detail | |
Classes | |
| class | CGridMapAligner | 
| A class for aligning two multi-metric maps (with an occupancy grid maps and a points map, at least) based on features extraction and matching.  More... | |
| class | CICP | 
| Several implementations of ICP (Iterative closest point) algorithms for aligning two point maps or a point map wrt a grid map.  More... | |
| class | CIncrementalMapPartitioner | 
| Finds partitions in metric maps based on N-cut graph partition theory.  More... | |
| class | CMetricMapBuilder | 
| This virtual class is the base for SLAM implementations.  More... | |
| class | CMetricMapBuilderICP | 
| A class for very simple 2D SLAM based on ICP.  More... | |
| class | CMetricMapBuilderRBPF | 
| This class implements a Rao-Blackwelized Particle Filter (RBPF) approach to map building (SLAM).  More... | |
| class | CMetricMapsAlignmentAlgorithm | 
| A base class for any algorithm able of maps alignment.  More... | |
| class | CMonteCarloLocalization2D | 
| Declares a class that represents a Probability Density Function (PDF) over a 2D pose (x,y,phi), using a set of weighted samples.  More... | |
| class | CMonteCarloLocalization3D | 
| Declares a class that represents a Probability Density Function (PDF) over a 3D pose (x,y,phi,yaw,pitch,roll), using a set of weighted samples.  More... | |
| class | COccupancyGridMapFeatureExtractor | 
| A class for detecting features from occupancy grid maps.  More... | |
| class | CRangeBearingKFSLAM | 
| An implementation of EKF-based SLAM with range-bearing sensors, odometry, a full 6D robot pose, and 3D landmarks.  More... | |
| class | CRangeBearingKFSLAM2D | 
| An implementation of EKF-based SLAM with range-bearing sensors, odometry, and a 2D (+heading) robot pose, and 2D landmarks.  More... | |
| class | CRejectionSamplingRangeOnlyLocalization | 
| An implementation of rejection sampling for generating 2D robot pose from range-only measurements within a landmarks (beacons) map.  More... | |
| struct | map_keyframe_t | 
| Map keyframe, comprising raw observations and they as a metric map.  More... | |
| class | PF_implementation | 
| A set of common data shared by PF implementations for both SLAM and localization.  More... | |
| struct | TAuxDataRecursiveJCBB | 
| struct | TDataAssociationResults | 
| The results from mrpt::slam::data_association.  More... | |
| class | TKLDParams | 
| Option set for KLD algorithm.  More... | |
| struct | TMetricMapAlignmentResult | 
| Used as base class for other result structures of each particular algorithm in CMetricMapsAlignmentAlgorithm derived classes.  More... | |
| struct | TMonteCarloLocalizationParams | 
| The struct for passing extra simulation parameters to the prediction stage when running a particle filter.  More... | |
Typedefs | |
| using | similarity_func_t = std::function< double(const map_keyframe_t &kf1, const map_keyframe_t &kf2, const mrpt::poses::CPose3D &relPose2wrt1)> | 
| Type of similarity evaluator for map keyframes.  More... | |
Enumerations | |
| enum | TICPAlgorithm { icpClassic = 0, icpLevenbergMarquardt } | 
| The ICP algorithm selection, used in mrpt::slam::CICP::options mrpt_slam_grp.  More... | |
| enum | TICPCovarianceMethod { icpCovLinealMSE = 0, icpCovFiniteDifferences } | 
| ICP covariance estimation methods, used in mrpt::slam::CICP::options.  More... | |
| enum | similarity_method_t : uint8_t { smMETRIC_MAP_MATCHING = 0, smOBSERVATION_OVERLAP, smCUSTOM_FUNCTION } | 
| For use in CIncrementalMapPartitioner.  More... | |
Functions | |
| template<class PARTICLETYPE , class BINTYPE > | |
| void | KLF_loadBinFromParticle (BINTYPE &outBin, const TKLDParams &opts, const PARTICLETYPE *currentParticleValue=nullptr, const mrpt::math::TPose3D *newPoseToBeInserted=nullptr) | 
| template<> | |
| void | KLF_loadBinFromParticle (mrpt::slam::detail::TPoseBin2D &outBin, const TKLDParams &opts, const CMonteCarloLocalization2D::CParticleDataContent *currentParticleValue, const TPose3D *newPoseToBeInserted) | 
| Fills out a "TPoseBin2D" variable, given a path hypotesis and (if not set to nullptr) a new pose appended at the end, using the KLD params in "options".  More... | |
| template<> | |
| void | KLF_loadBinFromParticle (mrpt::slam::detail::TPoseBin3D &outBin, const TKLDParams &opts, const CMonteCarloLocalization3D::CParticleDataContent *currentParticleValue, const TPose3D *newPoseToBeInserted) | 
| Fills out a "TPoseBin3D" variable, given a path hypotesis and (if not set to nullptr) a new pose appended at the end, using the KLD params in "options".  More... | |
| template<> | |
| void | KLF_loadBinFromParticle (detail::TPoseBin2D &outBin, const TKLDParams &opts, const mrpt::maps::CRBPFParticleData *currentParticleValue, const TPose3D *newPoseToBeInserted) | 
| Fills out a "TPoseBin2D" variable, given a path hypotesis and (if not set to nullptr) a new pose appended at the end, using the KLD params in "options".  More... | |
| template<> | |
| void | KLF_loadBinFromParticle (detail::TPathBin2D &outBin, const TKLDParams &opts, const mrpt::maps::CRBPFParticleData *currentParticleValue, const TPose3D *newPoseToBeInserted) | 
| Fills out a "TPathBin2D" variable, given a path hypotesis and (if not set to nullptr) a new pose appended at the end, using the KLD params in "options".  More... | |
| template<typename T , TDataAssociationMetric METRIC> | |
| double | joint_pdf_metric (const CMatrixDynamic< T > &Z_observations_mean, const CMatrixDynamic< T > &Y_predictions_mean, const CMatrixDynamic< T > &Y_predictions_cov, const TAuxDataRecursiveJCBB &info, [[maybe_unused]] const TDataAssociationResults &aux_data) | 
| Computes the joint distance metric (mahalanobis or matching likelihood) between two a set of associations.  More... | |
| template<TDataAssociationMetric METRIC> | |
| bool | isCloser (const double v1, const double v2) | 
| template<> | |
| bool | isCloser< metricMaha > (const double v1, const double v2) | 
| template<> | |
| bool | isCloser< metricML > (const double v1, const double v2) | 
| template<typename T , TDataAssociationMetric METRIC> | |
| void | JCBB_recursive (const mrpt::math::CMatrixDynamic< T > &Z_observations_mean, const mrpt::math::CMatrixDynamic< T > &Y_predictions_mean, const mrpt::math::CMatrixDynamic< T > &Y_predictions_cov, TDataAssociationResults &results, const TAuxDataRecursiveJCBB &info, const observation_index_t curObsIdx) | 
Observations overlap functions  | |
| double | observationsOverlap (const mrpt::obs::CObservation *o1, const mrpt::obs::CObservation *o2, const mrpt::poses::CPose3D *pose_o2_wrt_o1=nullptr) | 
| Estimates the "overlap" or "matching ratio" of two observations (range [0,1]), possibly taking into account their relative positions.  More... | |
| double | observationsOverlap (const mrpt::obs::CObservation::Ptr &o1, const mrpt::obs::CObservation::Ptr &o2, const mrpt::poses::CPose3D *pose_o2_wrt_o1=nullptr) | 
| Estimates the "overlap" or "matching ratio" of two observations (range [0,1]), possibly taking into account their relative positions.  More... | |
| double | observationsOverlap (const mrpt::obs::CSensoryFrame &sf1, const mrpt::obs::CSensoryFrame &sf2, const mrpt::poses::CPose3D *pose_sf2_wrt_sf1=nullptr) | 
| Estimates the "overlap" or "matching ratio" of two set of observations (range [0,1]), possibly taking into account their relative positions.  More... | |
| double | observationsOverlap (const mrpt::obs::CSensoryFrame::Ptr &sf1, const mrpt::obs::CSensoryFrame::Ptr &sf2, const mrpt::poses::CPose3D *pose_sf2_wrt_sf1=nullptr) | 
| Estimates the "overlap" or "matching ratio" of two set of observations (range [0,1]), possibly taking into account their relative positions.  More... | |
Data association | |
| enum | TDataAssociationMethod { assocNN = 0, assocJCBB } | 
| Different algorithms for data association, used in mrpt::slam::data_association.  More... | |
| enum | TDataAssociationMetric { metricMaha = 0, metricML } | 
| Different metrics for data association, used in mrpt::slam::data_association For a comparison of both methods see paper:  More... | |
| using | observation_index_t = size_t | 
| Used in mrpt::slam::TDataAssociationResults.  More... | |
| using | prediction_index_t = size_t | 
| Used in mrpt::slam::TDataAssociationResults.  More... | |
| void | data_association_full_covariance (const mrpt::math::CMatrixDouble &Z_observations_mean, const mrpt::math::CMatrixDouble &Y_predictions_mean, const mrpt::math::CMatrixDouble &Y_predictions_cov, TDataAssociationResults &results, const TDataAssociationMethod method=assocJCBB, const TDataAssociationMetric metric=metricMaha, const double chi2quantile=0.99, const bool DAT_ASOC_USE_KDTREE=true, const std::vector< prediction_index_t > &predictions_IDs=std::vector< prediction_index_t >(), const TDataAssociationMetric compatibilityTestMetric=metricMaha, const double log_ML_compat_test_threshold=0.0) | 
| Computes the data-association between the prediction of a set of landmarks and their observations, all of them with covariance matrices - Generic version with prediction full cross-covariances.  More... | |
| void | data_association_independent_predictions (const mrpt::math::CMatrixDouble &Z_observations_mean, const mrpt::math::CMatrixDouble &Y_predictions_mean, const mrpt::math::CMatrixDouble &Y_predictions_cov, TDataAssociationResults &results, const TDataAssociationMethod method=assocJCBB, const TDataAssociationMetric metric=metricMaha, const double chi2quantile=0.99, const bool DAT_ASOC_USE_KDTREE=true, const std::vector< prediction_index_t > &predictions_IDs=std::vector< prediction_index_t >(), const TDataAssociationMetric compatibilityTestMetric=metricMaha, const double log_ML_compat_test_threshold=0.0) | 
| Computes the data-association between the prediction of a set of landmarks and their observations, all of them with covariance matrices - Generic version with NO prediction cross-covariances.  More... | |
The ICP algorithm selection, used in mrpt::slam::CICP::options mrpt_slam_grp.
| Enumerator | |
|---|---|
| icpClassic | |
| icpLevenbergMarquardt | |
| bool mrpt::slam::isCloser | ( | const double | v1, | 
| const double | v2 | ||
| ) | 
| bool mrpt::slam::isCloser< metricMaha > | ( | const double | v1, | 
| const double | v2 | ||
| ) | 
Definition at line 137 of file data_association.cpp.
| bool mrpt::slam::isCloser< metricML > | ( | const double | v1, | 
| const double | v2 | ||
| ) | 
Definition at line 143 of file data_association.cpp.
| void mrpt::slam::JCBB_recursive | ( | const mrpt::math::CMatrixDynamic< T > & | Z_observations_mean, | 
| const mrpt::math::CMatrixDynamic< T > & | Y_predictions_mean, | ||
| const mrpt::math::CMatrixDynamic< T > & | Y_predictions_cov, | ||
| TDataAssociationResults & | results, | ||
| const TAuxDataRecursiveJCBB & | info, | ||
| const observation_index_t | curObsIdx | ||
| ) | 
Definition at line 156 of file data_association.cpp.
References mrpt::slam::TAuxDataRecursiveJCBB::currentAssociation, mrpt::slam::TAuxDataRecursiveJCBB::nObservations, and results.
| double mrpt::slam::joint_pdf_metric | ( | const CMatrixDynamic< T > & | Z_observations_mean, | 
| const CMatrixDynamic< T > & | Y_predictions_mean, | ||
| const CMatrixDynamic< T > & | Y_predictions_cov, | ||
| const TAuxDataRecursiveJCBB & | info, | ||
| [[maybe_unused] ] const TDataAssociationResults & | aux_data | ||
| ) | 
Computes the joint distance metric (mahalanobis or matching likelihood) between two a set of associations.
On "currentAssociation": maps "ID_obs" -> "ID_pred" For each landmark ID in the observations (ID_obs), its association in the predictions, that is: ID_pred = associations[ID_obs]
Definition at line 64 of file data_association.cpp.
References ASSERT_, mrpt::slam::TAuxDataRecursiveJCBB::currentAssociation, mrpt::math::MatrixBase< T, CMatrixDynamic< T > >::det(), mrpt::math::extractSubmatrixSymmetricalBlocksDyn(), mrpt::math::MatrixBase< T, CMatrixDynamic< T > >::inverse_LLt(), mrpt::slam::TAuxDataRecursiveJCBB::length_O, M_2PI, metricMaha, metricML, and mrpt::math::multiply_HtCH_scalar().
| void mrpt::slam::KLF_loadBinFromParticle | ( | BINTYPE & | outBin, | 
| const TKLDParams & | opts, | ||
| const PARTICLETYPE * | currentParticleValue = nullptr,  | 
        ||
| const mrpt::math::TPose3D * | newPoseToBeInserted = nullptr  | 
        ||
| ) | 
| void mrpt::slam::KLF_loadBinFromParticle | ( | mrpt::slam::detail::TPoseBin3D & | outBin, | 
| const TKLDParams & | opts, | ||
| const CMonteCarloLocalization3D::CParticleDataContent * | currentParticleValue, | ||
| const TPose3D * | newPoseToBeInserted | ||
| ) | 
Fills out a "TPoseBin3D" variable, given a path hypotesis and (if not set to nullptr) a new pose appended at the end, using the KLD params in "options".
Definition at line 35 of file CMonteCarloLocalization3D.cpp.
References ASSERT_, mrpt::slam::TKLDParams::KLD_binSize_PHI, mrpt::slam::TKLDParams::KLD_binSize_XY, mrpt::math::TPose3D::pitch, mrpt::slam::detail::TPoseBin3D::pitch, mrpt::math::TPose3D::roll, mrpt::slam::detail::TPoseBin3D::roll, mrpt::round(), mrpt::math::TPose3D::x, mrpt::slam::detail::TPoseBin3D::x, mrpt::math::TPose3D::y, mrpt::slam::detail::TPoseBin3D::y, mrpt::math::TPose3D::yaw, mrpt::slam::detail::TPoseBin3D::yaw, mrpt::math::TPose3D::z, and mrpt::slam::detail::TPoseBin3D::z.
| void mrpt::slam::KLF_loadBinFromParticle | ( | mrpt::slam::detail::TPoseBin2D & | outBin, | 
| const TKLDParams & | opts, | ||
| const CMonteCarloLocalization2D::CParticleDataContent * | currentParticleValue, | ||
| const TPose3D * | newPoseToBeInserted | ||
| ) | 
Fills out a "TPoseBin2D" variable, given a path hypotesis and (if not set to nullptr) a new pose appended at the end, using the KLD params in "options".
Definition at line 41 of file CMonteCarloLocalization2D.cpp.
References ASSERT_, mrpt::slam::TKLDParams::KLD_binSize_PHI, mrpt::slam::TKLDParams::KLD_binSize_XY, mrpt::slam::detail::TPoseBin2D::phi, mrpt::math::TPose2D::phi, mrpt::round(), mrpt::slam::detail::TPoseBin2D::x, mrpt::math::TPose2D::x, mrpt::math::TPose3D::x, mrpt::slam::detail::TPoseBin2D::y, mrpt::math::TPose2D::y, mrpt::math::TPose3D::y, and mrpt::math::TPose3D::yaw.
| void mrpt::slam::KLF_loadBinFromParticle | ( | detail::TPoseBin2D & | outBin, | 
| const TKLDParams & | opts, | ||
| const mrpt::maps::CRBPFParticleData * | currentParticleValue, | ||
| const TPose3D * | newPoseToBeInserted | ||
| ) | 
Fills out a "TPoseBin2D" variable, given a path hypotesis and (if not set to nullptr) a new pose appended at the end, using the KLD params in "options".
Definition at line 46 of file CMultiMetricMapPDF_RBPF.cpp.
References ASSERT_, mrpt::slam::TKLDParams::KLD_binSize_PHI, mrpt::slam::TKLDParams::KLD_binSize_XY, mrpt::slam::detail::TPoseBin2D::phi, mrpt::maps::CRBPFParticleData::robotPath, mrpt::round(), mrpt::slam::detail::TPoseBin2D::x, mrpt::math::TPose3D::x, mrpt::slam::detail::TPoseBin2D::y, mrpt::math::TPose3D::y, and mrpt::math::TPose3D::yaw.
| void mrpt::slam::KLF_loadBinFromParticle | ( | detail::TPathBin2D & | outBin, | 
| const TKLDParams & | opts, | ||
| const mrpt::maps::CRBPFParticleData * | currentParticleValue, | ||
| const TPose3D * | newPoseToBeInserted | ||
| ) | 
Fills out a "TPathBin2D" variable, given a path hypotesis and (if not set to nullptr) a new pose appended at the end, using the KLD params in "options".
Definition at line 73 of file CMultiMetricMapPDF_RBPF.cpp.
References mrpt::slam::detail::TPathBin2D::bins, mrpt::slam::TKLDParams::KLD_binSize_PHI, mrpt::slam::TKLDParams::KLD_binSize_XY, mrpt::maps::CRBPFParticleData::robotPath, mrpt::round(), mrpt::math::TPose3D::x, mrpt::math::TPose3D::y, and mrpt::math::TPose3D::yaw.
| 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 |