Main MRPT website > C++ reference
MRPT logo
CRangeBearingKFSLAM.h
Go to the documentation of this file.
1 /* +---------------------------------------------------------------------------+
2  | Mobile Robot Programming Toolkit (MRPT) |
3  | http://www.mrpt.org/ |
4  | |
5  | Copyright (c) 2005-2014, Individual contributors, see AUTHORS file |
6  | See: http://www.mrpt.org/Authors - All rights reserved. |
7  | Released under BSD License. See details in http://www.mrpt.org/License |
8  +---------------------------------------------------------------------------+ */
9 #ifndef CRangeBearingKFSLAM_H
10 #define CRangeBearingKFSLAM_H
11 
17 
19 #include <mrpt/utils/bimap.h>
20 
27 #include <mrpt/slam/CLandmark.h>
28 #include <mrpt/slam/CSimpleMap.h>
31 
32 #include <mrpt/slam/link_pragmas.h>
33 
34 namespace mrpt
35 {
36  namespace slam
37  {
38  using namespace mrpt::bayes;
39 
40  /** An implementation of EKF-based SLAM with range-bearing sensors, odometry, a full 6D robot pose, and 3D landmarks.
41  * The main method is "processActionObservation" which processes pairs of action/observation.
42  * The state vector comprises: 3D robot position, a quaternion for its attitude, and the 3D landmarks in the map.
43  *
44  * The following Wiki page describes an front-end application based on this class:
45  * http://www.mrpt.org/Application:kf-slam
46  *
47  * For the theory behind this implementation, see the technical report in:
48  * http://www.mrpt.org/6D-SLAM
49  *
50  * \sa An implementation for 2D only: CRangeBearingKFSLAM2D
51  * \ingroup metric_slam_grp
52  */
54  public bayes::CKalmanFilterCapable<7 /* x y z qr qx qy qz*/,3 /* range yaw pitch */, 3 /* x y z */, 7 /* Ax Ay Az Aqr Aqx Aqy Aqz */ >
55  // <size_t VEH_SIZE, size_t OBS_SIZE, size_t FEAT_SIZE, size_t ACT_SIZE, size typename kftype = double>
56  {
57  public:
58  typedef mrpt::math::TPoint3D landmark_point_t; //!< Either mrpt::math::TPoint2D or mrpt::math::TPoint3D
59 
60  /** Constructor. */
62 
63  /** Destructor: */
64  virtual ~CRangeBearingKFSLAM();
65 
66  void reset(); //!< Reset the state of the SLAM filter: The map is emptied and the robot put back to (0,0,0).
67 
68  /** 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.
69  * \param action May contain odometry
70  * \param SF The set of observations, must contain at least one CObservationBearingRange
71  */
72  void processActionObservation(
73  CActionCollectionPtr &action,
74  CSensoryFramePtr &SF );
75 
76  /** Returns the complete mean and cov.
77  * \param out_robotPose The mean and the 7x7 covariance matrix of the robot 6D pose
78  * \param out_landmarksPositions One entry for each of the M landmark positions (3D).
79  * \param out_landmarkIDs Each element[index] (for indices of out_landmarksPositions) gives the corresponding landmark ID.
80  * \param out_fullState The complete state vector (7+3M).
81  * \param out_fullCovariance The full (7+3M)x(7+3M) covariance matrix of the filter.
82  * \sa getCurrentRobotPose
83  */
84  void getCurrentState(
85  CPose3DQuatPDFGaussian &out_robotPose,
86  std::vector<mrpt::math::TPoint3D> &out_landmarksPositions,
87  std::map<unsigned int,CLandmark::TLandmarkID> &out_landmarkIDs,
88  CVectorDouble &out_fullState,
89  CMatrixDouble &out_fullCovariance
90  ) const;
91 
92  /** Returns the complete mean and cov.
93  * \param out_robotPose The mean and the 7x7 covariance matrix of the robot 6D pose
94  * \param out_landmarksPositions One entry for each of the M landmark positions (3D).
95  * \param out_landmarkIDs Each element[index] (for indices of out_landmarksPositions) gives the corresponding landmark ID.
96  * \param out_fullState The complete state vector (7+3M).
97  * \param out_fullCovariance The full (7+3M)x(7+3M) covariance matrix of the filter.
98  * \sa getCurrentRobotPose
99  */
100  inline void getCurrentState(
101  CPose3DPDFGaussian &out_robotPose,
102  std::vector<mrpt::math::TPoint3D> &out_landmarksPositions,
103  std::map<unsigned int,CLandmark::TLandmarkID> &out_landmarkIDs,
104  CVectorDouble &out_fullState,
105  CMatrixDouble &out_fullCovariance
106  ) const
107  {
109  this->getCurrentState(q,out_landmarksPositions,out_landmarkIDs,out_fullState,out_fullCovariance);
110  out_robotPose = CPose3DPDFGaussian(q);
111  }
112 
113  /** Returns the mean & the 7x7 covariance matrix of the robot 6D pose (with rotation as a quaternion).
114  * \sa getCurrentState, getCurrentRobotPoseMean
115  */
116  void getCurrentRobotPose( CPose3DQuatPDFGaussian &out_robotPose ) const;
117 
118  /** Get the current robot pose mean, as a 3D+quaternion pose.
119  * \sa getCurrentRobotPose
120  */
121  mrpt::poses::CPose3DQuat getCurrentRobotPoseMean() const;
122 
123  /** Returns the mean & the 6x6 covariance matrix of the robot 6D pose (with rotation as 3 angles).
124  * \sa getCurrentState
125  */
126  inline void getCurrentRobotPose( CPose3DPDFGaussian &out_robotPose ) const
127  {
129  this->getCurrentRobotPose(q);
130  out_robotPose = CPose3DPDFGaussian(q);
131  }
132 
133  /** Returns a 3D representation of the landmarks in the map and the robot 3D position according to the current filter state.
134  * \param out_objects
135  */
136  void getAs3DObject( mrpt::opengl::CSetOfObjectsPtr &outObj ) const;
137 
138  /** Load options from a ini-like file/text
139  */
140  void loadOptions( const mrpt::utils::CConfigFileBase &ini );
141 
142  /** The options for the algorithm
143  */
145  {
146  /** Default values
147  */
148  TOptions();
149 
150  /** Load from a config file/text
151  */
152  void loadFromConfigFile(
153  const mrpt::utils::CConfigFileBase &source,
154  const std::string &section);
155 
156  /** This method must display clearly all the contents of the structure in textual form, sending it to a CStream.
157  */
158  void dumpToTextStream(CStream &out) const;
159 
160  /** A 7-length vector with the std. deviation of the transition model in (x,y,z, qr,qx,qy,qz) used only when there is no odometry (if there is odo, its uncertainty values will be used instead); x y z: In meters.
161  */
163 
164  /** The std. deviation of the sensor (for the matrix R in the kalman filters), in meters and radians.
165  */
166  float std_sensor_range, std_sensor_yaw, std_sensor_pitch;
167 
168  /** Additional std. dev. to sum to the motion model in the z axis (useful when there is only 2D odometry and we want to put things hard to the algorithm) (default=0)
169  */
171 
172  /** If set to true (default=false), map will be partitioned using the method stated by partitioningMethod
173  */
175 
176  /** Default = 3
177  */
179 
180  /** Applicable only if "doPartitioningExperiment=true".
181  * 0: Automatically detect partition through graph-cut.
182  * N>=1: Cut every "N" observations.
183  */
185 
186  // Data association:
189  double data_assoc_IC_chi2_thres; //!< Threshold in [0,1] for the chi2square test for individual compatibility between predictions and observations (default: 0.99)
190  TDataAssociationMetric data_assoc_IC_metric; //!< Whether to use mahalanobis (->chi2 criterion) vs. Matching likelihood.
191  double data_assoc_IC_ml_threshold;//!< Only if data_assoc_IC_metric==ML, the log-ML threshold (Default=0.0)
192 
193  bool create_simplemap; //!< Whether to fill m_SFs (default=false)
194 
195  bool force_ignore_odometry; //!< Whether to ignore the input odometry and behave as if there was no odometry at all (default: false)
196  } options;
197 
198  /** Information for data-association:
199  * \sa getLastDataAssociation
200  */
202  {
204  Y_pred_means(0,0),
205  Y_pred_covs(0,0)
206  {
207  }
208 
209  void clear() {
210  results.clear();
211  predictions_IDs.clear();
212  newly_inserted_landmarks.clear();
213  }
214 
215  // Predictions from the map:
216  CMatrixTemplateNumeric<kftype> Y_pred_means,Y_pred_covs;
218 
219  /** Map from the 0-based index within the last observation and the landmark 0-based index in the map (the robot-map state vector)
220  Only used for stats and so. */
221  std::map<size_t,size_t> newly_inserted_landmarks;
222 
223  // DA results:
225  };
226 
227  /** Returns a read-only reference to the information on the last data-association */
229  return m_last_data_association;
230  }
231 
232 
233  /** Return the last partition of the sequence of sensoryframes (it is NOT a partition of the map!!)
234  * Only if options.doPartitioningExperiment = true
235  * \sa getLastPartitionLandmarks
236  */
237  void getLastPartition( std::vector<vector_uint> &parts )
238  {
239  parts = m_lastPartitionSet;
240  }
241 
242  /** Return the partitioning of the landmarks in clusters accoring to the last partition.
243  * Note that the same landmark may appear in different clusters (the partition is not in the space of landmarks)
244  * Only if options.doPartitioningExperiment = true
245  * \param 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 !!).
246  * \sa getLastPartition
247  */
248  void getLastPartitionLandmarks( std::vector<vector_uint> &landmarksMembership ) const;
249 
250  /** For testing only: returns the partitioning as "getLastPartitionLandmarks" but as if a fixed-size submaps (size K) were have been used.
251  */
252  void getLastPartitionLandmarksAsIfFixedSubmaps( size_t K, std::vector<vector_uint> &landmarksMembership );
253 
254 
255  /** Computes the ratio of the missing information matrix elements which are ignored under a certain partitioning of the landmarks.
256  * \sa getLastPartitionLandmarks, getLastPartitionLandmarksAsIfFixedSubmaps
257  */
258  double computeOffDiagonalBlocksApproximationError( const std::vector<vector_uint> &landmarksMembership ) const;
259 
260 
261  /** The partitioning of the entire map is recomputed again.
262  * Only when options.doPartitioningExperiment = true.
263  * This can be used after changing the parameters of the partitioning method.
264  * After this method, you can call getLastPartitionLandmarks.
265  * \sa getLastPartitionLandmarks
266  */
267  void reconsiderPartitionsNow();
268 
269 
270  /** Provides access to the parameters of the map partitioning algorithm.
271  */
273  {
274  return &mapPartitioner.options;
275  }
276 
277  /** Save the current state of the filter (robot pose & map) to a MATLAB script which displays all the elements in 2D
278  */
279  void saveMapAndPath2DRepresentationAsMATLABFile(
280  const std::string &fil,
281  float stdCount=3.0f,
282  const std::string &styleLandmarks = std::string("b"),
283  const std::string &stylePath = std::string("r"),
284  const std::string &styleRobot = std::string("r") ) const;
285 
286 
287 
288  protected:
289 
290  /** @name Virtual methods for Kalman Filter implementation
291  @{
292  */
293 
294  /** Must return the action vector u.
295  * \param out_u The action vector which will be passed to OnTransitionModel
296  */
297  void OnGetAction( KFArray_ACT &out_u ) const;
298 
299  /** Implements the transition model \f$ \hat{x}_{k|k-1} = f( \hat{x}_{k-1|k-1}, u_k ) \f$
300  * \param in_u The vector returned by OnGetAction.
301  * \param inout_x At input has \f[ \hat{x}_{k-1|k-1} \f] , at output must have \f$ \hat{x}_{k|k-1} \f$ .
302  * \param 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
303  */
304  void OnTransitionModel(
305  const KFArray_ACT &in_u,
306  KFArray_VEH &inout_x,
307  bool &out_skipPrediction
308  ) const;
309 
310  /** Implements the transition Jacobian \f$ \frac{\partial f}{\partial x} \f$
311  * \param out_F Must return the Jacobian.
312  * The returned matrix must be \f$V \times V\f$ with V being either the size of the whole state vector (for non-SLAM problems) or VEH_SIZE (for SLAM problems).
313  */
314  void OnTransitionJacobian( KFMatrix_VxV &out_F ) const;
315 
316  /** Implements the transition noise covariance \f$ Q_k \f$
317  * \param out_Q Must return the covariance matrix.
318  * The returned matrix must be of the same size than the jacobian from OnTransitionJacobian
319  */
320  void OnTransitionNoise( KFMatrix_VxV &out_Q ) const;
321 
322  /** 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.
323  *
324  * \param 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.
325  * \param 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.
326  * \param 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".
327  * \param in_lm_indices_in_S The indices of the map landmarks (range [0,getNumberOfLandmarksInTheMap()-1]) that can be found in the matrix in_S.
328  *
329  * This method will be called just once for each complete KF iteration.
330  * \note It is assumed that the observations are independent, i.e. there are NO cross-covariances between them.
331  */
332  void OnGetObservationsAndDataAssociation(
333  vector_KFArray_OBS &out_z,
334  vector_int &out_data_association,
335  const vector_KFArray_OBS &in_all_predictions,
336  const KFMatrix &in_S,
337  const vector_size_t &in_lm_indices_in_S,
338  const KFMatrix_OxO &in_R
339  );
340 
341  void OnObservationModel(
342  const vector_size_t &idx_landmarks_to_predict,
343  vector_KFArray_OBS &out_predictions
344  ) const;
345 
346  /** Implements the observation Jacobians \f$ \frac{\partial h_i}{\partial x} \f$ and (when applicable) \f$ \frac{\partial h_i}{\partial y_i} \f$.
347  * \param 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.
348  * \param Hx The output Jacobian \f$ \frac{\partial h_i}{\partial x} \f$.
349  * \param Hy The output Jacobian \f$ \frac{\partial h_i}{\partial y_i} \f$.
350  */
351  void OnObservationJacobians(
352  const size_t &idx_landmark_to_predict,
353  KFMatrix_OxV &Hx,
354  KFMatrix_OxF &Hy
355  ) const;
356 
357  /** Computes A=A-B, which may need to be re-implemented depending on the topology of the individual scalar components (eg, angles).
358  */
359  void OnSubstractObservationVectors(KFArray_OBS &A, const KFArray_OBS &B) const;
360 
361  /** Return the observation NOISE covariance matrix, that is, the model of the Gaussian additive noise of the sensor.
362  * \param out_R The noise covariance matrix. It might be non diagonal, but it'll usually be.
363  */
364  void OnGetObservationNoise(KFMatrix_OxO &out_R) const;
365 
366  /** This will be called before OnGetObservationsAndDataAssociation to allow the application to reduce the number of covariance landmark predictions to be made.
367  * For example, features which are known to be "out of sight" shouldn't be added to the output list to speed up the calculations.
368  * \param 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.
369  * \param out_LM_indices_to_predict The list of landmark indices in the map [0,getNumberOfLandmarksInTheMap()-1] that should be predicted.
370  * \note This is not a pure virtual method, so it should be implemented only if desired. The default implementation returns a vector with all the landmarks in the map.
371  * \sa OnGetObservations, OnDataAssociation
372  */
373  void OnPreComputingPredictions(
374  const vector_KFArray_OBS &in_all_prediction_means,
375  vector_size_t &out_LM_indices_to_predict ) const;
376 
377  /** If applicable to the given problem, this method implements the inverse observation model needed to extend the "map" with a new "element".
378  * \param in_z The observation vector whose inverse sensor model is to be computed. This is actually one of the vector<> returned by OnGetObservations().
379  * \param out_yn The F-length vector with the inverse observation model \f$ y_n=y(x,z_n) \f$.
380  * \param out_dyn_dxv The \f$F \times V\f$ Jacobian of the inv. sensor model wrt the robot pose \f$ \frac{\partial y_n}{\partial x_v} \f$.
381  * \param out_dyn_dhn The \f$F \times O\f$ Jacobian of the inv. sensor model wrt the observation vector \f$ \frac{\partial y_n}{\partial h_n} \f$.
382  *
383  * - O: OBS_SIZE
384  * - V: VEH_SIZE
385  * - F: FEAT_SIZE
386  *
387  * \note OnNewLandmarkAddedToMap will be also called after calling this method if a landmark is actually being added to the map.
388  */
389  void OnInverseObservationModel(
390  const KFArray_OBS & in_z,
391  KFArray_FEAT & out_yn,
392  KFMatrix_FxV & out_dyn_dxv,
393  KFMatrix_FxO & out_dyn_dhn ) const;
394 
395  /** If applicable to the given problem, do here any special handling of adding a new landmark to the map.
396  * \param 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.
397  * \param 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.
398  * \sa OnInverseObservationModel
399  */
400  void OnNewLandmarkAddedToMap(
401  const size_t in_obsIdx,
402  const size_t in_idxNewFeat );
403 
404 
405  /** 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.
406  */
407  void OnNormalizeStateVector();
408 
409  /** @}
410  */
411 
412  /** Set up by processActionObservation
413  */
414  CActionCollectionPtr m_action;
415 
416  /** Set up by processActionObservation
417  */
418  CSensoryFramePtr m_SF;
419 
420  /** The mapping between landmark IDs and indexes in the Pkk cov. matrix:
421  */
423 
424 
425  /** Used for map partitioning experiments
426  */
427  CIncrementalMapPartitioner mapPartitioner;
428 
429  /** The sequence of all the observations and the robot path (kept for debugging, statistics,etc)
430  */
431  CSimpleMap m_SFs;
433  std::vector<vector_uint> m_lastPartitionSet;
435  TDataAssocInfo m_last_data_association; //!< Last data association
436 
437  /** Return the last odometry, as a pose increment. */
438  mrpt::poses::CPose3DQuat getIncrementFromOdometry() const;
439 
440 
441  }; // end class
442  } // End of namespace
443 } // End of namespace
444 
445 
446 
447 
448 #endif
Virtual base for Kalman Filter (EKF,IEKF,UKF) implementations.
mrpt::math::TPoint3D landmark_point_t
Either mrpt::math::TPoint2D or mrpt::math::TPoint3D.
An implementation of EKF-based SLAM with range-bearing sensors, odometry, a full 6D robot pose...
const TDataAssocInfo & getLastDataAssociation() const
Returns a read-only reference to the information on the last data-association.
bool force_ignore_odometry
Whether to ignore the input odometry and behave as if there was no odometry at all (default: false) ...
The namespace for Bayesian filtering algorithm: different particle filters and Kalman filter algorith...
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 ...
dynamic_vector< float > CVectorFloat
Column vector, like Eigen::MatrixXf, but automatically initialized to zeros since construction...
Definition: eigen_frwds.h:51
Declares a class that represents a Probability Density function (PDF) of a 3D pose using a quaternion...
This class allows loading and storing values and vectors of different types from a configuration text...
CVectorFloat stds_Q_no_odo
A 7-length vector with the std.
CIncrementalMapPartitioner::TOptions * mapPartitionOptions()
Provides access to the parameters of the map partitioning algorithm.
This base class is used to provide a unified interface to files,memory buffers,..Please see the deriv...
Definition: CStream.h:38
std::vector< size_t > vector_size_t
int partitioningMethod
Applicable only if "doPartitioningExperiment=true".
TDataAssociationMetric
Different metrics for data association, used in mrpt::slam::data_association For a comparison of both...
CMatrixTemplateNumeric< double > CMatrixDouble
Declares a matrix of double numbers (non serializable).
void getCurrentRobotPose(CPose3DPDFGaussian &out_robotPose) const
Returns the mean & the 6x6 covariance matrix of the robot 6D pose (with rotation as 3 angles)...
A bidirectional version of std::map, declared as bimap and which actually contains two std...
Definition: bimap.h:27
TDataAssociationMetric data_assoc_IC_metric
Whether to use mahalanobis (->chi2 criterion) vs. Matching likelihood.
A class used to store a 3D pose as a translation (x,y,z) and a quaternion (qr,qx,qy,qz).
Definition: CPose3DQuat.h:41
double data_assoc_IC_ml_threshold
Only if data_assoc_IC_metric==ML, the log-ML threshold (Default=0.0)
This class stores a sequence of pairs, thus a "metric map" can be t...
Definition: CSimpleMap.h:34
This is the global namespace for all Mobile Robot Programming Toolkit (MRPT) libraries.
This class can be used to make partitions on a map/graph build from observations taken at some poses/...
void getCurrentState(CPose3DPDFGaussian &out_robotPose, std::vector< mrpt::math::TPoint3D > &out_landmarksPositions, std::map< unsigned int, CLandmark::TLandmarkID > &out_landmarkIDs, CVectorDouble &out_fullState, CMatrixDouble &out_fullCovariance) const
Returns the complete mean and cov.
std::vector< int32_t > vector_int
Declares a class that represents a Probability Density function (PDF) of a 3D pose ...
bool create_simplemap
Whether to fill m_SFs (default=false)
bool doPartitioningExperiment
If set to true (default=false), map will be partitioned using the method stated by partitioningMethod...
dynamic_vector< double > CVectorDouble
Column vector, like Eigen::MatrixXd, but automatically initialized to zeros since construction...
Definition: eigen_frwds.h:53
The results from mrpt::slam::data_association.
Lightweight 3D point.
TDataAssociationMethod
Different algorithms for data association, used in mrpt::slam::data_association.
double data_assoc_IC_chi2_thres
Threshold in [0,1] for the chi2square test for individual compatibility between predictions and obser...
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...
This is a virtual base class for sets of options than can be loaded from and/or saved to configuratio...



Page generated by Doxygen 1.8.8 for MRPT 1.2.2 SVN:Unversioned directory at Tue Oct 14 02:14:08 UTC 2014