MRPT  1.9.9
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-2018, 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 
16 
18 #include <mrpt/containers/bimap.h>
19 
20 #include <mrpt/obs/CSensoryFrame.h>
26 #include <mrpt/maps/CLandmark.h>
27 #include <mrpt/maps/CSimpleMap.h>
30 
31 namespace mrpt::slam
32 {
33 /** An implementation of EKF-based SLAM with range-bearing sensors, odometry, a
34  * full 6D robot pose, and 3D landmarks.
35  * The main method is "processActionObservation" which processes pairs of
36  * action/observation.
37  * The state vector comprises: 3D robot position, a quaternion for its
38  * attitude, and the 3D landmarks in the map.
39  *
40  * The following Wiki page describes an front-end application based on this
41  * class:
42  * http://www.mrpt.org/Application:kf-slam
43  *
44  * For the theory behind this implementation, see the technical report in:
45  * http://www.mrpt.org/6D-SLAM
46  *
47  * \sa An implementation for 2D only: CRangeBearingKFSLAM2D
48  * \ingroup metric_slam_grp
49  */
51  : public bayes::CKalmanFilterCapable<7 /* x y z qr qx qy qz*/,
52  3 /* range yaw pitch */, 3 /* x y z */,
53  7 /* Ax Ay Az Aqr Aqx Aqy Aqz */>
54 // <size_t VEH_SIZE, size_t OBS_SIZE, size_t FEAT_SIZE, size_t
55 // ACT_SIZE, size typename kftype = double>
56 {
57  public:
58  /** Either mrpt::math::TPoint2D or mrpt::math::TPoint3D */
60 
61  /** Constructor. */
63 
64  /** Destructor: */
65  virtual ~CRangeBearingKFSLAM();
66 
67  /** Reset the state of the SLAM filter: The map is emptied and the robot put
68  * back to (0,0,0). */
69  void reset();
70 
71  /** Process one new action and observations to update the map and robot pose
72  *estimate. See the description of the class at the top of this page.
73  * \param action May contain odometry
74  * \param SF The set of observations, must contain at least one
75  *CObservationBearingRange
76  */
80 
81  /** Returns the complete mean and cov.
82  * \param out_robotPose The mean and the 7x7 covariance matrix of the
83  * robot 6D pose
84  * \param out_landmarksPositions One entry for each of the M landmark
85  * positions (3D).
86  * \param out_landmarkIDs Each element[index] (for indices of
87  * out_landmarksPositions) gives the corresponding landmark ID.
88  * \param out_fullState The complete state vector (7+3M).
89  * \param out_fullCovariance The full (7+3M)x(7+3M) covariance matrix of
90  * the filter.
91  * \sa getCurrentRobotPose
92  */
93  void getCurrentState(
95  std::vector<mrpt::math::TPoint3D>& out_landmarksPositions,
96  std::map<unsigned int, mrpt::maps::CLandmark::TLandmarkID>&
97  out_landmarkIDs,
98  mrpt::math::CVectorDouble& out_fullState,
99  mrpt::math::CMatrixDouble& out_fullCovariance) const;
100 
101  /** Returns the complete mean and cov.
102  * \param out_robotPose The mean and the 7x7 covariance matrix of the
103  * robot 6D pose
104  * \param out_landmarksPositions One entry for each of the M landmark
105  * positions (3D).
106  * \param out_landmarkIDs Each element[index] (for indices of
107  * out_landmarksPositions) gives the corresponding landmark ID.
108  * \param out_fullState The complete state vector (7+3M).
109  * \param out_fullCovariance The full (7+3M)x(7+3M) covariance matrix of
110  * the filter.
111  * \sa getCurrentRobotPose
112  */
113  inline void getCurrentState(
114  mrpt::poses::CPose3DPDFGaussian& out_robotPose,
115  std::vector<mrpt::math::TPoint3D>& out_landmarksPositions,
116  std::map<unsigned int, mrpt::maps::CLandmark::TLandmarkID>&
117  out_landmarkIDs,
118  mrpt::math::CVectorDouble& out_fullState,
119  mrpt::math::CMatrixDouble& out_fullCovariance) const
120  {
123  this->getCurrentState(
124  q, out_landmarksPositions, out_landmarkIDs, out_fullState,
125  out_fullCovariance);
126  out_robotPose = mrpt::poses::CPose3DPDFGaussian(q);
127  }
128 
129  /** Returns the mean & the 7x7 covariance matrix of the robot 6D pose (with
130  * rotation as a quaternion).
131  * \sa getCurrentState, getCurrentRobotPoseMean
132  */
133  void getCurrentRobotPose(
134  mrpt::poses::CPose3DQuatPDFGaussian& out_robotPose) const;
135 
136  /** Get the current robot pose mean, as a 3D+quaternion pose.
137  * \sa getCurrentRobotPose
138  */
140 
141  /** Returns the mean & the 6x6 covariance matrix of the robot 6D pose (with
142  * rotation as 3 angles).
143  * \sa getCurrentState
144  */
145  inline void getCurrentRobotPose(
146  mrpt::poses::CPose3DPDFGaussian& out_robotPose) const
147  {
150  this->getCurrentRobotPose(q);
151  out_robotPose = mrpt::poses::CPose3DPDFGaussian(q);
152  }
153 
154  /** Returns a 3D representation of the landmarks in the map and the robot 3D
155  * position according to the current filter state.
156  * \param out_objects
157  */
159 
160  /** Load options from a ini-like file/text
161  */
163 
164  /** The options for the algorithm
165  */
167  {
168  /** Default values */
169  TOptions();
170 
171  void loadFromConfigFile(
173  const std::string& section) override; // See base docs
174  void dumpToTextStream(
175  std::ostream& out) const override; // See base docs
176 
177  /** A 7-length vector with the std. deviation of the transition model in
178  * (x,y,z, qr,qx,qy,qz) used only when there is no odometry (if there is
179  * odo, its uncertainty values will be used instead); x y z: In meters.
180  */
182 
183  /** The std. deviation of the sensor (for the matrix R in the kalman
184  * filters), in meters and radians. */
186 
187  /** Additional std. dev. to sum to the motion model in the z axis
188  * (useful when there is only 2D odometry and we want to put things hard
189  * to the algorithm) (default=0) */
191 
192  /** If set to true (default=false), map will be partitioned using the
193  * method stated by partitioningMethod */
195 
196  /** Default = 3 */
198 
199  /** Applicable only if "doPartitioningExperiment=true".
200  * 0: Automatically detect partition through graph-cut.
201  * N>=1: Cut every "N" observations.
202  */
204 
205  // Data association:
208  /** Threshold in [0,1] for the chi2square test for individual
209  * compatibility between predictions and observations (default: 0.99) */
211  /** Whether to use mahalanobis (->chi2 criterion) vs. Matching
212  * likelihood. */
214  /** Only if data_assoc_IC_metric==ML, the log-ML threshold (Default=0.0)
215  */
217 
218  /** Whether to fill m_SFs (default=false) */
220 
221  /** Whether to ignore the input odometry and behave as if there was no
222  * odometry at all (default: false) */
224  } options;
225 
226  /** Information for data-association:
227  * \sa getLastDataAssociation
228  */
230  {
232  void clear()
233  {
234  results.clear();
235  predictions_IDs.clear();
236  newly_inserted_landmarks.clear();
237  }
238 
239  // Predictions from the map:
241  std::vector<size_t> predictions_IDs;
242 
243  /** Map from the 0-based index within the last observation and the
244  landmark 0-based index in the map (the robot-map state vector)
245  Only used for stats and so. */
246  std::map<size_t, size_t> newly_inserted_landmarks;
247 
248  // DA results:
250  };
251 
252  /** Returns a read-only reference to the information on the last
253  * data-association */
255  {
257  }
258 
259  /** Return the last partition of the sequence of sensoryframes (it is NOT a
260  * partition of the map!!)
261  * Only if options.doPartitioningExperiment = true
262  * \sa getLastPartitionLandmarks
263  */
264  void getLastPartition(std::vector<std::vector<uint32_t>>& parts)
265  {
266  parts = m_lastPartitionSet;
267  }
268 
269  /** Return the partitioning of the landmarks in clusters accoring to the
270  * last partition.
271  * Note that the same landmark may appear in different clusters (the
272  * partition is not in the space of landmarks)
273  * Only if options.doPartitioningExperiment = true
274  * \param landmarksMembership The i'th element of this vector is the set
275  * of clusters to which the i'th landmark in the map belongs to (landmark
276  * index != landmark ID !!).
277  * \sa getLastPartition
278  */
280  std::vector<std::vector<uint32_t>>& landmarksMembership) const;
281 
282  /** For testing only: returns the partitioning as
283  * "getLastPartitionLandmarks" but as if a fixed-size submaps (size K) were
284  * have been used.
285  */
287  size_t K, std::vector<std::vector<uint32_t>>& landmarksMembership);
288 
289  /** Computes the ratio of the missing information matrix elements which are
290  * ignored under a certain partitioning of the landmarks.
291  * \sa getLastPartitionLandmarks, getLastPartitionLandmarksAsIfFixedSubmaps
292  */
294  const std::vector<std::vector<uint32_t>>& landmarksMembership) const;
295 
296  /** The partitioning of the entire map is recomputed again.
297  * Only when options.doPartitioningExperiment = true.
298  * This can be used after changing the parameters of the partitioning
299  * method.
300  * After this method, you can call getLastPartitionLandmarks.
301  * \sa getLastPartitionLandmarks
302  */
304 
305  /** Provides access to the parameters of the map partitioning algorithm.
306  */
308  {
309  return &mapPartitioner.options;
310  }
311 
312  /** Save the current state of the filter (robot pose & map) to a MATLAB
313  * script which displays all the elements in 2D
314  */
316  const std::string& fil, float stdCount = 3.0f,
317  const std::string& styleLandmarks = std::string("b"),
318  const std::string& stylePath = std::string("r"),
319  const std::string& styleRobot = std::string("r")) const;
320 
321  protected:
322  /** @name Virtual methods for Kalman Filter implementation
323  @{
324  */
325 
326  /** Must return the action vector u.
327  * \param out_u The action vector which will be passed to OnTransitionModel
328  */
329  void OnGetAction(KFArray_ACT& out_u) const;
330 
331  /** Implements the transition model \f$ \hat{x}_{k|k-1} = f(
332  * \hat{x}_{k-1|k-1}, u_k ) \f$
333  * \param in_u The vector returned by OnGetAction.
334  * \param inout_x At input has \f[ \hat{x}_{k-1|k-1} \f] , at output must
335  * have \f$ \hat{x}_{k|k-1} \f$ .
336  * \param out_skip Set this to true if for some reason you want to skip the
337  * prediction step (to do not modify either the vector or the covariance).
338  * Default:false
339  */
340  void OnTransitionModel(
341  const KFArray_ACT& in_u, KFArray_VEH& inout_x,
342  bool& out_skipPrediction) const;
343 
344  /** Implements the transition Jacobian \f$ \frac{\partial f}{\partial x} \f$
345  * \param out_F Must return the Jacobian.
346  * The returned matrix must be \f$V \times V\f$ with V being either the
347  * size of the whole state vector (for non-SLAM problems) or VEH_SIZE (for
348  * SLAM problems).
349  */
350  void OnTransitionJacobian(KFMatrix_VxV& out_F) const;
351 
352  /** Implements the transition noise covariance \f$ Q_k \f$
353  * \param out_Q Must return the covariance matrix.
354  * The returned matrix must be of the same size than the jacobian from
355  * OnTransitionJacobian
356  */
357  void OnTransitionNoise(KFMatrix_VxV& out_Q) const;
358 
359  /** This is called between the KF prediction step and the update step, and
360  * the application must return the observations and, when applicable, the
361  * data association between these observations and the current map.
362  *
363  * \param out_z N vectors, each for one "observation" of length OBS_SIZE, N
364  * being the number of "observations": how many observed landmarks for a
365  * map, or just one if not applicable.
366  * \param out_data_association An empty vector or, where applicable, a
367  * vector where the i'th element corresponds to the position of the
368  * observation in the i'th row of out_z within the system state vector (in
369  * the range [0,getNumberOfLandmarksInTheMap()-1]), or -1 if it is a new map
370  * element and we want to insert it at the end of this KF iteration.
371  * \param in_S The full covariance matrix of the observation predictions
372  * (i.e. the "innovation covariance matrix"). This is a M*O x M*O matrix
373  * with M=length of "in_lm_indices_in_S".
374  * \param in_lm_indices_in_S The indices of the map landmarks (range
375  * [0,getNumberOfLandmarksInTheMap()-1]) that can be found in the matrix
376  * in_S.
377  *
378  * This method will be called just once for each complete KF iteration.
379  * \note It is assumed that the observations are independent, i.e. there
380  * are NO cross-covariances between them.
381  */
383  vector_KFArray_OBS& out_z, std::vector<int>& out_data_association,
384  const vector_KFArray_OBS& in_all_predictions, const KFMatrix& in_S,
385  const std::vector<size_t>& in_lm_indices_in_S,
386  const KFMatrix_OxO& in_R);
387 
388  void OnObservationModel(
389  const std::vector<size_t>& idx_landmarks_to_predict,
390  vector_KFArray_OBS& out_predictions) const;
391 
392  /** Implements the observation Jacobians \f$ \frac{\partial h_i}{\partial x}
393  * \f$ and (when applicable) \f$ \frac{\partial h_i}{\partial y_i} \f$.
394  * \param idx_landmark_to_predict The index of the landmark in the map
395  * whose prediction is expected as output. For non SLAM-like problems, this
396  * will be zero and the expected output is for the whole state vector.
397  * \param Hx The output Jacobian \f$ \frac{\partial h_i}{\partial x} \f$.
398  * \param Hy The output Jacobian \f$ \frac{\partial h_i}{\partial y_i}
399  * \f$.
400  */
402  const size_t& idx_landmark_to_predict, KFMatrix_OxV& Hx,
403  KFMatrix_OxF& Hy) const;
404 
405  /** Computes A=A-B, which may need to be re-implemented depending on the
406  * topology of the individual scalar components (eg, angles).
407  */
409  KFArray_OBS& A, const KFArray_OBS& B) const;
410 
411  /** Return the observation NOISE covariance matrix, that is, the model of
412  * the Gaussian additive noise of the sensor.
413  * \param out_R The noise covariance matrix. It might be non diagonal, but
414  * it'll usually be.
415  */
416  void OnGetObservationNoise(KFMatrix_OxO& out_R) const;
417 
418  /** This will be called before OnGetObservationsAndDataAssociation to allow
419  * the application to reduce the number of covariance landmark predictions
420  * to be made.
421  * For example, features which are known to be "out of sight" shouldn't be
422  * added to the output list to speed up the calculations.
423  * \param in_all_prediction_means The mean of each landmark predictions;
424  * the computation or not of the corresponding covariances is what we're
425  * trying to determined with this method.
426  * \param out_LM_indices_to_predict The list of landmark indices in the map
427  * [0,getNumberOfLandmarksInTheMap()-1] that should be predicted.
428  * \note This is not a pure virtual method, so it should be implemented
429  * only if desired. The default implementation returns a vector with all the
430  * landmarks in the map.
431  * \sa OnGetObservations, OnDataAssociation
432  */
434  const vector_KFArray_OBS& in_all_prediction_means,
435  std::vector<size_t>& out_LM_indices_to_predict) const;
436 
437  /** If applicable to the given problem, this method implements the inverse
438  * observation model needed to extend the "map" with a new "element".
439  * \param in_z The observation vector whose inverse sensor model is to be
440  * computed. This is actually one of the vector<> returned by
441  * OnGetObservations().
442  * \param out_yn The F-length vector with the inverse observation model \f$
443  * y_n=y(x,z_n) \f$.
444  * \param out_dyn_dxv The \f$F \times V\f$ Jacobian of the inv. sensor
445  * model wrt the robot pose \f$ \frac{\partial y_n}{\partial x_v} \f$.
446  * \param out_dyn_dhn The \f$F \times O\f$ Jacobian of the inv. sensor
447  * model wrt the observation vector \f$ \frac{\partial y_n}{\partial h_n}
448  * \f$.
449  *
450  * - O: OBS_SIZE
451  * - V: VEH_SIZE
452  * - F: FEAT_SIZE
453  *
454  * \note OnNewLandmarkAddedToMap will be also called after calling this
455  * method if a landmark is actually being added to the map.
456  */
458  const KFArray_OBS& in_z, KFArray_FEAT& out_yn,
459  KFMatrix_FxV& out_dyn_dxv, KFMatrix_FxO& out_dyn_dhn) const;
460 
461  /** If applicable to the given problem, do here any special handling of
462  * adding a new landmark to the map.
463  * \param in_obsIndex The index of the observation whose inverse sensor is
464  * to be computed. It corresponds to the row in in_z where the observation
465  * can be found.
466  * \param in_idxNewFeat The index that this new feature will have in the
467  * state vector (0:just after the vehicle state, 1: after that,...). Save
468  * this number so data association can be done according to these indices.
469  * \sa OnInverseObservationModel
470  */
472  const size_t in_obsIdx, const size_t in_idxNewFeat);
473 
474  /** This method is called after the prediction and after the update, to give
475  * the user an opportunity to normalize the state vector (eg, keep angles
476  * within -pi,pi range) if the application requires it.
477  */
478  void OnNormalizeStateVector();
479 
480  /** @}
481  */
482 
483  /** Set up by processActionObservation */
485 
486  /** Set up by processActionObservation */
488 
489  /** The mapping between landmark IDs and indexes in the Pkk cov. matrix: */
491  m_IDs;
492 
493  /** Used for map partitioning experiments */
495 
496  /** The sequence of all the observations and the robot path (kept for
497  * debugging, statistics,etc)
498  */
501  std::vector<std::vector<uint32_t>> m_lastPartitionSet;
502 
503  /** Last data association */
505 
506  /** Return the last odometry, as a pose increment. */
508 
509 }; // end class
510 }
511 #endif
512 
513 
mrpt::math::CMatrixFixedNumeric< double, OBS_SIZE, VEH_SIZE > KFMatrix_OxV
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)...
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.
void OnObservationJacobians(const size_t &idx_landmark_to_predict, KFMatrix_OxV &Hx, KFMatrix_OxF &Hy) const
Implements the observation Jacobians and (when applicable) .
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.
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...
Definition: CSimpleMap.h:33
void reconsiderPartitionsNow()
The partitioning of the entire map is recomputed again.
mrpt::math::CArrayNumeric< double, VEH_SIZE > KFArray_VEH
GLdouble GLdouble GLdouble GLdouble q
Definition: glext.h:3721
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.
void OnNormalizeStateVector()
This method is called after the prediction and after the update, to give the user an opportunity to n...
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 OnPreComputingPredictions(const vector_KFArray_OBS &in_all_prediction_means, std::vector< size_t > &out_LM_indices_to_predict) const
This will be called before OnGetObservationsAndDataAssociation to allow the application to reduce the...
mrpt::math::CMatrixTemplateNumeric< double > KFMatrix
Column vector, like Eigen::MatrixX*, but automatically initialized to zeros since construction...
Definition: eigen_frwds.h:44
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 OnGetAction(KFArray_ACT &out_u) const
Must return the action vector u.
void OnTransitionJacobian(KFMatrix_VxV &out_F) const
Implements the transition Jacobian .
mrpt::poses::CPose3DQuat getCurrentRobotPoseMean() const
Get the current robot pose mean, as a 3D+quaternion pose.
TDataAssocInfo m_last_data_association
Last data association.
mrpt::containers::bimap< mrpt::maps::CLandmark::TLandmarkID, unsigned int > m_IDs
The mapping between landmark IDs and indexes in the Pkk cov.
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...
mrpt::math::CMatrixTemplateNumeric< kftype > Y_pred_means
Declares a class that represents a Probability Density function (PDF) of a 3D pose using a quaternion...
mrpt::math::CArrayNumeric< double, FEAT_SIZE > KFArray_FEAT
CIncrementalMapPartitioner::TOptions * mapPartitionOptions()
Provides access to the parameters of the map partitioning algorithm.
mrpt::math::CMatrixFixedNumeric< double, VEH_SIZE, VEH_SIZE > KFMatrix_VxV
void OnTransitionNoise(KFMatrix_VxV &out_Q) const
Implements the transition noise covariance .
This class allows loading and storing values and vectors of different types from a configuration text...
mrpt::math::CArrayNumeric< double, OBS_SIZE > KFArray_OBS
int partitioningMethod
Applicable only if "doPartitioningExperiment=true".
TDataAssociationMetric
Different metrics for data association, used in mrpt::slam::data_association For a comparison of both...
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 scala...
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).
Definition: CPose3DQuat.h:46
mrpt::math::CMatrixFixedNumeric< double, OBS_SIZE, OBS_SIZE > KFMatrix_OxO
mrpt::maps::CSimpleMap m_SFs
The sequence of all the observations and the robot path (kept for debugging, statistics,etc)
GLsizei const GLchar ** string
Definition: glext.h:4101
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::aligned_std_vector< KFArray_OBS > vector_KFArray_OBS
void loadOptions(const mrpt::config::CConfigFileBase &ini)
Load options from a ini-like file/text.
mrpt::math::CArrayNumeric< double, ACT_SIZE > KFArray_ACT
void OnGetObservationNoise(KFMatrix_OxO &out_R) const
Return the observation NOISE covariance matrix, that is, the model of the Gaussian additive noise of ...
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)
This is called between the KF prediction step and the update step, and the application must return th...
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.
void OnObservationModel(const std::vector< size_t > &idx_landmarks_to_predict, vector_KFArray_OBS &out_predictions) const
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 &section) override
This method load the options from a ".ini"-like file or memory-stored string list.
mrpt::math::CMatrixFixedNumeric< double, FEAT_SIZE, VEH_SIZE > KFMatrix_FxV
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 OnTransitionModel(const KFArray_ACT &in_u, KFArray_VEH &inout_x, bool &out_skipPrediction) const
Implements the transition model .
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
Definition: glext.h:4082
mrpt::math::CMatrixFixedNumeric< double, OBS_SIZE, FEAT_SIZE > KFMatrix_OxF
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 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 ex...
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...
The results from mrpt::slam::data_association.
Lightweight 3D point.
mrpt::math::CMatrixTemplateNumeric< kftype > Y_pred_covs
mrpt::obs::CActionCollection::Ptr m_action
Set up by processActionObservation.
TDataAssociationMethod
Different algorithms for data association, used in mrpt::slam::data_association.
virtual ~CRangeBearingKFSLAM()
Destructor:
double data_assoc_IC_chi2_thres
Threshold in [0,1] for the chi2square test for individual compatibility between predictions and obser...
mrpt::math::CMatrixFixedNumeric< double, FEAT_SIZE, OBS_SIZE > KFMatrix_FxO
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::CVectorFloat stds_Q_no_odo
A 7-length vector with the std.



Page generated by Doxygen 1.8.14 for MRPT 1.9.9 Git: 7d5e6d718 Fri Aug 24 01:51:28 2018 +0200 at lun nov 2 08:35:50 CET 2020