Visual Servoing Platform  version 3.6.1 under development (2024-10-18)
pf-nonlinear-example.cpp
1 /*
2  * ViSP, open source Visual Servoing Platform software.
3  * Copyright (C) 2005 - 2024 by Inria. All rights reserved.
4  *
5  * This software is free software; you can redistribute it and/or modify
6  * it under the terms of the GNU General Public License as published by
7  * the Free Software Foundation; either version 2 of the License, or
8  * (at your option) any later version.
9  * See the file LICENSE.txt at the root directory of this source
10  * distribution for additional information about the GNU GPL.
11  *
12  * For using ViSP with software that can not be combined with the GNU
13  * GPL, please contact Inria about acquiring a ViSP Professional
14  * Edition License.
15  *
16  * See https://visp.inria.fr for more information.
17  *
18  * This software was developed at:
19  * Inria Rennes - Bretagne Atlantique
20  * Campus Universitaire de Beaulieu
21  * 35042 Rennes Cedex
22  * France
23  *
24  * If you have questions regarding the use of this file, please contact
25  * Inria at visp@inria.fr
26  *
27  * This file is provided AS IS with NO WARRANTY OF ANY KIND, INCLUDING THE
28  * WARRANTY OF DESIGN, MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE.
29  */
30 
67 #include <iostream>
68 
69 // ViSP includes
70 #include <visp3/core/vpConfig.h>
71 #include <visp3/core/vpGaussRand.h>
72 #ifdef VISP_HAVE_DISPLAY
73 #include <visp3/gui/vpPlot.h>
74 #endif
75 
76 // PF includes
77 #include <visp3/core/vpParticleFilter.h>
78 
79 #if (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11)
80 
81 #ifdef ENABLE_VISP_NAMESPACE
82 using namespace VISP_NAMESPACE_NAME;
83 #endif
84 
85 namespace
86 {
94 vpColVector fx(const vpColVector &particle, const double &dt)
95 {
96  vpColVector point(4);
97  point[0] = particle[1] * dt + particle[0];
98  point[1] = particle[1];
99  point[2] = particle[3] * dt + particle[2];
100  point[3] = particle[3];
101  return point;
102 }
103 
113 void computeCoordinatesFromMeasurement(const vpColVector &z, const double &xRadar, const double &yRadar, double &x, double &y)
114 {
115  double dx = z[0] * std::cos(z[1]);
116  double dy = z[0] * std::sin(z[1]);
117  x = dx + xRadar;
118  y = dy + yRadar;
119 }
120 
129 double computeError(const double &x0, const double &y0, const double &x1, const double &y1)
130 {
131  double dx = x0 - x1;
132  double dy = y0 - y1;
133  double error = std::sqrt(dx * dx + dy * dy);
134  return error;
135 }
136 
144 double computeStateError(const vpColVector &state, const vpColVector &gt_X)
145 {
146  double error = computeError(state[0], state[2], gt_X[0], gt_X[1]);
147  return error;
148 }
149 
159 double computeMeasurementsError(const vpColVector &z, const double &xRadar, const double &yRadar, const vpColVector &gt_X)
160 {
161  double xMeas = 0., yMeas = 0.;
162  computeCoordinatesFromMeasurement(z, xRadar, yRadar, xMeas, yMeas);
163  double error = computeError(xMeas, yMeas, gt_X[0], gt_X[1]);
164  return error;
165 }
166 }
167 
172 class vpRadarStation
173 {
174 public:
184  vpRadarStation(const double &x, const double &y, const double &range_std, const double &elev_angle_std,
185  const double &distMaxAllowed)
186  : m_x(x)
187  , m_y(y)
188  , m_rngRange(range_std, 0., 4224)
189  , m_rngElevAngle(elev_angle_std, 0., 2112)
190  {
191  double sigmaDistance = distMaxAllowed / 3.;
192  double sigmaDistanceSquared = sigmaDistance * sigmaDistance;
193  m_constantDenominator = 1. / std::sqrt(2. * M_PI * sigmaDistanceSquared);
194  m_constantExpDenominator = -1. / (2. * sigmaDistanceSquared);
195  }
196 
204  {
205  vpColVector meas(2);
206  double dx = particle[0] - m_x;
207  double dy = particle[2] - m_y;
208  meas[0] = std::sqrt(dx * dx + dy * dy);
209  meas[1] = std::atan2(dy, dx);
210  return meas;
211  }
212 
222  {
223  double dx = pos[0] - m_x;
224  double dy = pos[1] - m_y;
225  double range = std::sqrt(dx * dx + dy * dy);
226  double elevAngle = std::atan2(dy, dx);
227  vpColVector measurements(2);
228  measurements[0] = range;
229  measurements[1] = elevAngle;
230  return measurements;
231  }
232 
242  {
243  vpColVector measurementsGT = measureGT(pos);
244  vpColVector measurementsNoisy = measurementsGT;
245  measurementsNoisy[0] += m_rngRange();
246  measurementsNoisy[1] += m_rngElevAngle();
247  return measurementsNoisy;
248  }
249 
260  double likelihood(const vpColVector &particle, const vpColVector &meas)
261  {
262  double xParticle = particle[0];
263  double yParticle = particle[2];
264  double xMeas = 0., yMeas = 0.;
265  computeCoordinatesFromMeasurement(meas, m_x, m_y, xMeas, yMeas);
266  double dist = computeError(xParticle, yParticle, xMeas, yMeas);
267  double likelihood = std::exp(m_constantExpDenominator * dist) * m_constantDenominator;
268  likelihood = std::min(likelihood, 1.0); // Clamp to have likelihood <= 1.
269  likelihood = std::max(likelihood, 0.); // Clamp to have likelihood >= 0.
270  return likelihood;
271  }
272 
273 private:
274  double m_x; // The position on the ground of the radar
275  double m_y; // The altitude of the radar
276  vpGaussRand m_rngRange; // Noise simulator for the range measurement
277  vpGaussRand m_rngElevAngle; // Noise simulator for the elevation angle measurement
278  double m_constantDenominator; // Denominator of the Gaussian function used in the likelihood computation.
279  double m_constantExpDenominator; // Denominator of the exponential in the Gaussian function used in the likelihood computation.
280 };
281 
285 class vpACSimulator
286 {
287 public:
295  vpACSimulator(const vpColVector &X0, const vpColVector &vel, const double &vel_std)
296  : m_pos(X0)
297  , m_vel(vel)
298  , m_rngVel(vel_std, 0.)
299  {
300 
301  }
302 
310  vpColVector update(const double &dt)
311  {
312  vpColVector dx = m_vel * dt;
313  dx[0] += m_rngVel() * dt;
314  dx[1] += m_rngVel() * dt;
315  m_pos += dx;
316  return m_pos;
317  }
318 
319 private:
320  vpColVector m_pos; // Position of the simulated aircraft
321  vpColVector m_vel; // Velocity of the simulated aircraft
322  vpGaussRand m_rngVel; // Random generator for slight variations of the velocity of the aircraft
323 };
324 
325 struct SoftwareArguments
326 {
327  // --- Main loop parameters---
328  static const int SOFTWARE_CONTINUE = 42;
329  bool m_useDisplay;
330  unsigned int m_nbStepsWarmUp;
331  unsigned int m_nbSteps;
332  double m_dt; // Period, expressed in seconds
333  double m_sigmaRange; // Standard deviation of the range measurement, expressed in meters.
334  double m_sigmaElevAngle; // Standard deviation of the elevation angle measurent, expressed in radians.
335  double m_stdevAircraftVelocity; // Standard deviation of the velocity of the simulated aircraft, to make it deviate a bit from the constant velocity model
336  double m_radar_X; // Radar position along the X-axis, in meters
337  double m_radar_Y; // Radar position along the Y-axis, in meters
338  double m_gt_X_init; // Ground truth initial position along the X-axis, in meters
339  double m_gt_Y_init; // Ground truth initial position along the Y-axis, in meters
340  double m_gt_vX_init; // Ground truth initial velocity along the X-axis, in meters
341  double m_gt_vY_init; // Ground truth initial velocity along the Y-axis, in meters
342  // --- PF parameters---
343  unsigned int m_N;
344  double m_maxDistanceForLikelihood;
345  double m_ampliMaxX;
346  double m_ampliMaxY;
347  double m_ampliMaxVx;
348  double m_ampliMaxVy;
349  long m_seedPF;
350  int m_nbThreads;
351 
353  : m_useDisplay(true)
354  , m_nbStepsWarmUp(200)
355  , m_nbSteps(300)
356  , m_dt(3.)
357  , m_sigmaRange(5)
358  , m_sigmaElevAngle(vpMath::rad(0.5))
359  , m_stdevAircraftVelocity(0.2)
360  , m_radar_X(0.)
361  , m_radar_Y(0.)
362  , m_gt_X_init(-500.)
363  , m_gt_Y_init(1000.)
364  , m_gt_vX_init(10.)
365  , m_gt_vY_init(5.)
366  , m_N(500)
367  , m_maxDistanceForLikelihood(50.)
368  , m_ampliMaxX(20.)
369  , m_ampliMaxY(200.)
370  , m_ampliMaxVx(1.)
371  , m_ampliMaxVy(0.5)
372  , m_seedPF(4224)
373  , m_nbThreads(1)
374  { }
375 
376  int parseArgs(const int argc, const char *argv[])
377  {
378  int i = 1;
379  while (i < argc) {
380  std::string arg(argv[i]);
381  if ((arg == "--nb-steps-main") && ((i+1) < argc)) {
382  m_nbSteps = std::atoi(argv[i + 1]);
383  ++i;
384  }
385  else if ((arg == "--nb-steps-warmup") && ((i+1) < argc)) {
386  m_nbStepsWarmUp = std::atoi(argv[i + 1]);
387  ++i;
388  }
389  else if ((arg == "--dt") && ((i+1) < argc)) {
390  m_dt = std::atoi(argv[i + 1]);
391  ++i;
392  }
393  else if ((arg == "--stdev-range") && ((i+1) < argc)) {
394  m_sigmaRange = std::atof(argv[i + 1]);
395  ++i;
396  }
397  else if ((arg == "--stdev-elev-angle") && ((i+1) < argc)) {
398  m_sigmaElevAngle = vpMath::rad(std::atof(argv[i + 1]));
399  ++i;
400  }
401  else if ((arg == "--stdev-aircraft-vel") && ((i+1) < argc)) {
402  m_stdevAircraftVelocity = std::atof(argv[i + 1]);
403  ++i;
404  }
405  else if ((arg == "--radar-X") && ((i+1) < argc)) {
406  m_radar_X = std::atof(argv[i + 1]);
407  ++i;
408  }
409  else if ((arg == "--radar-Y") && ((i+1) < argc)) {
410  m_radar_Y = std::atof(argv[i + 1]);
411  ++i;
412  }
413  else if ((arg == "--gt-X0") && ((i+1) < argc)) {
414  m_gt_X_init = std::atof(argv[i + 1]);
415  ++i;
416  }
417  else if ((arg == "--gt-Y0") && ((i+1) < argc)) {
418  m_gt_Y_init = std::atof(argv[i + 1]);
419  ++i;
420  }
421  else if ((arg == "--gt-vX0") && ((i+1) < argc)) {
422  m_gt_vX_init = std::atof(argv[i + 1]);
423  ++i;
424  }
425  else if ((arg == "--gt-vY0") && ((i+1) < argc)) {
426  m_gt_vY_init = std::atof(argv[i + 1]);
427  ++i;
428  }
429  else if ((arg == "--max-distance-likelihood") && ((i+1) < argc)) {
430  m_maxDistanceForLikelihood = std::atof(argv[i + 1]);
431  ++i;
432  }
433  else if (((arg == "-N") || (arg == "--nb-particles")) && ((i+1) < argc)) {
434  m_N = std::atoi(argv[i + 1]);
435  ++i;
436  }
437  else if ((arg == "--seed") && ((i+1) < argc)) {
438  m_seedPF = std::atoi(argv[i + 1]);
439  ++i;
440  }
441  else if ((arg == "--nb-threads") && ((i+1) < argc)) {
442  m_nbThreads = std::atoi(argv[i + 1]);
443  ++i;
444  }
445  else if ((arg == "--ampli-max-X") && ((i+1) < argc)) {
446  m_ampliMaxX = std::atof(argv[i + 1]);
447  ++i;
448  }
449  else if ((arg == "--ampli-max-Y") && ((i+1) < argc)) {
450  m_ampliMaxY = std::atof(argv[i + 1]);
451  ++i;
452  }
453  else if ((arg == "--ampli-max-vX") && ((i+1) < argc)) {
454  m_ampliMaxVx = std::atof(argv[i + 1]);
455  ++i;
456  }
457  else if ((arg == "--ampli-max-vY") && ((i+1) < argc)) {
458  m_ampliMaxVy = std::atof(argv[i + 1]);
459  ++i;
460  }
461  else if (arg == "-d") {
462  m_useDisplay = false;
463  }
464  else if ((arg == "-h") || (arg == "--help")) {
465  printUsage(std::string(argv[0]));
466  SoftwareArguments defaultArgs;
467  defaultArgs.printDetails();
468  return 0;
469  }
470  else {
471  std::cout << "WARNING: unrecognised argument \"" << arg << "\"";
472  if (i + 1 < argc) {
473  std::cout << " with associated value(s) { ";
474  int nbValues = 0;
475  int j = i + 1;
476  bool hasToRun = true;
477  while ((j < argc) && hasToRun) {
478  std::string nextValue(argv[j]);
479  if (nextValue.find("--") == std::string::npos) {
480  std::cout << nextValue << " ";
481  ++nbValues;
482  }
483  else {
484  hasToRun = false;
485  }
486  ++j;
487  }
488  std::cout << "}" << std::endl;
489  i += nbValues;
490  }
491  }
492  ++i;
493  }
494  return SOFTWARE_CONTINUE;
495  }
496 
497 private:
498  void printUsage(const std::string &softName)
499  {
500  std::cout << "SYNOPSIS" << std::endl;
501  std::cout << " " << softName << " [--nb-steps-main <uint>] [--nb-steps-warmup <uint>]" << std::endl;
502  std::cout << " [--dt <double>] [--stdev-range <double>] [--stdev-elev-angle <double>] [--stdev-aircraft-vel <double>]" << std::endl;
503  std::cout << " [--radar-X <double>] [--radar-Y <double>]" << std::endl;
504  std::cout << " [--gt-X0 <double>] [--gt-Y0 <double>] [--gt-vX0 <double>] [--gt-vY0 <double>]" << std::endl;
505  std::cout << " [--max-distance-likelihood <double>] [-N, --nb-particles <uint>] [--seed <int>] [--nb-threads <int>]" << std::endl;
506  std::cout << " [--ampli-max-X <double>] [--ampli-max-Y <double>] [--ampli-max-vX <double>] [--ampli-max-vY <double>]" << std::endl;
507  std::cout << " [-d, --no-display] [-h]" << std::endl;
508  }
509 
510  void printDetails()
511  {
512  std::cout << std::endl << std::endl;
513  std::cout << "DETAILS" << std::endl;
514  std::cout << " --nb-steps-main" << std::endl;
515  std::cout << " Number of steps in the main loop." << std::endl;
516  std::cout << " Default: " << m_nbSteps << std::endl;
517  std::cout << std::endl;
518  std::cout << " --nb-steps-warmup" << std::endl;
519  std::cout << " Number of steps in the warmup loop." << std::endl;
520  std::cout << " Default: " << m_nbStepsWarmUp << std::endl;
521  std::cout << std::endl;
522  std::cout << " --dt" << std::endl;
523  std::cout << " Timestep of the simulation, in seconds." << std::endl;
524  std::cout << " Default: " << m_dt << std::endl;
525  std::cout << std::endl;
526  std::cout << " --stdev-range" << std::endl;
527  std::cout << " Standard deviation of the range measurements, in meters." << std::endl;
528  std::cout << " Default: " << m_sigmaRange << std::endl;
529  std::cout << std::endl;
530  std::cout << " --stdev-elev-angle" << std::endl;
531  std::cout << " Standard deviation of the elevation angle measurements, in degrees." << std::endl;
532  std::cout << " Default: " << vpMath::deg(m_sigmaElevAngle) << std::endl;
533  std::cout << std::endl;
534  std::cout << " --stdev-aircraft-vel" << std::endl;
535  std::cout << " Standard deviation of the aircraft velocity, in m/s." << std::endl;
536  std::cout << " Default: " << m_stdevAircraftVelocity << std::endl;
537  std::cout << std::endl;
538  std::cout << " --radar-X" << std::endl;
539  std::cout << " Position along the X-axis of the radar, in meters." << std::endl;
540  std::cout << " Be careful, because singularities happen if the aircraft flies above the radar." << std::endl;
541  std::cout << " Default: " << m_radar_X << std::endl;
542  std::cout << std::endl;
543  std::cout << " --radar-Y" << std::endl;
544  std::cout << " Position along the Y-axis of the radar, in meters." << std::endl;
545  std::cout << " Be careful, because singularities happen if the aircraft flies above the radar." << std::endl;
546  std::cout << " Default: " << m_radar_Y << std::endl;
547  std::cout << std::endl;
548  std::cout << " --gt-X0" << std::endl;
549  std::cout << " Initial position along the X-axis of the aircraft, in meters." << std::endl;
550  std::cout << " Be careful, because singularities happen if the aircraft flies above the radar." << std::endl;
551  std::cout << " Default: " << m_gt_X_init << std::endl;
552  std::cout << std::endl;
553  std::cout << " --gt-Y0" << std::endl;
554  std::cout << " Initial position along the Y-axis of the aircraft, in meters." << std::endl;
555  std::cout << " Be careful, because singularities happen if the aircraft flies above the radar." << std::endl;
556  std::cout << " Default: " << m_gt_Y_init << std::endl;
557  std::cout << std::endl;
558  std::cout << " --gt-vX0" << std::endl;
559  std::cout << " Initial velocity along the X-axis of the aircraft, in m/s." << std::endl;
560  std::cout << " Be careful, because singularities happen if the aircraft flies above the radar." << std::endl;
561  std::cout << " Default: " << m_gt_vX_init << std::endl;
562  std::cout << std::endl;
563  std::cout << " --gt-vY0" << std::endl;
564  std::cout << " Initial velocity along the Y-axis of the aircraft, in m/s." << std::endl;
565  std::cout << " Be careful, because singularities happen if the aircraft flies above the radar." << std::endl;
566  std::cout << " Default: " << m_gt_vY_init << std::endl;
567  std::cout << std::endl;
568  std::cout << " --max-distance-likelihood" << std::endl;
569  std::cout << " Maximum tolerated distance between a particle and the measurements." << std::endl;
570  std::cout << " Above this value, the likelihood of the particle is 0." << std::endl;
571  std::cout << " Default: " << m_maxDistanceForLikelihood << std::endl;
572  std::cout << std::endl;
573  std::cout << " -N, --nb-particles" << std::endl;
574  std::cout << " Number of particles of the Particle Filter." << std::endl;
575  std::cout << " Default: " << m_N << std::endl;
576  std::cout << std::endl;
577  std::cout << " --seed" << std::endl;
578  std::cout << " Seed to initialize the Particle Filter." << std::endl;
579  std::cout << " Use a negative value makes to use the current timestamp instead." << std::endl;
580  std::cout << " Default: " << m_seedPF << std::endl;
581  std::cout << std::endl;
582  std::cout << " --nb-threads" << std::endl;
583  std::cout << " Set the number of threads to use in the Particle Filter (only if OpenMP is available)." << std::endl;
584  std::cout << " Use a negative value to use the maximum number of threads instead." << std::endl;
585  std::cout << " Default: " << m_nbThreads << std::endl;
586  std::cout << std::endl;
587  std::cout << " --ampli-max-X" << std::endl;
588  std::cout << " Maximum amplitude of the noise added to a particle along the X-axis." << std::endl;
589  std::cout << " Default: " << m_ampliMaxX << std::endl;
590  std::cout << std::endl;
591  std::cout << " --ampli-max-Y" << std::endl;
592  std::cout << " Maximum amplitude of the noise added to a particle along the Y-axis." << std::endl;
593  std::cout << " Default: " << m_ampliMaxY << std::endl;
594  std::cout << std::endl;
595  std::cout << " --ampli-max-vX" << std::endl;
596  std::cout << " Maximum amplitude of the noise added to a particle to the velocity along the X-axis component." << std::endl;
597  std::cout << " Default: " << m_ampliMaxVx << std::endl;
598  std::cout << std::endl;
599  std::cout << " --ampli-max-vY" << std::endl;
600  std::cout << " Maximum amplitude of the noise added to a particle to the velocity along the Y-axis component." << std::endl;
601  std::cout << " Default: " << m_ampliMaxVy << std::endl;
602  std::cout << std::endl;
603  std::cout << " -d, --no-display" << std::endl;
604  std::cout << " Deactivate display." << std::endl;
605  std::cout << " Default: display is ";
606 #ifdef VISP_HAVE_DISPLAY
607  std::cout << "ON" << std::endl;
608 #else
609  std::cout << "OFF" << std::endl;
610 #endif
611  std::cout << std::endl;
612  std::cout << " -h, --help" << std::endl;
613  std::cout << " Display this help." << std::endl;
614  std::cout << std::endl;
615  }
616 };
617 
618 int main(const int argc, const char *argv[])
619 {
620  SoftwareArguments args;
621  int returnCode = args.parseArgs(argc, argv);
622  if (returnCode != SoftwareArguments::SOFTWARE_CONTINUE) {
623  return returnCode;
624  }
625 
626  // Initialize the attributes of the PF
627  std::vector<double> stdevsPF = { args.m_ampliMaxX /3., args.m_ampliMaxVx /3., args.m_ampliMaxY /3. , args.m_ampliMaxVy /3. };
628  int seedPF = args.m_seedPF;
629  unsigned int nbParticles = args.m_N;
630  int nbThreads = args.m_nbThreads;
631 
632  vpColVector X0(4);
633  X0[0] = 0.9 * args.m_gt_X_init; // x, i.e. 10% of error with regard to ground truth
634  X0[1] = 0.9 * args.m_gt_vX_init; // dx/dt, i.e. 10% of error with regard to ground truth
635  X0[2] = 0.9 * args.m_gt_Y_init; // y, i.e. 10% of error with regard to ground truth
636  X0[3] = 0.9 * args.m_gt_vY_init; // dy/dt, i.e. 10% of error with regard to ground truth
637 
640  using std::placeholders::_1;
641  using std::placeholders::_2;
642  vpParticleFilter<vpColVector>::vpLikelihoodFunction likelihoodFunc = std::bind(&vpRadarStation::likelihood, &radar, _1, _2);
645 
646  // Initialize the PF
647  vpParticleFilter<vpColVector> filter(nbParticles, stdevsPF, seedPF, nbThreads);
648  filter.init(X0, f, likelihoodFunc, checkResamplingFunc, resamplingFunc);
649 
650 #ifdef VISP_HAVE_DISPLAY
651  vpPlot *plot = nullptr;
652  if (args.m_useDisplay) {
653  // Initialize the plot
654  plot = new vpPlot(4);
655  plot->initGraph(0, 3);
656  plot->setTitle(0, "Position along X-axis");
657  plot->setUnitX(0, "Time (s)");
658  plot->setUnitY(0, "Position (m)");
659  plot->setLegend(0, 0, "GT");
660  plot->setLegend(0, 1, "Filtered");
661  plot->setLegend(0, 2, "Measure");
662  plot->setColor(0, 0, vpColor::red);
663  plot->setColor(0, 1, vpColor::blue);
664  plot->setColor(0, 2, vpColor::black);
665 
666  plot->initGraph(1, 3);
667  plot->setTitle(1, "Velocity along X-axis");
668  plot->setUnitX(1, "Time (s)");
669  plot->setUnitY(1, "Velocity (m/s)");
670  plot->setLegend(1, 0, "GT");
671  plot->setLegend(1, 1, "Filtered");
672  plot->setLegend(1, 2, "Measure");
673  plot->setColor(1, 0, vpColor::red);
674  plot->setColor(1, 1, vpColor::blue);
675  plot->setColor(1, 2, vpColor::black);
676 
677  plot->initGraph(2, 3);
678  plot->setTitle(2, "Position along Y-axis");
679  plot->setUnitX(2, "Time (s)");
680  plot->setUnitY(2, "Position (m)");
681  plot->setLegend(2, 0, "GT");
682  plot->setLegend(2, 1, "Filtered");
683  plot->setLegend(2, 2, "Measure");
684  plot->setColor(2, 0, vpColor::red);
685  plot->setColor(2, 1, vpColor::blue);
686  plot->setColor(2, 2, vpColor::black);
687 
688  plot->initGraph(3, 3);
689  plot->setTitle(3, "Velocity along Y-axis");
690  plot->setUnitX(3, "Time (s)");
691  plot->setUnitY(3, "Velocity (m/s)");
692  plot->setLegend(3, 0, "GT");
693  plot->setLegend(3, 1, "Filtered");
694  plot->setLegend(3, 2, "Measure");
695  plot->setColor(3, 0, vpColor::red);
696  plot->setColor(3, 1, vpColor::blue);
697  plot->setColor(3, 2, vpColor::black);
698  }
699 #endif
700 
701  // Initialize the simulation
702  vpColVector ac_pos(2);
703  ac_pos[0] = args.m_gt_X_init;
704  ac_pos[1] = args.m_gt_Y_init;
705  vpColVector ac_vel(2);
706  ac_vel[0] = args.m_gt_vX_init;
707  ac_vel[1] = args.m_gt_vY_init;
708  vpACSimulator ac(ac_pos, ac_vel, args.m_stdevAircraftVelocity);
709  vpColVector gt_Xprec = ac_pos;
710  vpColVector gt_Vprec = ac_vel;
711  double averageFilteringTime = 0.;
712  double meanErrorFilter = 0., meanErrorNoise = 0.;
713  double xNoise_prec = 0., yNoise_prec = 0.;
714 
715  // Warmup loop
716  const unsigned int nbStepsWarmUp = args.m_nbStepsWarmUp;
717  for (unsigned int i = 0; i < nbStepsWarmUp; ++i) {
718  // Update object pose
719  vpColVector gt_X = ac.update(args.m_dt);
720 
721  // Perform the measurement
722  vpColVector z = radar.measureWithNoise(gt_X);
723 
724  // Use the UKF to filter the measurement
725  double t0 = vpTime::measureTimeMicros();
726  filter.filter(z, args.m_dt);
727  averageFilteringTime += vpTime::measureTimeMicros() - t0;
728  gt_Xprec = gt_X;
729 
730  // Save the noisy position
731  computeCoordinatesFromMeasurement(z, args.m_radar_X, args.m_radar_Y, xNoise_prec, yNoise_prec);
732  }
733 
734  for (unsigned int i = 0; i < args.m_nbSteps; ++i) {
735  // Perform the measurement
736  vpColVector gt_X = ac.update(args.m_dt);
737  vpColVector gt_V = (gt_X - gt_Xprec) / args.m_dt;
738  vpColVector z = radar.measureWithNoise(gt_X);
739 
740  // Use the PF to filter the measurement
741  double t0 = vpTime::measureTimeMicros();
742  filter.filter(z, args.m_dt);
743  averageFilteringTime += vpTime::measureTimeMicros() - t0;
744 
745  // Compute the error between GT and filtered state for statistics at the end of the program
746  vpColVector Xest = filter.computeFilteredState();
747  vpColVector gtState = vpColVector({ gt_Xprec[0], gt_Vprec[0], gt_Xprec[1], gt_Vprec[1] });
748  double normErrorFilter = computeStateError(Xest, gt_X);
749  meanErrorFilter += normErrorFilter;
750 
751  // Compute the error between GT and noisy measurements for statistics at the end of the program
752  double xNoise = 0., yNoise = 0.;
753  computeCoordinatesFromMeasurement(z, args.m_radar_X, args.m_radar_Y, xNoise, yNoise);
754  double normErrorNoise = computeMeasurementsError(z, args.m_radar_X, args.m_radar_Y, gt_X);
755  meanErrorNoise += normErrorNoise;
756 
757 #ifdef VISP_HAVE_DISPLAY
758  if (args.m_useDisplay) {
759  // Plot the ground truth, measurement and filtered state
760  plot->plot(0, 0, i, gt_X[0]);
761  plot->plot(0, 1, i, Xest[0]);
762  plot->plot(0, 2, i, xNoise);
763 
764  double vxNoise = (xNoise - xNoise_prec) / args.m_dt;
765  plot->plot(1, 0, i, gt_V[0]);
766  plot->plot(1, 1, i, Xest[1]);
767  plot->plot(1, 2, i, vxNoise);
768 
769  plot->plot(2, 0, i, gt_X[1]);
770  plot->plot(2, 1, i, Xest[2]);
771  plot->plot(2, 2, i, yNoise);
772 
773  double vyNoise = (yNoise - yNoise_prec) / args.m_dt;
774  plot->plot(3, 0, i, gt_V[1]);
775  plot->plot(3, 1, i, Xest[3]);
776  plot->plot(3, 2, i, vyNoise);
777  }
778 #endif
779 
780  gt_Xprec = gt_X;
781  gt_Vprec = gt_V;
782  xNoise_prec = xNoise;
783  yNoise_prec = yNoise;
784  }
785 
786  // COmpute and display the error statistics and computation time
787  meanErrorFilter /= static_cast<double>(args.m_nbSteps);
788  meanErrorNoise /= static_cast<double>(args.m_nbSteps);
789  averageFilteringTime = averageFilteringTime / (static_cast<double>(args.m_nbSteps) + static_cast<double>(nbStepsWarmUp));
790  std::cout << "Mean error filter = " << meanErrorFilter << "m" << std::endl;
791  std::cout << "Mean error noise = " << meanErrorNoise << "m" << std::endl;
792  std::cout << "Mean filtering time = " << averageFilteringTime << "us" << std::endl;
793 
794  if (args.m_useDisplay) {
795  std::cout << "Press Enter to quit..." << std::endl;
796  std::cin.get();
797  }
798 
799 #ifdef VISP_HAVE_DISPLAY
800  if (args.m_useDisplay) {
801  delete plot;
802  }
803 #endif
804 
805  // For the unit tests that uses this program
806  const double maxError = 150.;
807  if (meanErrorFilter > maxError) {
808  std::cerr << "Error: max tolerated error = " << maxError << ", mean error = " << meanErrorFilter << std::endl;
809  return -1;
810  }
811  else if (meanErrorFilter >= meanErrorNoise) {
812  std::cerr << "Error: mean error without filter = " << meanErrorNoise << ", mean error with filter = " << meanErrorFilter << std::endl;
813  return -1;
814  }
815 
816  return 0;
817 }
818 #else
819 int main()
820 {
821  std::cout << "This example is only available if you compile ViSP in C++11 standard or higher." << std::endl;
822  return 0;
823 }
824 #endif
Class to simulate a flying aircraft.
vpColVector update(const double &dt)
Compute the new position of the aircraft after dt seconds have passed since the last update.
vpACSimulator(const vpColVector &X0, const vpColVector &vel, const double &vel_std)
Construct a new vpACSimulator object.
Implementation of column vector and the associated operations.
Definition: vpColVector.h:191
static const vpColor red
Definition: vpColor.h:217
static const vpColor blue
Definition: vpColor.h:223
static const vpColor black
Definition: vpColor.h:211
Class for generating random number with normal probability density.
Definition: vpGaussRand.h:117
Provides simple mathematics computation tools that are not available in the C mathematics library (ma...
Definition: vpMath.h:111
static double rad(double deg)
Definition: vpMath.h:129
static double deg(double rad)
Definition: vpMath.h:119
The class permits to use a Particle Filter.
std::function< vpParticlesWithWeights(const std::vector< vpColVector > &, const std::vector< double > &)> vpResamplingFunction
Function that takes as argument the vector of particles and the vector of associated weights....
std::function< vpColVector(const vpColVector &, const double &)> vpProcessFunction
Process model function, which projects a particle forward in time. The first argument is a particle,...
std::function< bool(const unsigned int &, const std::vector< double > &)> vpResamplingConditionFunction
Function that takes as argument the number of particles and the vector of weights associated to each ...
std::function< double(const vpColVector &, const MeasurementsType &)> vpLikelihoodFunction
Likelihood function, which evaluates the likelihood of a particle with regard to the measurements....
This class enables real time drawing of 2D or 3D graphics. An instance of the class open a window whi...
Definition: vpPlot.h:112
void initGraph(unsigned int graphNum, unsigned int curveNbr)
Definition: vpPlot.cpp:203
void setUnitY(unsigned int graphNum, const std::string &unity)
Definition: vpPlot.cpp:530
void setLegend(unsigned int graphNum, unsigned int curveNum, const std::string &legend)
Definition: vpPlot.cpp:552
void plot(unsigned int graphNum, unsigned int curveNum, double x, double y)
Definition: vpPlot.cpp:270
void setUnitX(unsigned int graphNum, const std::string &unitx)
Definition: vpPlot.cpp:520
void setColor(unsigned int graphNum, unsigned int curveNum, vpColor color)
Definition: vpPlot.cpp:246
void setTitle(unsigned int graphNum, const std::string &title)
Definition: vpPlot.cpp:510
Class that permits to convert the position of the aircraft into range and elevation angle measurement...
vpRadarStation(const double &x, const double &y, const double &range_std, const double &elev_angle_std, const double &distMaxAllowed)
Construct a new vpRadarStation object.
double likelihood(const vpColVector &particle, const vpColVector &meas)
Compute the likelihood of a particle (value between 0. and 1.) knowing the measurements....
vpColVector measureWithNoise(const vpColVector &pos)
Noisy measurement of the range and elevation angle that correspond to pos.
vpColVector state_to_measurement(const vpColVector &particle)
Convert a particle of the Particle Filter into the measurement space.
vpColVector measureGT(const vpColVector &pos)
Perfect measurement of the range and elevation angle that correspond to pos.
VISP_EXPORT double measureTimeMicros()
bool m_useDisplay
If true, activate the plot and the renderer if VISP_HAVE_DISPLAY is defined.
int m_nbThreads
Number of thread to use in the Particle Filter.
unsigned int m_nbSteps
Number of steps for the main loop.
double m_ampliMaxVx
Amplitude max of the noise for the state component corresponding to the velocity along the X-axis.
double m_ampliMaxY
Amplitude max of the noise for the state component corresponding to the Y coordinate.
unsigned int m_N
The number of particles.
double m_ampliMaxVy
Amplitude max of the noise for the state component corresponding to the velocity along the Y-axis.
double m_maxDistanceForLikelihood
The maximum allowed distance between a particle and the measurement, leading to a likelihood equal to...
int parseArgs(const int argc, const char *argv[])
unsigned int m_nbStepsWarmUp
Number of steps for the warmup phase.
double m_ampliMaxX
Amplitude max of the noise for the state component corresponding to the X coordinate.
long m_seedPF
Seed for the random generators of the PF.