MRPT  2.0.1
test.cpp
Go to the documentation of this file.
1 /* +------------------------------------------------------------------------+
2  | Mobile Robot Programming Toolkit (MRPT) |
3  | https://www.mrpt.org/ |
4  | |
5  | Copyright (c) 2005-2020, Individual contributors, see AUTHORS file |
6  | See: https://www.mrpt.org/Authors - All rights reserved. |
7  | Released under BSD License. See: https://www.mrpt.org/License |
8  +------------------------------------------------------------------------+ */
9 // ------------------------------------------------------
10 // Refer to the description in the wiki:
11 // https://www.mrpt.org/Kalman_Filters
12 // ------------------------------------------------------
13 
16 
19 #include <mrpt/math/wrap2pi.h>
21 #include <mrpt/obs/CSensoryFrame.h>
22 #include <mrpt/random.h>
23 #include <mrpt/system/os.h>
24 #include <iostream>
25 
26 using namespace mrpt;
27 using namespace mrpt::bayes;
28 using namespace mrpt::gui;
29 using namespace mrpt::math;
30 using namespace mrpt::obs;
31 using namespace mrpt::random;
32 using namespace std;
33 
34 #define BEARING_SENSOR_NOISE_STD DEG2RAD(15.0f)
35 #define RANGE_SENSOR_NOISE_STD 0.3f
36 #define DELTA_TIME 0.1f
37 
38 #define VEHICLE_INITIAL_X 4.0f
39 #define VEHICLE_INITIAL_Y 4.0f
40 #define VEHICLE_INITIAL_V 1.0f
41 #define VEHICLE_INITIAL_W DEG2RAD(20.0f)
42 
43 #define TRANSITION_MODEL_STD_XY 0.03f
44 #define TRANSITION_MODEL_STD_VXY 0.20f
45 
46 #define NUM_PARTICLES 2000
47 
48 // Uncomment to save text files with grount truth vs. estimated states
49 //#define SAVE_GT_LOGS
50 
51 // ------------------------------------------------------
52 // Implementation of the system models as a EKF
53 // ------------------------------------------------------
55  4 /* x y vx vy*/, 2 /* range yaw */, 0, 1 /* Atime */>
56 // <size_t VEH_SIZE, size_t OBS_SIZE, size_t FEAT_SIZE, size_t
57 // ACT_SIZE, size typename kftype = double>
58 {
59  public:
60  CRangeBearing();
61  ~CRangeBearing() override;
62 
63  void doProcess(
64  double DeltaTime, double observationRange, double observationBearing);
65 
66  void getState(KFVector& xkk, KFMatrix& pkk)
67  {
68  xkk = m_xkk;
69  pkk = m_pkk;
70  }
71 
72  protected:
73  float m_obsBearing, m_obsRange;
74  float m_deltaTime;
75 
76  /** @name Virtual methods for Kalman Filter implementation
77  @{
78  */
79 
80  /** Must return the action vector u.
81  * \param out_u The action vector which will be passed to OnTransitionModel
82  */
83  void OnGetAction(KFArray_ACT& out_u) const override;
84 
85  /** Implements the transition model \f$ \hat{x}_{k|k-1} = f(
86  * \hat{x}_{k-1|k-1}, u_k ) \f$
87  * \param in_u The vector returned by OnGetAction.
88  * \param inout_x At input has \f$ \hat{x}_{k-1|k-1} \f$, at output must
89  * have \f$ \hat{x}_{k|k-1} \f$.
90  * \param out_skip Set this to true if for some reason you want to skip the
91  * prediction step (to do not modify either the vector or the covariance).
92  * Default:false
93  */
94  void OnTransitionModel(
95  const KFArray_ACT& in_u, KFArray_VEH& inout_x,
96  bool& out_skipPrediction) const override;
97 
98  /** Implements the transition Jacobian \f$ \frac{\partial f}{\partial x} \f$
99  * \param out_F Must return the Jacobian.
100  * The returned matrix must be \f$N \times N\f$ with N being either the
101  * size of the whole state vector or get_vehicle_size().
102  */
103  void OnTransitionJacobian(KFMatrix_VxV& out_F) const override;
104 
105  /** Implements the transition noise covariance \f$ Q_k \f$
106  * \param out_Q Must return the covariance matrix.
107  * The returned matrix must be of the same size than the jacobian from
108  * OnTransitionJacobian
109  */
110  void OnTransitionNoise(KFMatrix_VxV& out_Q) const override;
111 
112  /** Return the observation NOISE covariance matrix, that is, the model of
113  * the Gaussian additive noise of the sensor.
114  * \param out_R The noise covariance matrix. It might be non diagonal, but
115  * it'll usually be.
116  * \note Upon call, it can be assumed that the previous contents of out_R
117  * are all zeros.
118  */
119  void OnGetObservationNoise(KFMatrix_OxO& out_R) const override;
120 
121  /** This is called between the KF prediction step and the update step, and
122  * the application must return the observations and, when applicable, the
123  * data association between these observations and the current map.
124  *
125  * \param out_z N vectors, each for one "observation" of length OBS_SIZE, N
126  * being the number of "observations": how many observed landmarks for a
127  * map, or just one if not applicable.
128  * \param out_data_association An empty vector or, where applicable, a
129  * vector where the i'th element corresponds to the position of the
130  * observation in the i'th row of out_z within the system state vector (in
131  * the range [0,getNumberOfLandmarksInTheMap()-1]), or -1 if it is a new map
132  * element and we want to insert it at the end of this KF iteration.
133  * \param in_all_predictions A vector with the prediction of ALL the
134  * landmarks in the map. Note that, in contrast, in_S only comprises a
135  * subset of all the landmarks.
136  * \param in_S The full covariance matrix of the observation predictions
137  * (i.e. the "innovation covariance matrix"). This is a M·O x M·O matrix
138  * with M=length of "in_lm_indices_in_S".
139  * \param in_lm_indices_in_S The indices of the map landmarks (range
140  * [0,getNumberOfLandmarksInTheMap()-1]) that can be found in the matrix
141  * in_S.
142  *
143  * This method will be called just once for each complete KF iteration.
144  * \note It is assumed that the observations are independent, i.e. there
145  * are NO cross-covariances between them.
146  */
147  void OnGetObservationsAndDataAssociation(
148  vector_KFArray_OBS& out_z, std::vector<int>& out_data_association,
149  const vector_KFArray_OBS& in_all_predictions, const KFMatrix& in_S,
150  const std::vector<size_t>& in_lm_indices_in_S,
151  const KFMatrix_OxO& in_R) override;
152 
153  /** Implements the observation prediction \f$ h_i(x) \f$.
154  * \param idx_landmark_to_predict The indices of the landmarks in the map
155  * whose predictions are expected as output. For non SLAM-like problems,
156  * this input value is undefined and the application should just generate
157  * one observation for the given problem.
158  * \param out_predictions The predicted observations.
159  */
160  void OnObservationModel(
161  const std::vector<size_t>& idx_landmarks_to_predict,
162  vector_KFArray_OBS& out_predictions) const override;
163 
164  /** Implements the observation Jacobians \f$ \frac{\partial h_i}{\partial x}
165  * \f$ and (when applicable) \f$ \frac{\partial h_i}{\partial y_i} \f$.
166  * \param idx_landmark_to_predict The index of the landmark in the map
167  * whose prediction is expected as output. For non SLAM-like problems, this
168  * will be zero and the expected output is for the whole state vector.
169  * \param Hx The output Jacobian \f$ \frac{\partial h_i}{\partial x} \f$.
170  * \param Hy The output Jacobian \f$ \frac{\partial h_i}{\partial y_i}
171  * \f$.
172  */
173  void OnObservationJacobians(
174  size_t idx_landmark_to_predict, KFMatrix_OxV& Hx,
175  KFMatrix_OxF& Hy) const override;
176 
177  /** Computes A=A-B, which may need to be re-implemented depending on the
178  * topology of the individual scalar components (eg, angles).
179  */
180  void OnSubstractObservationVectors(
181  KFArray_OBS& A, const KFArray_OBS& B) const override;
182 
183  /** @}
184  */
185 };
186 
187 // ---------------------------------------------------------------
188 // Implementation of the system models as a Particle Filter
189 // ---------------------------------------------------------------
191 {
192  float x, y, vx, vy; // Vehicle state (position & velocities)
193 };
194 
196  : public mrpt::bayes::CParticleFilterData<CParticleVehicleData>,
198  CRangeBearingParticleFilter,
199  mrpt::bayes::CParticleFilterData<CParticleVehicleData>::CParticleList>
200 {
201  public:
202  /** Update the m_particles, predicting the posterior of robot pose and map
203  * after a movement command.
204  * This method has additional configuration parameters in "options".
205  * Performs the update stage of the RBPF, using the sensed Sensorial Frame:
206  *
207  * \param action This is a pointer to CActionCollection, containing the
208  * pose change the robot has been commanded.
209  * \param observation This must be a pointer to a CSensoryFrame object,
210  * with robot sensed observations.
211  *
212  * \sa options
213  */
214  void prediction_and_update_pfStandardProposal(
215  const mrpt::obs::CActionCollection* action,
216  const mrpt::obs::CSensoryFrame* observation,
218  override;
219 
220  void initializeParticles(size_t numParticles);
221 
222  /** Computes the average velocity & position
223  */
224  void getMean(float& x, float& y, float& vx, float& vy);
225 };
226 
227 // ------------------------------------------------------
228 // TestBayesianTracking
229 // ------------------------------------------------------
231 {
233 
234  CDisplayWindowPlots winEKF("Tracking - Extended Kalman Filter", 450, 400);
235  CDisplayWindowPlots winPF("Tracking - Particle Filter", 450, 400);
236 
237  winEKF.setPos(10, 10);
238  winPF.setPos(480, 10);
239 
240  winEKF.axis(-2, 20, -10, 10);
241  winEKF.axis_equal();
242  winPF.axis(-2, 20, -10, 10);
243  winPF.axis_equal();
244 
245  // Create EKF
246  // ----------------------
247  CRangeBearing EKF;
249 
251  EKF.KF_options.enable_profiler = true;
252 
253  // Create PF
254  // ----------------------
256  PF_options.adaptiveSampleSize = false;
259 
260  CRangeBearingParticleFilter particles;
262  CParticleFilter PF;
263  PF.m_options = PF_options;
264 
265 #ifdef SAVE_GT_LOGS
266  CFileOutputStream fo_log_ekf("log_GT_vs_EKF.txt");
267  fo_log_ekf.printf(
268  "%%%% GT_X GT_Y EKF_MEAN_X EKF_MEAN_Y EKF_STD_X EKF_STD_Y\n");
269 #endif
270 
271  // Init. simulation:
272  // -------------------------
273  float x = VEHICLE_INITIAL_X, y = VEHICLE_INITIAL_Y, phi = -180.0_deg,
275  float t = 0;
276 
277  while (winEKF.isOpen() && winPF.isOpen() && !mrpt::system::os::kbhit())
278  {
279  // Update vehicle:
280  x += v * DELTA_TIME * (cos(phi) - sin(phi));
281  y += v * DELTA_TIME * (sin(phi) + cos(phi));
282  phi += w * DELTA_TIME;
283 
284  v += 1.0f * DELTA_TIME * cos(t);
285  w -= 0.1f * DELTA_TIME * sin(t);
286 
287  // Simulate noisy observation:
288  float realBearing = atan2(y, x);
289  float obsBearing =
290  realBearing + BEARING_SENSOR_NOISE_STD *
292  printf(
293  "Real/Simulated bearing: %.03f / %.03f deg\n", RAD2DEG(realBearing),
294  RAD2DEG(obsBearing));
295 
296  float realRange = sqrt(square(x) + square(y));
297  float obsRange =
298  max(0.0, realRange +
300  getRandomGenerator().drawGaussian1D_normalized());
301  printf("Real/Simulated range: %.03f / %.03f \n", realRange, obsRange);
302 
303  // Process with EKF:
304  EKF.doProcess(DELTA_TIME, obsRange, obsBearing);
305 
306  // Process with PF:
307  CSensoryFrame SF;
308  CObservationBearingRange::Ptr obsRangeBear =
309  CObservationBearingRange::Create();
310  obsRangeBear->sensedData.resize(1);
311  obsRangeBear->sensedData[0].range = obsRange;
312  obsRangeBear->sensedData[0].yaw = obsBearing;
313  SF.insert(obsRangeBear); // memory freed by SF.
314 
315  EKF.getProfiler().enter("PF:complete_step");
316  PF.executeOn(particles, nullptr, &SF); // Process in the PF
317  EKF.getProfiler().leave("PF:complete_step");
318 
319  // Show EKF state:
320  CRangeBearing::KFVector EKF_xkk;
321  CRangeBearing::KFMatrix EKF_pkk;
322 
323  EKF.getState(EKF_xkk, EKF_pkk);
324 
325  printf(
326  "Real: x:%.03f y=%.03f heading=%.03f v=%.03f w=%.03f\n", x, y, phi,
327  v, w);
328  cout << "EKF: " << EKF_xkk << endl;
329 
330  // Show PF state:
331  cout << "Particle filter ESS: " << particles.ESS() << endl;
332 
333  // Draw EKF state:
334  CRangeBearing::KFMatrix COVXY(2, 2);
335  COVXY(0, 0) = EKF_pkk(0, 0);
336  COVXY(1, 1) = EKF_pkk(1, 1);
337  COVXY(0, 1) = COVXY(1, 0) = EKF_pkk(0, 1);
338 
339  winEKF.plotEllipse(
340  EKF_xkk[0], EKF_xkk[1], COVXY, 3, "b-2", "ellipse_EKF");
341 
342 // Save GT vs EKF state:
343 #ifdef SAVE_GT_LOGS
344  // %% GT_X GT_Y EKF_MEAN_X EKF_MEAN_Y EKF_STD_X EKF_STD_Y:
345  fo_log_ekf.printf(
346  "%f %f %f %f %f %f\n", x, y, // Real (GT)
347  EKF_xkk[0], EKF_xkk[1], std::sqrt(EKF_pkk(0, 0)),
348  std::sqrt(EKF_pkk(1, 1)));
349 #endif
350 
351  // Draw the velocity vector:
352  vector<float> vx(2), vy(2);
353  vx[0] = EKF_xkk[0];
354  vx[1] = vx[0] + EKF_xkk[2] * 1;
355  vy[0] = EKF_xkk[1];
356  vy[1] = vy[0] + EKF_xkk[3] * 1;
357  winEKF.plot(vx, vy, "g-4", "velocityEKF");
358 
359  // Draw PF state:
360  {
361  size_t i, N = particles.m_particles.size();
362  vector<float> parts_x(N), parts_y(N);
363  for (i = 0; i < N; i++)
364  {
365  parts_x[i] = particles.m_particles[i].d->x;
366  parts_y[i] = particles.m_particles[i].d->y;
367  }
368 
369  winPF.plot(parts_x, parts_y, "b.2", "particles");
370 
371  // Draw PF velocities:
372  float avrg_x, avrg_y, avrg_vx, avrg_vy;
373 
374  particles.getMean(avrg_x, avrg_y, avrg_vx, avrg_vy);
375 
376  vector<float> vx(2), vy(2);
377  vx[0] = avrg_x;
378  vx[1] = vx[0] + avrg_vx * 1;
379  vy[0] = avrg_y;
380  vy[1] = vy[0] + avrg_vy * 1;
381  winPF.plot(vx, vy, "g-4", "velocityPF");
382  }
383 
384  // Draw GT:
385  winEKF.plot(vector<float>(1, x), vector<float>(1, y), "k.8", "plot_GT");
386  winPF.plot(vector<float>(1, x), vector<float>(1, y), "k.8", "plot_GT");
387 
388  // Draw noisy observations:
389  vector<float> obs_x(2), obs_y(2);
390  obs_x[0] = obs_y[0] = 0;
391  obs_x[1] = obsRange * cos(obsBearing);
392  obs_y[1] = obsRange * sin(obsBearing);
393 
394  winEKF.plot(obs_x, obs_y, "r", "plot_obs_ray");
395  winPF.plot(obs_x, obs_y, "r", "plot_obs_ray");
396 
397  // Delay:
398  std::this_thread::sleep_for(
399  std::chrono::milliseconds((int)(DELTA_TIME * 1000)));
400  t += DELTA_TIME;
401  }
402 }
403 
404 // ------------------------------------------------------
405 // MAIN
406 // ------------------------------------------------------
407 int main()
408 {
409  try
410  {
412  return 0;
413  }
414  catch (const std::exception& e)
415  {
416  std::cerr << "MRPT error: " << mrpt::exception_to_str(e) << std::endl;
417  return -1;
418  }
419  catch (...)
420  {
421  printf("Untyped exception!!");
422  return -1;
423  }
424 }
425 
427 {
428  // KF_options.method = kfEKFNaive;
429  KF_options.method = kfEKFAlaDavison;
430 
431  // INIT KF STATE
432  m_xkk.resize(4); // State: (x,y,heading,v,w)
433  m_xkk[0] = VEHICLE_INITIAL_X;
434  m_xkk[1] = VEHICLE_INITIAL_Y;
435  m_xkk[2] = -VEHICLE_INITIAL_V;
436  m_xkk[3] = 0;
437 
438  // Initial cov: Large uncertainty
439  m_pkk.setIdentity(4);
440  m_pkk(0, 0) = m_pkk(1, 1) = square(5.0f);
441  m_pkk(2, 2) = m_pkk(3, 3) = square(1.0f);
442 }
443 
446  double DeltaTime, double observationRange, double observationBearing)
447 {
448  m_deltaTime = (float)DeltaTime;
449  m_obsBearing = (float)observationBearing;
450  m_obsRange = (float)observationRange;
451 
452  runOneKalmanIteration();
453 }
454 
455 /** Must return the action vector u.
456  * \param out_u The action vector which will be passed to OnTransitionModel
457  */
458 void CRangeBearing::OnGetAction(KFArray_ACT& u) const { u[0] = m_deltaTime; }
459 /** Implements the transition model \f$ \hat{x}_{k|k-1} = f( \hat{x}_{k-1|k-1},
460  * u_k ) \f$
461  * \param in_u The vector returned by OnGetAction.
462  * \param inout_x At input has \f$ \hat{x}_{k-1|k-1} \f$, at output must have
463  * \f$ \hat{x}_{k|k-1} \f$.
464  * \param out_skip Set this to true if for some reason you want to skip the
465  * prediction step (to do not modify either the vector or the covariance).
466  * Default:false
467  */
469  const KFArray_ACT& in_u, KFArray_VEH& inout_x,
470  bool& out_skipPrediction) const
471 {
472  // in_u[0] : Delta time
473  // in_out_x: [0]:x [1]:y [2]:vx [3]: vy
474  inout_x[0] += in_u[0] * inout_x[2];
475  inout_x[1] += in_u[0] * inout_x[3];
476 }
477 
478 /** Implements the transition Jacobian \f$ \frac{\partial f}{\partial x} \f$
479  * \param out_F Must return the Jacobian.
480  * The returned matrix must be \f$N \times N\f$ with N being either the size
481  * of the whole state vector or get_vehicle_size().
482  */
483 void CRangeBearing::OnTransitionJacobian(KFMatrix_VxV& F) const
484 {
485  F.setIdentity();
486 
487  F(0, 2) = m_deltaTime;
488  F(1, 3) = m_deltaTime;
489 }
490 
491 /** Implements the transition noise covariance \f$ Q_k \f$
492  * \param out_Q Must return the covariance matrix.
493  * The returned matrix must be of the same size than the jacobian from
494  * OnTransitionJacobian
495  */
496 void CRangeBearing::OnTransitionNoise(KFMatrix_VxV& Q) const
497 {
498  Q(0, 0) = Q(1, 1) = square(TRANSITION_MODEL_STD_XY);
499  Q(2, 2) = Q(3, 3) = square(TRANSITION_MODEL_STD_VXY);
500 }
501 
502 /** Return the observation NOISE covariance matrix, that is, the model of the
503  * Gaussian additive noise of the sensor.
504  * \param out_R The noise covariance matrix. It might be non diagonal, but it'll
505  * usually be.
506  * \note Upon call, it can be assumed that the previous contents of out_R are
507  * all zeros.
508  */
509 void CRangeBearing::OnGetObservationNoise(KFMatrix_OxO& R) const
510 {
513 }
514 
516  vector_KFArray_OBS& out_z, std::vector<int>& out_data_association,
517  const vector_KFArray_OBS& in_all_predictions, const KFMatrix& in_S,
518  const std::vector<size_t>& in_lm_indices_in_S, const KFMatrix_OxO& in_R)
519 {
520  out_z.resize(1);
521  out_z[0][0] = m_obsBearing;
522  out_z[0][1] = m_obsRange;
523 
524  out_data_association.clear(); // Not used
525 }
526 
527 /** Implements the observation prediction \f$ h_i(x) \f$.
528  * \param idx_landmark_to_predict The indices of the landmarks in the map whose
529  * predictions are expected as output. For non SLAM-like problems, this input
530  * value is undefined and the application should just generate one observation
531  * for the given problem.
532  * \param out_predictions The predicted observations.
533  */
535  const std::vector<size_t>& idx_landmarks_to_predict,
536  vector_KFArray_OBS& out_predictions) const
537 {
538  // predicted bearing:
539  kftype x = m_xkk[0];
540  kftype y = m_xkk[1];
541 
542  kftype h_bear = atan2(y, x);
543  kftype h_range = sqrt(square(x) + square(y));
544 
545  // idx_landmarks_to_predict is ignored in NON-SLAM problems
546  out_predictions.resize(1);
547  out_predictions[0][0] = h_bear;
548  out_predictions[0][1] = h_range;
549 }
550 
551 /** Implements the observation Jacobians \f$ \frac{\partial h_i}{\partial x} \f$
552  * and (when applicable) \f$ \frac{\partial h_i}{\partial y_i} \f$.
553  * \param idx_landmark_to_predict The index of the landmark in the map whose
554  * prediction is expected as output. For non SLAM-like problems, this will be
555  * zero and the expected output is for the whole state vector.
556  * \param Hx The output Jacobian \f$ \frac{\partial h_i}{\partial x} \f$.
557  * \param Hy The output Jacobian \f$ \frac{\partial h_i}{\partial y_i} \f$.
558  */
560  size_t idx_landmark_to_predict, KFMatrix_OxV& Hx, KFMatrix_OxF& Hy) const
561 {
562  // predicted bearing:
563  kftype x = m_xkk[0];
564  kftype y = m_xkk[1];
565 
566  Hx.setZero();
567  Hx(0, 0) = -y / (square(x) + square(y));
568  Hx(0, 1) = 1 / (x * (1 + square(y / x)));
569 
570  Hx(1, 0) = x / sqrt(square(x) + square(y));
571  Hx(1, 1) = y / sqrt(square(x) + square(y));
572 
573  // Hy: Not used
574 }
575 
576 /** Computes A=A-B, which may need to be re-implemented depending on the
577  * topology of the individual scalar components (eg, angles).
578  */
580  KFArray_OBS& A, const KFArray_OBS& B) const
581 {
582  A -= B;
583  math::wrapToPiInPlace(A[0]); // The angular component
584 }
585 
586 /** Update the m_particles, predicting the posterior of robot pose and map after
587  * a movement command.
588  * This method has additional configuration parameters in "options".
589  * Performs the update stage of the RBPF, using the sensed Sensorial Frame:
590  *
591  * \param action This is a pointer to CActionCollection, containing the pose
592  * change the robot has been commanded.
593  * \param observation This must be a pointer to a CSensoryFrame object, with
594  * robot sensed observations.
595  *
596  * \sa options
597  */
599  const mrpt::obs::CActionCollection* action,
600  const mrpt::obs::CSensoryFrame* observation,
602 {
603  size_t i, N = m_particles.size();
604 
605  // Transition model:
606  for (i = 0; i < N; i++)
607  {
608  m_particles[i].d->x +=
609  DELTA_TIME * m_particles[i].d->vx +
612  m_particles[i].d->y +=
613  DELTA_TIME * m_particles[i].d->vy +
616 
617  m_particles[i].d->vx +=
620  m_particles[i].d->vy +=
623  }
624 
627  ASSERT_(obs);
628  ASSERT_(obs->sensedData.size() == 1);
629  float obsRange = obs->sensedData[0].range;
630  float obsBearing = obs->sensedData[0].yaw;
631 
632  // Update weights
633  for (i = 0; i < N; i++)
634  {
635  float predicted_range =
636  sqrt(square(m_particles[i].d->x) + square(m_particles[i].d->y));
637  float predicted_bearing =
638  atan2(m_particles[i].d->y, m_particles[i].d->x);
639 
640  m_particles[i].log_w +=
641  log(math::normalPDF(
642  predicted_range - obsRange, 0, RANGE_SENSOR_NOISE_STD)) +
643  log(math::normalPDF(
644  math::wrapToPi(predicted_bearing - obsBearing), 0,
646  }
647 
648  // Resample is automatically performed by CParticleFilter when required.
649 }
650 
652 {
653  clearParticles();
654  m_particles.resize(M);
655  for (CParticleList::iterator it = m_particles.begin();
656  it != m_particles.end(); it++)
657  it->d.reset(new CParticleVehicleData());
658 
659  for (CParticleList::iterator it = m_particles.begin();
660  it != m_particles.end(); it++)
661  {
662  (*it).d->x = getRandomGenerator().drawUniform(
663  VEHICLE_INITIAL_X - 2.0f, VEHICLE_INITIAL_X + 2.0f);
664  (*it).d->y = getRandomGenerator().drawUniform(
665  VEHICLE_INITIAL_Y - 2.0f, VEHICLE_INITIAL_Y + 2.0f);
666 
667  (*it).d->vx =
669  (*it).d->vy = getRandomGenerator().drawGaussian1D(0, 0.2f);
670 
671  it->log_w = 0;
672  }
673 }
674 
675 /** Computes the average velocity
676  */
678  float& x, float& y, float& vx, float& vy)
679 {
680  double sumW = 0;
681  for (CParticleList::iterator it = m_particles.begin();
682  it != m_particles.end(); it++)
683  sumW += exp(it->log_w);
684 
685  ASSERT_(sumW > 0);
686 
687  x = y = vx = vy = 0;
688 
689  for (CParticleList::iterator it = m_particles.begin();
690  it != m_particles.end(); it++)
691  {
692  const double w = exp(it->log_w) / sumW;
693 
694  x += (float)w * (*it).d->x;
695  y += (float)w * (*it).d->y;
696  vx += (float)w * (*it).d->vx;
697  vy += (float)w * (*it).d->vy;
698  }
699 }
void prediction_and_update_pfStandardProposal(const mrpt::obs::CActionCollection *action, const mrpt::obs::CSensoryFrame *observation, const bayes::CParticleFilter::TParticleFilterOptions &PF_options) override
Update the m_particles, predicting the posterior of robot pose and map after a movement command...
A namespace of pseudo-random numbers generators of diferent distributions.
void insert(const CObservation::Ptr &obs)
Inserts a new observation to the list: The pointer to the objects is copied, thus DO NOT delete the p...
void OnTransitionJacobian(KFMatrix_VxV &out_F) const override
Implements the transition Jacobian .
Create a GUI window and display plots with MATLAB-like interfaces and commands.
#define RANGE_SENSOR_NOISE_STD
CParticleList m_particles
The array of particles.
void OnTransitionModel(const KFArray_ACT &in_u, KFArray_VEH &inout_x, bool &out_skipPrediction) const override
Implements the transition model .
void TestBayesianTracking()
The namespace for Bayesian filtering algorithm: different particle filters and Kalman filter algorith...
bool enable_profiler
If enabled (default=false), detailed timing information will be dumped to the console thru a CTimerLo...
void randomize(const uint32_t seed)
Initialize the PRNG from the given random seed.
double ESS() const override
Returns the normalized ESS (Estimated Sample Size), in the range [0,1].
void OnGetObservationsAndDataAssociation(vector_KFArray_OBS &out_z, std::vector< int > &out_data_association, const vector_KFArray_OBS &in_all_predictions, const KFMatrix &in_S, const std::vector< size_t > &in_lm_indices_in_S, const KFMatrix_OxO &in_R) override
This is called between the KF prediction step and the update step, and the application must return th...
#define NUM_PARTICLES
T::Ptr getObservationByClass(size_t ith=0) const
Returns the i&#39;th observation of a given class (or of a descendant class), or nullptr if there is no s...
STL namespace.
void OnObservationJacobians(size_t idx_landmark_to_predict, KFMatrix_OxV &Hx, KFMatrix_OxF &Hy) const override
Implements the observation Jacobians and (when applicable) .
#define VEHICLE_INITIAL_Y
Declares a class for storing a collection of robot actions.
void getState(KFVector &xkk, KFMatrix &pkk)
#define ASSERT_(f)
Defines an assertion mechanism.
Definition: exceptions.h:120
return_t drawUniform(const double Min, const double Max)
Generate a uniformly distributed pseudo-random number using the MT19937 algorithm, scaled to the selected range.
void wrapToPiInPlace(T &a)
Modifies the given angle to translate it into the ]-pi,pi] range.
Definition: wrap2pi.h:61
This base provides a set of functions for maths stuff.
TParticleResamplingAlgorithm resamplingMethod
The resampling algorithm to use (default=prMultinomial).
void initializeParticles(size_t numParticles)
mrpt::system::VerbosityLevel & verbosity_level
TKF_options KF_options
Generic options for the Kalman Filter algorithm itself.
#define BEARING_SENSOR_NOISE_STD
Virtual base for Kalman Filter (EKF,IEKF,UKF) implementations.
This namespace contains representation of robot actions and observations.
Declares a class for storing a "sensory frame", a set of "observations" taken by the robot approximat...
Definition: CSensoryFrame.h:51
void OnObservationModel(const std::vector< size_t > &idx_landmarks_to_predict, vector_KFArray_OBS &out_predictions) const override
Implements the observation prediction .
This class acts as a common interface to the different interfaces (see CParticleFilter::TParticleFilt...
return_t drawGaussian1D(const double mean, const double std)
Generate a normally distributed pseudo-random number.
#define VEHICLE_INITIAL_V
T wrapToPi(T a)
Modifies the given angle to translate it into the ]-pi,pi] range.
Definition: wrap2pi.h:50
This template class declares the array of particles and its internal data, managing some memory-relat...
#define DELTA_TIME
return_t square(const num_t x)
Inline function for the square of a number.
void OnTransitionNoise(KFMatrix_VxV &out_Q) const override
Implements the transition noise covariance .
void enter(const std::string_view &func_name) noexcept
Start of a named section.
This is the global namespace for all Mobile Robot Programming Toolkit (MRPT) libraries.
void executeOn(CParticleFilterCapable &obj, const mrpt::obs::CActionCollection *action, const mrpt::obs::CSensoryFrame *observation, TParticleFilterStats *stats=nullptr)
Executes a complete prediction + update step of the selected particle filtering algorithm.
#define TRANSITION_MODEL_STD_XY
void getMean(float &x, float &y, float &vx, float &vy)
Computes the average velocity & position.
const float R
#define VEHICLE_INITIAL_X
The configuration of a particle filter.
void OnGetAction(KFArray_ACT &out_u) const override
Must return the action vector u.
constexpr double RAD2DEG(const double x)
Radians to degrees.
This observation represents a number of range-bearing value pairs, each one for a detected landmark...
bool kbhit() noexcept
An OS-independent version of kbhit, which returns true if a key has been pushed.
Definition: os.cpp:392
void OnGetObservationNoise(KFMatrix_OxO &out_R) const override
Return the observation NOISE covariance matrix, that is, the model of the Gaussian additive noise of ...
double leave(const std::string_view &func_name) noexcept
End of a named section.
std::string exception_to_str(const std::exception &e)
Builds a nice textual representation of a nested exception, which if generated using MRPT macros (THR...
Definition: exceptions.cpp:59
mrpt::io::CFileOutputStream CFileOutputStream
Classes for creating GUI windows for 2D and 3D visualization.
Definition: about_box.h:14
TKFMethod method
The method to employ (default: kfEKFNaive)
void doProcess(double DeltaTime, double observationRange, double observationBearing)
void OnSubstractObservationVectors(KFArray_OBS &A, const KFArray_OBS &B) const override
Computes A=A-B, which may need to be re-implemented depending on the topology of the individual scala...
CParticleFilter::TParticleFilterOptions m_options
The options to be used in the PF, must be set before executing any step of the particle filter...
CRandomGenerator & getRandomGenerator()
A static instance of a CRandomGenerator class, for use in single-thread applications.
double normalPDF(double x, double mu, double std)
Evaluates the univariate normal (Gaussian) distribution at a given point "x".
Definition: math.cpp:33
mrpt::system::CTimeLogger & getProfiler()
#define VEHICLE_INITIAL_W
TParticleFilterAlgorithm PF_algorithm
The PF algorithm to use (default=pfStandardProposal) See TParticleFilterAlgorithm for the possibiliti...
#define TRANSITION_MODEL_STD_VXY
A curiously recurring template pattern (CRTP) approach to providing the basic functionality of any CP...
bool adaptiveSampleSize
A flag that indicates whether the CParticleFilterCapable object should perform adative sample size (d...
double drawGaussian1D_normalized()
Generate a normalized (mean=0, std=1) normally distributed sample.



Page generated by Doxygen 1.8.14 for MRPT 2.0.1 Git: 0fef1a6d7 Fri Apr 3 23:00:21 2020 +0200 at vie abr 3 23:20:28 CEST 2020