92         std::vector<mrpt::math::TPoint3D>& out_landmarksPositions,
    93         std::map<unsigned int, mrpt::maps::CLandmark::TLandmarkID>&
   112         std::vector<mrpt::math::TPoint3D>& out_landmarksPositions,
   113         std::map<unsigned int, mrpt::maps::CLandmark::TLandmarkID>&
   121             q, out_landmarksPositions, out_landmarkIDs, out_fullState,
   172             std::ostream& out) 
const override;  
   277         std::vector<std::vector<uint32_t>>& landmarksMembership) 
const;
   284         size_t K, std::vector<std::vector<uint32_t>>& landmarksMembership);
   291         const std::vector<std::vector<uint32_t>>& landmarksMembership) 
const;
   339         bool& out_skipPrediction) 
const override;
   382         const std::vector<size_t>& in_lm_indices_in_S,
   386         const std::vector<size_t>& idx_landmarks_to_predict,
   399         const size_t& idx_landmark_to_predict, 
KFMatrix_OxV& Hx,
   432         std::vector<size_t>& out_LM_indices_to_predict) 
const override;
   469         const size_t in_obsIdx, 
const size_t in_idxNewFeat) 
override;
 
void getCurrentRobotPose(mrpt::poses::CPose3DQuatPDFGaussian &out_robotPose) const
Returns the mean & the 7x7 covariance matrix of the robot 6D pose (with rotation as a quaternion)...
 
mrpt::math::CMatrixDynamic< kftype > Y_pred_means
 
TOptions options
Algorithm parameters. 
 
An implementation of EKF-based SLAM with range-bearing sensors, odometry, a full 6D robot pose...
 
void reset()
Reset the state of the SLAM filter: The map is emptied and the robot put back to (0,0,0). 
 
mrpt::poses::CPose3DQuat getIncrementFromOdometry() const
Return the last odometry, as a pose increment. 
 
This is a virtual base class for sets of options than can be loaded from and/or saved to configuratio...
 
void getLastPartitionLandmarks(std::vector< std::vector< uint32_t >> &landmarksMembership) const
Return the partitioning of the landmarks in clusters accoring to the last partition. 
 
mrpt::math::CVectorFixed< double, ACT_SIZE > KFArray_ACT
 
mrpt::math::CMatrixFixed< double, VEH_SIZE, VEH_SIZE > KFMatrix_VxV
 
bool force_ignore_odometry
Whether to ignore the input odometry and behave as if there was no odometry at all (default: false) ...
 
This class stores a sequence of <Probabilistic Pose,SensoryFrame> pairs, thus a "metric map" can be t...
 
void reconsiderPartitionsNow()
The partitioning of the entire map is recomputed again. 
 
GLdouble GLdouble GLdouble GLdouble q
 
void processActionObservation(mrpt::obs::CActionCollection::Ptr &action, mrpt::obs::CSensoryFrame::Ptr &SF)
Process one new action and observations to update the map and robot pose estimate. 
 
std::map< size_t, size_t > newly_inserted_landmarks
Map from the 0-based index within the last observation and the landmark 0-based index in the map (the...
 
void OnObservationModel(const std::vector< size_t > &idx_landmarks_to_predict, vector_KFArray_OBS &out_predictions) const override
 
void saveMapAndPath2DRepresentationAsMATLABFile(const std::string &fil, float stdCount=3.0f, const std::string &styleLandmarks=std::string("b"), const std::string &stylePath=std::string("r"), const std::string &styleRobot=std::string("r")) const
Save the current state of the filter (robot pose & map) to a MATLAB script which displays all the ele...
 
void OnTransitionModel(const KFArray_ACT &in_u, KFArray_VEH &inout_x, bool &out_skipPrediction) const override
Implements the transition model . 
 
mrpt::math::CVectorFixed< double, VEH_SIZE > KFArray_VEH
 
void OnNormalizeStateVector() override
This method is called after the prediction and after the update, to give the user an opportunity to n...
 
mrpt::poses::CPose3DQuat getCurrentRobotPoseMean() const
Get the current robot pose mean, as a 3D+quaternion pose. 
 
mrpt::math::CMatrixFixed< double, FEAT_SIZE, OBS_SIZE > KFMatrix_FxO
 
TDataAssocInfo m_last_data_association
Last data association. 
 
float std_odo_z_additional
Additional std. 
 
mrpt::containers::bimap< mrpt::maps::CLandmark::TLandmarkID, unsigned int > m_IDs
The mapping between landmark IDs and indexes in the Pkk cov. 
 
Declares a class that represents a Probability Density function (PDF) of a 3D pose using a quaternion...
 
Configuration parameters. 
 
CIncrementalMapPartitioner::TOptions * mapPartitionOptions()
Provides access to the parameters of the map partitioning algorithm. 
 
This class allows loading and storing values and vectors of different types from a configuration text...
 
mrpt::math::CMatrixDynamic< double > KFMatrix
 
void OnGetObservationsAndDataAssociation(vector_KFArray_OBS &out_z, std::vector< int > &out_data_association, const vector_KFArray_OBS &in_all_predictions, const KFMatrix &in_S, const std::vector< size_t > &in_lm_indices_in_S, const KFMatrix_OxO &in_R) override
This is called between the KF prediction step and the update step, and the application must return th...
 
TDataAssociationMetric data_assoc_metric
 
int partitioningMethod
Applicable only if "doPartitioningExperiment=true". 
 
TDataAssociationMetric
Different metrics for data association, used in mrpt::slam::data_association For a comparison of both...
 
TOptions()
Default values. 
 
void getCurrentRobotPose(mrpt::poses::CPose3DPDFGaussian &out_robotPose) const
Returns the mean & the 6x6 covariance matrix of the robot 6D pose (with rotation as 3 angles)...
 
Virtual base for Kalman Filter (EKF,IEKF,UKF) implementations. 
 
CIncrementalMapPartitioner mapPartitioner
Used for map partitioning experiments. 
 
TDataAssociationMetric data_assoc_IC_metric
Whether to use mahalanobis (->chi2 criterion) vs. 
 
double computeOffDiagonalBlocksApproximationError(const std::vector< std::vector< uint32_t >> &landmarksMembership) const
Computes the ratio of the missing information matrix elements which are ignored under a certain parti...
 
A class used to store a 3D pose as a translation (x,y,z) and a quaternion (qr,qx,qy,qz). 
 
mrpt::maps::CSimpleMap m_SFs
The sequence of all the observations and the robot path (kept for debugging, statistics,etc) 
 
GLsizei const GLchar ** string
 
double data_assoc_IC_ml_threshold
Only if data_assoc_IC_metric==ML, the log-ML threshold (Default=0.0) 
 
std::vector< std::vector< uint32_t > > m_lastPartitionSet
 
mrpt::math::CMatrixFixed< double, FEAT_SIZE, VEH_SIZE > KFMatrix_FxV
 
mrpt::math::CVectorFixed< double, FEAT_SIZE > KFArray_FEAT
 
void OnGetAction(KFArray_ACT &out_u) const override
Must return the action vector u. 
 
void loadOptions(const mrpt::config::CConfigFileBase &ini)
Load options from a ini-like file/text. 
 
void OnSubstractObservationVectors(KFArray_OBS &A, const KFArray_OBS &B) const override
Computes A=A-B, which may need to be re-implemented depending on the topology of the individual scala...
 
void OnGetObservationNoise(KFMatrix_OxO &out_R) const override
Return the observation NOISE covariance matrix, that is, the model of the Gaussian additive noise of ...
 
void getCurrentState(mrpt::poses::CPose3DPDFGaussian &out_robotPose, std::vector< mrpt::math::TPoint3D > &out_landmarksPositions, std::map< unsigned int, mrpt::maps::CLandmark::TLandmarkID > &out_landmarkIDs, mrpt::math::CVectorDouble &out_fullState, mrpt::math::CMatrixDouble &out_fullCovariance) const
Returns the complete mean and cov. 
 
std::vector< KFArray_OBS > vector_KFArray_OBS
 
std::vector< size_t > predictions_IDs
 
Finds partitions in metric maps based on N-cut graph partition theory. 
 
mrpt::obs::CSensoryFrame::Ptr m_SF
Set up by processActionObservation. 
 
void getCurrentState(mrpt::poses::CPose3DQuatPDFGaussian &out_robotPose, std::vector< mrpt::math::TPoint3D > &out_landmarksPositions, std::map< unsigned int, mrpt::maps::CLandmark::TLandmarkID > &out_landmarkIDs, mrpt::math::CVectorDouble &out_fullState, mrpt::math::CMatrixDouble &out_fullCovariance) const
Returns the complete mean and cov. 
 
mrpt::slam::CRangeBearingKFSLAM::TOptions options
 
void loadFromConfigFile(const mrpt::config::CConfigFileBase &source, const std::string §ion) override
This method load the options from a ".ini"-like file or memory-stored string list. 
 
float quantiles_3D_representation
Default = 3. 
 
void OnTransitionNoise(KFMatrix_VxV &out_Q) const override
Implements the transition noise covariance . 
 
void getLastPartitionLandmarksAsIfFixedSubmaps(size_t K, std::vector< std::vector< uint32_t >> &landmarksMembership)
For testing only: returns the partitioning as "getLastPartitionLandmarks" but as if a fixed-size subm...
 
void dumpToTextStream(std::ostream &out) const override
This method should clearly display all the contents of the structure in textual form, sending it to a std::ostream. 
 
void getAs3DObject(mrpt::opengl::CSetOfObjects::Ptr &outObj) const
Returns a 3D representation of the landmarks in the map and the robot 3D position according to the cu...
 
GLsizei GLsizei GLchar * source
 
const TDataAssocInfo & getLastDataAssociation() const
Returns a read-only reference to the information on the last data-association. 
 
Declares a class that represents a Probability Density function (PDF) of a 3D pose ...
 
void OnNewLandmarkAddedToMap(const size_t in_obsIdx, const size_t in_idxNewFeat) override
If applicable to the given problem, do here any special handling of adding a new landmark to the map...
 
Information for data-association: 
 
mrpt::math::CMatrixDynamic< kftype > Y_pred_covs
 
CRangeBearingKFSLAM()
Constructor. 
 
bool create_simplemap
Whether to fill m_SFs (default=false) 
 
TDataAssociationMethod data_assoc_method
 
bool doPartitioningExperiment
If set to true (default=false), map will be partitioned using the method stated by partitioningMethod...
 
TDataAssociationResults results
 
void OnObservationJacobians(const size_t &idx_landmark_to_predict, KFMatrix_OxV &Hx, KFMatrix_OxF &Hy) const override
Implements the observation Jacobians  and (when applicable) . 
 
The results from mrpt::slam::data_association. 
 
The options for the algorithm. 
 
mrpt::math::CVectorFixed< double, OBS_SIZE > KFArray_OBS
 
void OnTransitionJacobian(KFMatrix_VxV &out_F) const override
Implements the transition Jacobian . 
 
mrpt::obs::CActionCollection::Ptr m_action
Set up by processActionObservation. 
 
TDataAssociationMethod
Different algorithms for data association, used in mrpt::slam::data_association. 
 
~CRangeBearingKFSLAM() override
Destructor: 
 
mrpt::math::CMatrixFixed< double, OBS_SIZE, VEH_SIZE > KFMatrix_OxV
 
float std_sensor_range
The std. 
 
double data_assoc_IC_chi2_thres
Threshold in [0,1] for the chi2square test for individual compatibility between predictions and obser...
 
void getLastPartition(std::vector< std::vector< uint32_t >> &parts)
Return the last partition of the sequence of sensoryframes (it is NOT a partition of the map!!) Only ...
 
mrpt::math::CMatrixFixed< double, OBS_SIZE, OBS_SIZE > KFMatrix_OxO
 
void OnPreComputingPredictions(const vector_KFArray_OBS &in_all_prediction_means, std::vector< size_t > &out_LM_indices_to_predict) const override
This will be called before OnGetObservationsAndDataAssociation to allow the application to reduce the...
 
mrpt::math::CMatrixFixed< double, OBS_SIZE, FEAT_SIZE > KFMatrix_OxF
 
mrpt::math::CVectorFloat stds_Q_no_odo
A 7-length vector with the std. 
 
void OnInverseObservationModel(const KFArray_OBS &in_z, KFArray_FEAT &out_yn, KFMatrix_FxV &out_dyn_dxv, KFMatrix_FxO &out_dyn_dhn) const override
If applicable to the given problem, this method implements the inverse observation model needed to ex...