An implementation of EKF-based SLAM with range-bearing sensors, odometry, a full 6D robot pose, and 3D landmarks.
The main method is "processActionObservation" which processes pairs of action/observation. The state vector comprises: 3D robot position, a quaternion for its attitude, and the 3D landmarks in the map.
The following Wiki page describes an front-end application based on this class: http://www.mrpt.org/Application:kf-slam
For the theory behind this implementation, see the technical report in: http://www.mrpt.org/6D-SLAM
Definition at line 81 of file CRangeBearingKFSLAM.h.
#include <mrpt/slam/CRangeBearingKFSLAM.h>
Classes | |
struct | TDataAssocInfo |
Information for data-association: More... | |
struct | TOptions |
The options for the algorithm. More... | |
Public Types | |
typedef double | kftype |
The numeric type used in the Kalman Filter (default=double) More... | |
typedef CKalmanFilterCapable< VEH_SIZE, OBS_SIZE, FEAT_SIZE, ACT_SIZE, double > | KFCLASS |
My class, in a shorter name! More... | |
typedef mrpt::dynamicsize_vector< double > | KFVector |
typedef CMatrixTemplateNumeric< double > | KFMatrix |
typedef CMatrixFixedNumeric< double, VEH_SIZE, VEH_SIZE > | KFMatrix_VxV |
typedef CMatrixFixedNumeric< double, OBS_SIZE, OBS_SIZE > | KFMatrix_OxO |
typedef CMatrixFixedNumeric< double, FEAT_SIZE, FEAT_SIZE > | KFMatrix_FxF |
typedef CMatrixFixedNumeric< double, ACT_SIZE, ACT_SIZE > | KFMatrix_AxA |
typedef CMatrixFixedNumeric< double, VEH_SIZE, OBS_SIZE > | KFMatrix_VxO |
typedef CMatrixFixedNumeric< double, VEH_SIZE, FEAT_SIZE > | KFMatrix_VxF |
typedef CMatrixFixedNumeric< double, FEAT_SIZE, VEH_SIZE > | KFMatrix_FxV |
typedef CMatrixFixedNumeric< double, FEAT_SIZE, OBS_SIZE > | KFMatrix_FxO |
typedef CMatrixFixedNumeric< double, OBS_SIZE, FEAT_SIZE > | KFMatrix_OxF |
typedef CMatrixFixedNumeric< double, OBS_SIZE, VEH_SIZE > | KFMatrix_OxV |
typedef CArrayNumeric< double, VEH_SIZE > | KFArray_VEH |
typedef CArrayNumeric< double, ACT_SIZE > | KFArray_ACT |
typedef CArrayNumeric< double, OBS_SIZE > | KFArray_OBS |
typedef mrpt::aligned_containers< KFArray_OBS >::vector_t | vector_KFArray_OBS |
typedef CArrayNumeric< double, FEAT_SIZE > | KFArray_FEAT |
Public Member Functions | |
CRangeBearingKFSLAM () | |
Constructor. More... | |
virtual | ~CRangeBearingKFSLAM () |
Destructor: More... | |
void | reset () |
Reset the state of the SLAM filter: The map is emptied and the robot put back to (0,0,0). More... | |
void | processActionObservation (CActionCollectionPtr &action, CSensoryFramePtr &SF) |
Process one new action and observations to update the map and robot pose estimate. More... | |
void | getCurrentState (CPose3DQuatPDFGaussian &out_robotPose, std::vector< CPoint3D > &out_landmarksPositions, std::map< unsigned int, CLandmark::TLandmarkID > &out_landmarkIDs, CVectorDouble &out_fullState, CMatrixDouble &out_fullCovariance) const |
Returns the complete mean and cov. More... | |
void | getCurrentState (CPose3DPDFGaussian &out_robotPose, std::vector< CPoint3D > &out_landmarksPositions, std::map< unsigned int, CLandmark::TLandmarkID > &out_landmarkIDs, CVectorDouble &out_fullState, CMatrixDouble &out_fullCovariance) const |
Returns the complete mean and cov. More... | |
void | getCurrentRobotPose (CPose3DQuatPDFGaussian &out_robotPose) const |
Returns the mean & the 7x7 covariance matrix of the robot 6D pose (with rotation as a quaternion). More... | |
mrpt::poses::CPose3DQuat | getCurrentRobotPoseMean () const |
Get the current robot pose mean, as a 3D+quaternion pose. More... | |
void | getCurrentRobotPose (CPose3DPDFGaussian &out_robotPose) const |
Returns the mean & the 6x6 covariance matrix of the robot 6D pose (with rotation as 3 angles). More... | |
void | getAs3DObject (mrpt::opengl::CSetOfObjectsPtr &outObj) const |
Returns a 3D representation of the landmarks in the map and the robot 3D position according to the current filter state. More... | |
void | loadOptions (const mrpt::utils::CConfigFileBase &ini) |
Load options from a ini-like file/text. More... | |
const TDataAssocInfo & | getLastDataAssociation () const |
Returns a read-only reference to the information on the last data-association. More... | |
void | getLastPartition (std::vector< vector_uint > &parts) |
Return the last partition of the sequence of sensoryframes (it is NOT a partition of the map!!) Only if options.doPartitioningExperiment = true. More... | |
void | getLastPartitionLandmarks (std::vector< vector_uint > &landmarksMembership) const |
Return the partitioning of the landmarks in clusters accoring to the last partition. More... | |
void | getLastPartitionLandmarksAsIfFixedSubmaps (size_t K, std::vector< vector_uint > &landmarksMembership) |
For testing only: returns the partitioning as "getLastPartitionLandmarks" but as if a fixed-size submaps (size K) were have been used. More... | |
double | computeOffDiagonalBlocksApproximationError (const std::vector< vector_uint > &landmarksMembership) const |
Computes the ratio of the missing information matrix elements which are ignored under a certain partitioning of the landmarks. More... | |
void | reconsiderPartitionsNow () |
The partitioning of the entire map is recomputed again. More... | |
CIncrementalMapPartitioner::TOptions * | mapPartitionOptions () |
Provides access to the parameters of the map partitioning algorithm. More... | |
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 elements in 2D. More... | |
size_t | getNumberOfLandmarksInTheMap () const |
bool | isMapEmpty () const |
size_t | getStateVectorLength () const |
void | getLandmarkMean (size_t idx, KFArray_FEAT &feat) const |
Returns the mean of the estimated value of the idx'th landmark (not applicable to non-SLAM problems). More... | |
void | getLandmarkCov (size_t idx, KFMatrix_FxF &feat_cov) const |
Returns the covariance of the idx'th landmark (not applicable to non-SLAM problems). More... | |
mrpt::utils::CTimeLogger & | getProfiler () |
Static Public Member Functions | |
static size_t | get_vehicle_size () |
static size_t | get_observation_size () |
static size_t | get_feature_size () |
static size_t | get_action_size () |
static void | printf_debug (const char *frmt,...) |
Sends a formated text to "debugOut" if not NULL, or to cout otherwise. More... | |
Public Attributes | |
mrpt::slam::CRangeBearingKFSLAM::TOptions | options |
TKF_options | KF_options |
Generic options for the Kalman Filter algorithm itself. More... | |
Protected Member Functions | |
mrpt::poses::CPose3DQuat | getIncrementFromOdometry () const |
Return the last odometry, as a pose increment. More... | |
void | runOneKalmanIteration () |
The main entry point, executes one complete step: prediction + update. More... | |
Virtual methods for Kalman Filter implementation | |
void | OnGetAction (KFArray_ACT &out_u) const |
Must return the action vector u. More... | |
void | OnTransitionModel (const KFArray_ACT &in_u, KFArray_VEH &inout_x, bool &out_skipPrediction) const |
Implements the transition model ![]() | |
void | OnTransitionJacobian (KFMatrix_VxV &out_F) const |
Implements the transition Jacobian ![]() | |
void | OnTransitionNoise (KFMatrix_VxV &out_Q) const |
Implements the transition noise covariance ![]() | |
void | OnGetObservationsAndDataAssociation (vector_KFArray_OBS &out_z, vector_int &out_data_association, const vector_KFArray_OBS &in_all_predictions, const KFMatrix &in_S, const vector_size_t &in_lm_indices_in_S, const KFMatrix_OxO &in_R) |
This is called between the KF prediction step and the update step, and the application must return the observations and, when applicable, the data association between these observations and the current map. More... | |
void | OnObservationModel (const vector_size_t &idx_landmarks_to_predict, vector_KFArray_OBS &out_predictions) const |
Implements the observation prediction ![]() | |
void | OnObservationJacobians (const size_t &idx_landmark_to_predict, KFMatrix_OxV &Hx, KFMatrix_OxF &Hy) const |
Implements the observation Jacobians ![]() ![]() | |
void | OnSubstractObservationVectors (KFArray_OBS &A, const KFArray_OBS &B) const |
Computes A=A-B, which may need to be re-implemented depending on the topology of the individual scalar components (eg, angles). More... | |
void | OnGetObservationNoise (KFMatrix_OxO &out_R) const |
Return the observation NOISE covariance matrix, that is, the model of the Gaussian additive noise of the sensor. More... | |
void | OnPreComputingPredictions (const vector_KFArray_OBS &in_all_prediction_means, vector_size_t &out_LM_indices_to_predict) const |
This will be called before OnGetObservationsAndDataAssociation to allow the application to reduce the number of covariance landmark predictions to be made. More... | |
void | OnInverseObservationModel (const KFArray_OBS &in_z, KFArray_FEAT &out_yn, KFMatrix_FxV &out_dyn_dxv, KFMatrix_FxO &out_dyn_dhn) const |
If applicable to the given problem, this method implements the inverse observation model needed to extend the "map" with a new "element". More... | |
void | OnNewLandmarkAddedToMap (const size_t in_obsIdx, const size_t in_idxNewFeat) |
If applicable to the given problem, do here any special handling of adding a new landmark to the map. More... | |
void | OnNormalizeStateVector () |
This method is called after the prediction and after the update, to give the user an opportunity to normalize the state vector (eg, keep angles within -pi,pi range) if the application requires it. More... | |
Virtual methods for Kalman Filter implementation | |
virtual void | OnTransitionJacobianNumericGetIncrements (KFArray_VEH &out_increments) const |
Only called if using a numeric approximation of the transition Jacobian, this method must return the increments in each dimension of the vehicle state vector while estimating the Jacobian. More... | |
virtual void | OnObservationJacobiansNumericGetIncrements (KFArray_VEH &out_veh_increments, KFArray_FEAT &out_feat_increments) const |
Only called if using a numeric approximation of the observation Jacobians, this method must return the increments in each dimension of the vehicle state vector while estimating the Jacobian. More... | |
virtual void | OnInverseObservationModel (const KFArray_OBS &in_z, KFArray_FEAT &out_yn, KFMatrix_FxV &out_dyn_dxv, KFMatrix_FxO &out_dyn_dhn, KFMatrix_FxF &out_dyn_dhn_R_dyn_dhnT, bool &out_use_dyn_dhn_jacobian) const |
If applicable to the given problem, this method implements the inverse observation model needed to extend the "map" with a new "element". More... | |
virtual void | OnPostIteration () |
This method is called after finishing one KF iteration and before returning from runOneKalmanIteration(). More... | |
Protected Attributes | |
CActionCollectionPtr | m_action |
Set up by processActionObservation. More... | |
CSensoryFramePtr | m_SF |
Set up by processActionObservation. More... | |
mrpt::utils::bimap< CLandmark::TLandmarkID, unsigned int > | m_IDs |
The mapping between landmark IDs and indexes in the Pkk cov. More... | |
CIncrementalMapPartitioner | mapPartitioner |
Used for map partitioning experiments. More... | |
CSimpleMap | m_SFs |
The sequence of all the observations and the robot path (kept for debugging, statistics,etc) More... | |
std::vector< vector_uint > | m_lastPartitionSet |
TDataAssocInfo | m_last_data_association |
Last data association. More... | |
mrpt::utils::CTimeLogger | m_timLogger |
Kalman filter state | |
KFVector | m_xkk |
The system state vector. More... | |
KFMatrix | m_pkk |
The system full covariance matrix. More... | |
|
inherited |
Definition at line 213 of file CKalmanFilterCapable.h.
|
inherited |
Definition at line 216 of file CKalmanFilterCapable.h.
|
inherited |
Definition at line 214 of file CKalmanFilterCapable.h.
|
inherited |
Definition at line 212 of file CKalmanFilterCapable.h.
|
inherited |
My class, in a shorter name!
Definition at line 192 of file CKalmanFilterCapable.h.
|
inherited |
Definition at line 196 of file CKalmanFilterCapable.h.
|
inherited |
Definition at line 201 of file CKalmanFilterCapable.h.
|
inherited |
Definition at line 200 of file CKalmanFilterCapable.h.
|
inherited |
Definition at line 207 of file CKalmanFilterCapable.h.
|
inherited |
Definition at line 206 of file CKalmanFilterCapable.h.
|
inherited |
Definition at line 209 of file CKalmanFilterCapable.h.
|
inherited |
Definition at line 199 of file CKalmanFilterCapable.h.
|
inherited |
Definition at line 210 of file CKalmanFilterCapable.h.
|
inherited |
Definition at line 204 of file CKalmanFilterCapable.h.
|
inherited |
Definition at line 203 of file CKalmanFilterCapable.h.
|
inherited |
Definition at line 198 of file CKalmanFilterCapable.h.
|
inherited |
The numeric type used in the Kalman Filter (default=double)
Definition at line 191 of file CKalmanFilterCapable.h.
|
inherited |
Definition at line 195 of file CKalmanFilterCapable.h.
|
inherited |
Definition at line 215 of file CKalmanFilterCapable.h.
mrpt::slam::CRangeBearingKFSLAM::CRangeBearingKFSLAM | ( | ) |
Constructor.
|
virtual |
Destructor:
double mrpt::slam::CRangeBearingKFSLAM::computeOffDiagonalBlocksApproximationError | ( | const std::vector< vector_uint > & | landmarksMembership | ) | const |
Computes the ratio of the missing information matrix elements which are ignored under a certain partitioning of the landmarks.
|
inlinestaticinherited |
Definition at line 186 of file CKalmanFilterCapable.h.
|
inlinestaticinherited |
Definition at line 185 of file CKalmanFilterCapable.h.
|
inlinestaticinherited |
Definition at line 184 of file CKalmanFilterCapable.h.
|
inlinestaticinherited |
Definition at line 183 of file CKalmanFilterCapable.h.
void mrpt::slam::CRangeBearingKFSLAM::getAs3DObject | ( | mrpt::opengl::CSetOfObjectsPtr & | outObj | ) | const |
Returns a 3D representation of the landmarks in the map and the robot 3D position according to the current filter state.
out_objects |
void mrpt::slam::CRangeBearingKFSLAM::getCurrentRobotPose | ( | CPose3DQuatPDFGaussian & | out_robotPose | ) | const |
Returns the mean & the 7x7 covariance matrix of the robot 6D pose (with rotation as a quaternion).
|
inline |
Returns the mean & the 6x6 covariance matrix of the robot 6D pose (with rotation as 3 angles).
Definition at line 154 of file CRangeBearingKFSLAM.h.
References mrpt::math::UNINITIALIZED_QUATERNION.
mrpt::poses::CPose3DQuat mrpt::slam::CRangeBearingKFSLAM::getCurrentRobotPoseMean | ( | ) | const |
Get the current robot pose mean, as a 3D+quaternion pose.
void mrpt::slam::CRangeBearingKFSLAM::getCurrentState | ( | CPose3DQuatPDFGaussian & | out_robotPose, |
std::vector< CPoint3D > & | out_landmarksPositions, | ||
std::map< unsigned int, CLandmark::TLandmarkID > & | out_landmarkIDs, | ||
CVectorDouble & | out_fullState, | ||
CMatrixDouble & | out_fullCovariance | ||
) | const |
Returns the complete mean and cov.
out_robotPose | The mean and the 7x7 covariance matrix of the robot 6D pose |
out_landmarksPositions | One entry for each of the M landmark positions (3D). |
out_landmarkIDs | Each element[index] (for indices of out_landmarksPositions) gives the corresponding landmark ID. |
out_fullState | The complete state vector (7+3M). |
out_fullCovariance | The full (7+3M)x(7+3M) covariance matrix of the filter. |
|
inline |
Returns the complete mean and cov.
out_robotPose | The mean and the 7x7 covariance matrix of the robot 6D pose |
out_landmarksPositions | One entry for each of the M landmark positions (3D). |
out_landmarkIDs | Each element[index] (for indices of out_landmarksPositions) gives the corresponding landmark ID. |
out_fullState | The complete state vector (7+3M). |
out_fullCovariance | The full (7+3M)x(7+3M) covariance matrix of the filter. |
Definition at line 128 of file CRangeBearingKFSLAM.h.
References mrpt::math::UNINITIALIZED_QUATERNION.
|
protected |
Return the last odometry, as a pose increment.
|
inlineinherited |
Returns the covariance of the idx'th landmark (not applicable to non-SLAM problems).
std::exception | On idx>= getNumberOfLandmarksInTheMap() |
Definition at line 230 of file CKalmanFilterCapable.h.
|
inlineinherited |
Returns the mean of the estimated value of the idx'th landmark (not applicable to non-SLAM problems).
std::exception | On idx>= getNumberOfLandmarksInTheMap() |
Definition at line 223 of file CKalmanFilterCapable.h.
References ASSERT_, and mrpt::system::os::memcpy().
|
inline |
Returns a read-only reference to the information on the last data-association.
Definition at line 256 of file CRangeBearingKFSLAM.h.
|
inline |
Return the last partition of the sequence of sensoryframes (it is NOT a partition of the map!!) Only if options.doPartitioningExperiment = true.
Definition at line 265 of file CRangeBearingKFSLAM.h.
void mrpt::slam::CRangeBearingKFSLAM::getLastPartitionLandmarks | ( | std::vector< vector_uint > & | landmarksMembership | ) | const |
Return the partitioning of the landmarks in clusters accoring to the last partition.
Note that the same landmark may appear in different clusters (the partition is not in the space of landmarks) Only if options.doPartitioningExperiment = true
landmarksMembership | The i'th element of this vector is the set of clusters to which the i'th landmark in the map belongs to (landmark index != landmark ID !!). |
void mrpt::slam::CRangeBearingKFSLAM::getLastPartitionLandmarksAsIfFixedSubmaps | ( | size_t | K, |
std::vector< vector_uint > & | landmarksMembership | ||
) |
For testing only: returns the partitioning as "getLastPartitionLandmarks" but as if a fixed-size submaps (size K) were have been used.
|
inlineinherited |
Definition at line 187 of file CKalmanFilterCapable.h.
References mrpt::bayes::detail::getNumberOfLandmarksInMap().
|
inlineinherited |
Definition at line 464 of file CKalmanFilterCapable.h.
|
inlineinherited |
Definition at line 218 of file CKalmanFilterCapable.h.
|
inlineinherited |
Definition at line 188 of file CKalmanFilterCapable.h.
References mrpt::bayes::detail::isMapEmpty().
void mrpt::slam::CRangeBearingKFSLAM::loadOptions | ( | const mrpt::utils::CConfigFileBase & | ini | ) |
Load options from a ini-like file/text.
|
inline |
Provides access to the parameters of the map partitioning algorithm.
Definition at line 300 of file CRangeBearingKFSLAM.h.
|
protectedvirtual |
Must return the action vector u.
out_u | The action vector which will be passed to OnTransitionModel |
Implements mrpt::bayes::CKalmanFilterCapable< 7, 3, 3, 7 >.
|
protectedvirtual |
Return the observation NOISE covariance matrix, that is, the model of the Gaussian additive noise of the sensor.
out_R | The noise covariance matrix. It might be non diagonal, but it'll usually be. |
Implements mrpt::bayes::CKalmanFilterCapable< 7, 3, 3, 7 >.
|
protectedvirtual |
This is called between the KF prediction step and the update step, and the application must return the observations and, when applicable, the data association between these observations and the current map.
out_z | N vectors, each for one "observation" of length OBS_SIZE, N being the number of "observations": how many observed landmarks for a map, or just one if not applicable. |
out_data_association | An empty vector or, where applicable, a vector where the i'th element corresponds to the position of the observation in the i'th row of out_z within the system state vector (in the range [0,getNumberOfLandmarksInTheMap()-1]), or -1 if it is a new map element and we want to insert it at the end of this KF iteration. |
in_S | The full covariance matrix of the observation predictions (i.e. the "innovation covariance matrix"). This is a M·O x M·O matrix with M=length of "in_lm_indices_in_S". |
in_lm_indices_in_S | The indices of the map landmarks (range [0,getNumberOfLandmarksInTheMap()-1]) that can be found in the matrix in_S. |
This method will be called just once for each complete KF iteration.
Implements mrpt::bayes::CKalmanFilterCapable< 7, 3, 3, 7 >.
|
inlineprotectedvirtualinherited |
If applicable to the given problem, this method implements the inverse observation model needed to extend the "map" with a new "element".
The uncertainty in the new map feature comes from two parts: one from the vehicle uncertainty (through the out_dyn_dxv Jacobian), and another from the uncertainty in the observation itself. By default, out_use_dyn_dhn_jacobian=true on call, and if it's left at "true", the base KalmanFilter class will compute the uncertainty of the landmark relative position from out_dyn_dhn. Only in some problems (e.g. MonoSLAM), it'll be needed for the application to directly return the covariance matrix out_dyn_dhn_R_dyn_dhnT, which is the equivalent to:
.
but may be computed from additional terms, or whatever needed by the user.
in_z | The observation vector whose inverse sensor model is to be computed. This is actually one of the vector<> returned by OnGetObservationsAndDataAssociation(). |
out_yn | The F-length vector with the inverse observation model ![]() |
out_dyn_dxv | The ![]() ![]() |
out_dyn_dhn | The ![]() ![]() |
out_dyn_dhn_R_dyn_dhnT | See the discussion above. |
Definition at line 417 of file CKalmanFilterCapable.h.
References MRPT_END, and MRPT_START.
|
protectedvirtual |
If applicable to the given problem, this method implements the inverse observation model needed to extend the "map" with a new "element".
in_z | The observation vector whose inverse sensor model is to be computed. This is actually one of the vector<> returned by OnGetObservations(). |
out_yn | The F-length vector with the inverse observation model ![]() |
out_dyn_dxv | The ![]() ![]() |
out_dyn_dhn | The ![]() ![]() |
Reimplemented from mrpt::bayes::CKalmanFilterCapable< 7, 3, 3, 7 >.
|
protectedvirtual |
If applicable to the given problem, do here any special handling of adding a new landmark to the map.
in_obsIndex | The index of the observation whose inverse sensor is to be computed. It corresponds to the row in in_z where the observation can be found. |
in_idxNewFeat | The index that this new feature will have in the state vector (0:just after the vehicle state, 1: after that,...). Save this number so data association can be done according to these indices. |
Reimplemented from mrpt::bayes::CKalmanFilterCapable< 7, 3, 3, 7 >.
|
protectedvirtual |
This method is called after the prediction and after the update, to give the user an opportunity to normalize the state vector (eg, keep angles within -pi,pi range) if the application requires it.
Reimplemented from mrpt::bayes::CKalmanFilterCapable< 7, 3, 3, 7 >.
|
protectedvirtual |
Implements the observation Jacobians and (when applicable)
.
idx_landmark_to_predict | The index of the landmark in the map whose prediction is expected as output. For non SLAM-like problems, this will be zero and the expected output is for the whole state vector. |
Hx | The output Jacobian ![]() |
Hy | The output Jacobian ![]() |
Reimplemented from mrpt::bayes::CKalmanFilterCapable< 7, 3, 3, 7 >.
|
inlineprotectedvirtualinherited |
Only called if using a numeric approximation of the observation Jacobians, this method must return the increments in each dimension of the vehicle state vector while estimating the Jacobian.
Definition at line 356 of file CKalmanFilterCapable.h.
|
protectedvirtual |
Implements the observation prediction .
idx_landmark_to_predict | The indices of the landmarks in the map whose predictions are expected as output. For non SLAM-like problems, this input value is undefined and the application should just generate one observation for the given problem. |
out_predictions | The predicted observations. |
Implements mrpt::bayes::CKalmanFilterCapable< 7, 3, 3, 7 >.
|
inlineprotectedvirtualinherited |
This method is called after finishing one KF iteration and before returning from runOneKalmanIteration().
Definition at line 453 of file CKalmanFilterCapable.h.
|
protectedvirtual |
This will be called before OnGetObservationsAndDataAssociation to allow the application to reduce the number of covariance landmark predictions to be made.
For example, features which are known to be "out of sight" shouldn't be added to the output list to speed up the calculations.
in_all_prediction_means | The mean of each landmark predictions; the computation or not of the corresponding covariances is what we're trying to determined with this method. |
out_LM_indices_to_predict | The list of landmark indices in the map [0,getNumberOfLandmarksInTheMap()-1] that should be predicted. |
Reimplemented from mrpt::bayes::CKalmanFilterCapable< 7, 3, 3, 7 >.
|
protectedvirtual |
Computes A=A-B, which may need to be re-implemented depending on the topology of the individual scalar components (eg, angles).
Reimplemented from mrpt::bayes::CKalmanFilterCapable< 7, 3, 3, 7 >.
|
protectedvirtual |
Implements the transition Jacobian .
out_F | Must return the Jacobian. The returned matrix must be ![]() |
Reimplemented from mrpt::bayes::CKalmanFilterCapable< 7, 3, 3, 7 >.
|
inlineprotectedvirtualinherited |
Only called if using a numeric approximation of the transition Jacobian, this method must return the increments in each dimension of the vehicle state vector while estimating the Jacobian.
Definition at line 277 of file CKalmanFilterCapable.h.
|
protectedvirtual |
Implements the transition model .
in_u | The vector returned by OnGetAction. |
inout_x | At input has
![]() |
out_skip | Set this to true if for some reason you want to skip the prediction step (to do not modify either the vector or the covariance). Default:false |
Implements mrpt::bayes::CKalmanFilterCapable< 7, 3, 3, 7 >.
|
protectedvirtual |
Implements the transition noise covariance .
out_Q | Must return the covariance matrix. The returned matrix must be of the same size than the jacobian from OnTransitionJacobian |
Implements mrpt::bayes::CKalmanFilterCapable< 7, 3, 3, 7 >.
|
staticinherited |
Sends a formated text to "debugOut" if not NULL, or to cout otherwise.
Referenced by mrpt::math::CLevenbergMarquardtTempl< VECTORTYPE, USERPARAM >::execute().
void mrpt::slam::CRangeBearingKFSLAM::processActionObservation | ( | CActionCollectionPtr & | action, |
CSensoryFramePtr & | SF | ||
) |
Process one new action and observations to update the map and robot pose estimate.
See the description of the class at the top of this page.
action | May contain odometry |
SF | The set of observations, must contain at least one CObservationBearingRange |
void mrpt::slam::CRangeBearingKFSLAM::reconsiderPartitionsNow | ( | ) |
The partitioning of the entire map is recomputed again.
Only when options.doPartitioningExperiment = true. This can be used after changing the parameters of the partitioning method. After this method, you can call getLastPartitionLandmarks.
void mrpt::slam::CRangeBearingKFSLAM::reset | ( | ) |
Reset the state of the SLAM filter: The map is emptied and the robot put back to (0,0,0).
|
inlineprotectedinherited |
The main entry point, executes one complete step: prediction + update.
It is protected since derived classes must provide a problem-specific entry point for users. The exact order in which this method calls the virtual method is explained in http://www.mrpt.org/Kalman_Filters
Definition at line 491 of file CKalmanFilterCapable.h.
References Abs(), ASSERT_, ASSERTDEB_, ASSERTMSG_, mrpt::bayes::TKF_options::debug_verify_analytic_jacobians, mrpt::bayes::TKF_options::debug_verify_analytic_jacobians_threshold, mrpt::math::distance(), mrpt::utils::CTimeLogger::enable(), mrpt::bayes::TKF_options::enable_profiler, mrpt::utils::CTimeLogger::enter(), mrpt::math::estimateJacobian(), mrpt::utils::find_in_vector(), mrpt::bayes::TKF_options::IKF_iterations, mrpt::bayes::kfEKFAlaDavison, mrpt::bayes::kfEKFNaive, mrpt::bayes::kfIKF, mrpt::bayes::kfIKFFull, mrpt::utils::CTimeLogger::leave(), mrpt::system::os::memcpy(), mrpt::bayes::TKF_options::method, MRPT_END, MRPT_START, sumAll(), THROW_EXCEPTION, mrpt::math::UNINITIALIZED_MATRIX, mrpt::bayes::TKF_options::use_analytic_observation_jacobian, mrpt::bayes::TKF_options::use_analytic_transition_jacobian, mrpt::mrpt::system::vectorToTextFile(), and mrpt::bayes::TKF_options::verbose.
void mrpt::slam::CRangeBearingKFSLAM::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 elements in 2D.
|
inherited |
Generic options for the Kalman Filter algorithm itself.
Definition at line 466 of file CKalmanFilterCapable.h.
|
protected |
Set up by processActionObservation.
Definition at line 441 of file CRangeBearingKFSLAM.h.
|
protected |
The mapping between landmark IDs and indexes in the Pkk cov.
matrix:
Definition at line 449 of file CRangeBearingKFSLAM.h.
|
protected |
Last data association.
Definition at line 462 of file CRangeBearingKFSLAM.h.
|
protected |
Definition at line 460 of file CRangeBearingKFSLAM.h.
|
protectedinherited |
The system full covariance matrix.
Definition at line 239 of file CKalmanFilterCapable.h.
|
protected |
Set up by processActionObservation.
Definition at line 445 of file CRangeBearingKFSLAM.h.
|
protected |
The sequence of all the observations and the robot path (kept for debugging, statistics,etc)
Definition at line 458 of file CRangeBearingKFSLAM.h.
|
protectedinherited |
Definition at line 243 of file CKalmanFilterCapable.h.
|
protectedinherited |
The system state vector.
Definition at line 238 of file CKalmanFilterCapable.h.
|
protected |
Used for map partitioning experiments.
Definition at line 454 of file CRangeBearingKFSLAM.h.
mrpt::slam::CRangeBearingKFSLAM::TOptions mrpt::slam::CRangeBearingKFSLAM::options |
Page generated by Doxygen 1.8.14 for MRPT 1.0.2 SVN: at lun oct 28 00:52:41 CET 2019 | Hosted on: |