Main MRPT website > C++ reference
MRPT logo
CRangeBearingKFSLAM2D.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 CRangeBearingKFSLAM2D_H
10 #define CRangeBearingKFSLAM2D_H
11 
18 
20 #include <mrpt/utils/bimap.h>
21 
26 #include <mrpt/slam/CLandmark.h>
27 #include <mrpt/slam/CSimpleMap.h>
30 
31 #include <mrpt/slam/link_pragmas.h>
32 
33 namespace mrpt
34 {
35  namespace slam
36  {
37  using namespace mrpt::bayes;
38  using namespace mrpt::poses;
39 
40  /** An implementation of EKF-based SLAM with range-bearing sensors, odometry, and a 2D (+heading) robot pose, and 2D landmarks.
41  * The main method is "processActionObservation" which processes pairs of action/observation.
42  *
43  * The following pages describe front-end applications based on this class:
44  * - http://www.mrpt.org/Application:2d-slam-demo
45  * - http://www.mrpt.org/Application:kf-slam
46  *
47  * \sa CRangeBearingKFSLAM \ingroup metric_slam_grp
48  */
50  public bayes::CKalmanFilterCapable<3 /* x y yaw */, 2 /* range yaw */, 2 /* x y */, 3 /* Ax Ay Ayaw */>
51  // <size_t VEH_SIZE, size_t OBS_SIZE, size_t FEAT_SIZE, size_t ACT_SIZE, size typename kftype = double>
52  {
53  public:
54  typedef mrpt::math::TPoint2D landmark_point_t; //!< Either mrpt::math::TPoint2D or mrpt::math::TPoint3D
55 
56  CRangeBearingKFSLAM2D( ); //!< Default constructor
57  virtual ~CRangeBearingKFSLAM2D(); //!< Destructor
58  void reset(); //!< Reset the state of the SLAM filter: The map is emptied and the robot put back to (0,0,0).
59 
60  /** 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.
61  * \param action May contain odometry
62  * \param SF The set of observations, must contain at least one CObservationBearingRange
63  */
64  void processActionObservation(
65  CActionCollectionPtr &action,
66  CSensoryFramePtr &SF );
67 
68  /** Returns the complete mean and cov.
69  * \param out_robotPose The mean & 3x3 covariance matrix of the robot 2D pose
70  * \param out_landmarksPositions One entry for each of the M landmark positions (2D).
71  * \param out_landmarkIDs Each element[index] (for indices of out_landmarksPositions) gives the corresponding landmark ID.
72  * \param out_fullState The complete state vector (3+2M).
73  * \param out_fullCovariance The full (3+2M)x(3+2M) covariance matrix of the filter.
74  * \sa getCurrentRobotPose
75  */
76  void getCurrentState(
77  CPosePDFGaussian &out_robotPose,
78  std::vector<TPoint2D> &out_landmarksPositions,
79  std::map<unsigned int,CLandmark::TLandmarkID> &out_landmarkIDs,
80  CVectorDouble &out_fullState,
81  CMatrixDouble &out_fullCovariance
82  ) const;
83 
84  /** Returns the mean & 3x3 covariance matrix of the robot 2D pose.
85  * \sa getCurrentState
86  */
87  void getCurrentRobotPose(
88  CPosePDFGaussian &out_robotPose ) const;
89 
90  /** Returns a 3D representation of the landmarks in the map and the robot 3D position according to the current filter state.
91  * \param out_objects
92  */
93  void getAs3DObject( mrpt::opengl::CSetOfObjectsPtr &outObj ) const;
94 
95  /** Load options from a ini-like file/text
96  */
97  void loadOptions( const mrpt::utils::CConfigFileBase &ini );
98 
99  /** The options for the algorithm
100  */
102  {
103  /** Default values
104  */
105  TOptions();
106 
107  /** Load from a config file/text
108  */
109  void loadFromConfigFile(
110  const mrpt::utils::CConfigFileBase &source,
111  const std::string &section);
112 
113  /** This method must display clearly all the contents of the structure in textual form, sending it to a CStream.
114  */
115  void dumpToTextStream(CStream &out) const;
116 
117 
118  CVectorFloat stds_Q_no_odo; //!< A 3-length vector with the std. deviation of the transition model in (x,y,phi) used only when there is no odometry (if there is odo, its uncertainty values will be used instead); x y: In meters, phi: radians (but in degrees when loading from a configuration ini-file!)
119  float std_sensor_range, std_sensor_yaw; //!< The std. deviation of the sensor (for the matrix R in the kalman filters), in meters and radians.
120  float quantiles_3D_representation; //!< Default = 3
121  bool create_simplemap; //!< Whether to fill m_SFs (default=false)
122 
123  // Data association:
126  double data_assoc_IC_chi2_thres; //!< Threshold in [0,1] for the chi2square test for individual compatibility between predictions and observations (default: 0.99)
127  TDataAssociationMetric data_assoc_IC_metric; //!< Whether to use mahalanobis (->chi2 criterion) vs. Matching likelihood.
128  double data_assoc_IC_ml_threshold;//!< Only if data_assoc_IC_metric==ML, the log-ML threshold (Default=0.0)
129 
130  };
131 
132  TOptions options; //!< The options for the algorithm
133 
134 
135  /** Save the current state of the filter (robot pose & map) to a MATLAB script which displays all the elements in 2D
136  */
137  void saveMapAndPath2DRepresentationAsMATLABFile(
138  const std::string &fil,
139  float stdCount=3.0f,
140  const std::string &styleLandmarks = std::string("b"),
141  const std::string &stylePath = std::string("r"),
142  const std::string &styleRobot = std::string("r") ) const;
143 
144 
145  /** Information for data-association:
146  * \sa getLastDataAssociation
147  */
149  {
151  Y_pred_means(0,0),
152  Y_pred_covs(0,0)
153  {
154  }
155 
156  void clear() {
157  results.clear();
158  predictions_IDs.clear();
159  newly_inserted_landmarks.clear();
160  }
161 
162  // Predictions from the map:
163  CMatrixTemplateNumeric<kftype> Y_pred_means,Y_pred_covs;
165 
166  /** Map from the 0-based index within the last observation and the landmark 0-based index in the map (the robot-map state vector)
167  Only used for stats and so. */
168  std::map<size_t,size_t> newly_inserted_landmarks;
169 
170  // DA results:
172  };
173 
174  /** Returns a read-only reference to the information on the last data-association */
176  return m_last_data_association;
177  }
178 
179  protected:
180 
181  /** @name Virtual methods for Kalman Filter implementation
182  @{
183  */
184 
185  /** Must return the action vector u.
186  * \param out_u The action vector which will be passed to OnTransitionModel
187  */
188  void OnGetAction( KFArray_ACT &out_u ) const;
189 
190  /** Implements the transition model \f$ \hat{x}_{k|k-1} = f( \hat{x}_{k-1|k-1}, u_k ) \f$
191  * \param in_u The vector returned by OnGetAction.
192  * \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$ .
193  * \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
194  */
195  void OnTransitionModel(
196  const KFArray_ACT &in_u,
197  KFArray_VEH &inout_x,
198  bool &out_skipPrediction
199  ) const;
200 
201  /** Implements the transition Jacobian \f$ \frac{\partial f}{\partial x} \f$
202  * \param out_F Must return the Jacobian.
203  * 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).
204  */
205  void OnTransitionJacobian( KFMatrix_VxV &out_F ) const;
206 
207  /** 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.
208  */
209  void OnTransitionJacobianNumericGetIncrements(KFArray_VEH &out_increments) const;
210 
211 
212  /** Implements the transition noise covariance \f$ Q_k \f$
213  * \param out_Q Must return the covariance matrix.
214  * The returned matrix must be of the same size than the jacobian from OnTransitionJacobian
215  */
216  void OnTransitionNoise( KFMatrix_VxV &out_Q ) const;
217 
218  /** 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.
219  *
220  * \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.
221  * \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.
222  * \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".
223  * \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.
224  *
225  * This method will be called just once for each complete KF iteration.
226  * \note It is assumed that the observations are independent, i.e. there are NO cross-covariances between them.
227  */
228  void OnGetObservationsAndDataAssociation(
229  vector_KFArray_OBS &out_z,
230  vector_int &out_data_association,
231  const vector_KFArray_OBS &in_all_predictions,
232  const KFMatrix &in_S,
233  const vector_size_t &in_lm_indices_in_S,
234  const KFMatrix_OxO &in_R
235  );
236 
237  void OnObservationModel(
238  const vector_size_t &idx_landmarks_to_predict,
239  vector_KFArray_OBS &out_predictions
240  ) const;
241 
242  /** Implements the observation Jacobians \f$ \frac{\partial h_i}{\partial x} \f$ and (when applicable) \f$ \frac{\partial h_i}{\partial y_i} \f$.
243  * \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.
244  * \param Hx The output Jacobian \f$ \frac{\partial h_i}{\partial x} \f$.
245  * \param Hy The output Jacobian \f$ \frac{\partial h_i}{\partial y_i} \f$.
246  */
247  void OnObservationJacobians(
248  const size_t &idx_landmark_to_predict,
249  KFMatrix_OxV &Hx,
250  KFMatrix_OxF &Hy
251  ) const;
252 
253  /** 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.
254  */
255  void OnObservationJacobiansNumericGetIncrements(
256  KFArray_VEH &out_veh_increments,
257  KFArray_FEAT &out_feat_increments ) const;
258 
259 
260  /** Computes A=A-B, which may need to be re-implemented depending on the topology of the individual scalar components (eg, angles).
261  */
262  void OnSubstractObservationVectors(KFArray_OBS &A, const KFArray_OBS &B) const;
263 
264  /** Return the observation NOISE covariance matrix, that is, the model of the Gaussian additive noise of the sensor.
265  * \param out_R The noise covariance matrix. It might be non diagonal, but it'll usually be.
266  */
267  void OnGetObservationNoise(KFMatrix_OxO &out_R) const;
268 
269  /** This will be called before OnGetObservationsAndDataAssociation to allow the application to reduce the number of covariance landmark predictions to be made.
270  * For example, features which are known to be "out of sight" shouldn't be added to the output list to speed up the calculations.
271  * \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.
272  * \param out_LM_indices_to_predict The list of landmark indices in the map [0,getNumberOfLandmarksInTheMap()-1] that should be predicted.
273  * \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.
274  * \sa OnGetObservations, OnDataAssociation
275  */
276  void OnPreComputingPredictions(
277  const vector_KFArray_OBS &in_all_prediction_means,
278  vector_size_t &out_LM_indices_to_predict ) const;
279 
280  /** If applicable to the given problem, this method implements the inverse observation model needed to extend the "map" with a new "element".
281  * \param in_z The observation vector whose inverse sensor model is to be computed. This is actually one of the vector<> returned by OnGetObservations().
282  * \param out_yn The F-length vector with the inverse observation model \f$ y_n=y(x,z_n) \f$.
283  * \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$.
284  * \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$.
285  *
286  * - O: OBS_SIZE
287  * - V: VEH_SIZE
288  * - F: FEAT_SIZE
289  *
290  * \note OnNewLandmarkAddedToMap will be also called after calling this method if a landmark is actually being added to the map.
291  */
292  void OnInverseObservationModel(
293  const KFArray_OBS & in_z,
294  KFArray_FEAT & out_yn,
295  KFMatrix_FxV & out_dyn_dxv,
296  KFMatrix_FxO & out_dyn_dhn ) const;
297 
298  /** If applicable to the given problem, do here any special handling of adding a new landmark to the map.
299  * \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.
300  * \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.
301  * \sa OnInverseObservationModel
302  */
303  void OnNewLandmarkAddedToMap(
304  const size_t in_obsIdx,
305  const size_t in_idxNewFeat );
306 
307 
308  /** 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.
309  */
310  void OnNormalizeStateVector();
311 
312  /** @}
313  */
314 
316  void getLandmarkIDsFromIndexInStateVector(std::map<unsigned int,CLandmark::TLandmarkID> &out_id2index) const
317  {
318  out_id2index = m_IDs.getInverseMap();
319  }
320 
321  protected:
322 
323  /** Set up by processActionObservation
324  */
325  CActionCollectionPtr m_action;
326 
327  /** Set up by processActionObservation
328  */
329  CSensoryFramePtr m_SF;
330 
331  /** The mapping between landmark IDs and indexes in the Pkk cov. matrix:
332  */
334 
335  /** The sequence of all the observations and the robot path (kept for debugging, statistics,etc)
336  */
337  CSimpleMap m_SFs;
339  TDataAssocInfo m_last_data_association; //!< Last data association
340 
341 
342  }; // end class
343  } // End of namespace
344 } // End of namespace
345 
346 #endif
An implementation of EKF-based SLAM with range-bearing sensors, odometry, and a 2D (+heading) robot p...
Virtual base for Kalman Filter (EKF,IEKF,UKF) implementations.
TOptions options
The options for the algorithm.
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...
bool create_simplemap
Whether to fill m_SFs (default=false)
The namespace for Bayesian filtering algorithm: different particle filters and Kalman filter algorith...
CVectorFloat stds_Q_no_odo
A 3-length vector with the std. deviation of the transition model in (x,y,phi) used only when there i...
dynamic_vector< float > CVectorFloat
Column vector, like Eigen::MatrixXf, but automatically initialized to zeros since construction...
Definition: eigen_frwds.h:51
This class allows loading and storing values and vectors of different types from a configuration text...
This base class is used to provide a unified interface to files,memory buffers,..Please see the deriv...
Definition: CStream.h:38
Declares a class that represents a Probability Density function (PDF) of a 2D pose ...
std::vector< size_t > vector_size_t
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).
double data_assoc_IC_ml_threshold
Only if data_assoc_IC_metric==ML, the log-ML threshold (Default=0.0)
A bidirectional version of std::map, declared as bimap and which actually contains two std...
Definition: bimap.h:27
mrpt::math::TPoint2D landmark_point_t
Either mrpt::math::TPoint2D or mrpt::math::TPoint3D.
Classes for 2D/3D geometry representation, both of single values and probability density distribution...
Definition: CPoint.h:17
const TDataAssocInfo & getLastDataAssociation() const
Returns a read-only reference to the information on the last data-association.
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.
double data_assoc_IC_chi2_thres
Threshold in [0,1] for the chi2square test for individual compatibility between predictions and obser...
std::vector< int32_t > vector_int
float std_sensor_yaw
The std. deviation of the sensor (for the matrix R in the kalman filters), in meters and radians...
TDataAssociationMetric data_assoc_IC_metric
Whether to use mahalanobis (->chi2 criterion) vs. Matching likelihood.
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.
TDataAssociationMethod
Different algorithms for data association, used in mrpt::slam::data_association.
Lightweight 2D point.
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