Visual Servoing Platform  version 3.6.1 under development (2024-09-10)
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 
58 // ViSP includes
59 #include <visp3/core/vpConfig.h>
60 #include <visp3/core/vpCameraParameters.h>
61 #include <visp3/core/vpGaussRand.h>
62 #include <visp3/core/vpHomogeneousMatrix.h>
63 #include <visp3/core/vpMeterPixelConversion.h>
64 #include <visp3/core/vpPixelMeterConversion.h>
66 #ifdef VISP_HAVE_DISPLAY
67 #include <visp3/gui/vpPlot.h>
68 #include <visp3/gui/vpDisplayFactory.h>
69 #endif
71 #include <visp3/vision/vpPose.h>
72 
74 #include <visp3/core/vpParticleFilter.h>
76 
77 #ifdef ENABLE_VISP_NAMESPACE
78 using namespace VISP_NAMESPACE_NAME;
79 #endif
80 
81 #if (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11)
83 
90 vpColVector fx(const vpColVector &x, const double & /*dt*/)
91 {
92  vpColVector x_kPlus1(4);
93  x_kPlus1[0] = x[0] * std::cos(x[3]) - x[1] * std::sin(x[3]); // wX
94  x_kPlus1[1] = x[0] * std::sin(x[3]) + x[1] * std::cos(x[3]); // wY
95  x_kPlus1[2] = x[2]; // wZ
96  x_kPlus1[3] = x[3]; // omega * dt
97  return x_kPlus1;
98 }
100 
102 
106 {
107 public:
116  vpObjectSimulator(const double &R, const double &w, const double &phi, const double &wZ)
117  : m_R(R)
118  , m_w(w)
119  , m_phi(phi)
120  , m_wZ(wZ)
121  { }
122 
129  vpColVector move(const double &t)
130  {
131  vpColVector wX(4, 1.);
132  wX[0] = m_R * std::cos(m_w * t + m_phi);
133  wX[1] = m_R * std::sin(m_w * t + m_phi);
134  wX[2] = m_wZ;
135  return wX;
136  }
137 
138 private:
139  double m_R; // Radius of the revolution around the world frame origin.
140  double m_w; // Pulsation of the motion.
141  double m_phi; // Phase of the motion.
142  const double m_wZ; // The z-coordinate of the object in the world frame.
143 };
145 
147 
151 {
152 public:
166  const std::vector<vpColVector> &markers, const double &sigmaDistance,
167  const double &noise_stdev, const long &seed)
168  : m_cam(cam)
169  , m_cMw(cMw)
170  , m_wRo(wRo)
171  , m_markers(markers)
172  , m_rng(noise_stdev, 0., seed)
173  {
174  double sigmaDistanceSquared = sigmaDistance * sigmaDistance;
175  m_constantDenominator = 1. / std::sqrt(2. * M_PI * sigmaDistanceSquared);
176  m_constantExpDenominator = -1. / (2. * sigmaDistanceSquared);
177  }
178 
180 
192  double likelihoodParticle(const vpColVector &x, const vpColVector &meas)
193  {
194  unsigned int nbMarkers = static_cast<unsigned int>(m_markers.size());
195  double likelihood = 0.;
197  vpTranslationVector wTo(x[0], x[1], x[2]);
198  wMo.build(wTo, m_wRo);
199  const unsigned int sizePt2D = 2;
200  const unsigned int idX = 0, idY = 1, idZ = 2;
201  double sumError = 0.;
202  for (unsigned int i = 0; i < nbMarkers; ++i) {
203  vpColVector cX = m_cMw * wMo * m_markers[i];
204  vpImagePoint projParticle;
205  vpMeterPixelConversion::convertPoint(m_cam, cX[idX] / cX[idZ], cX[idY] / cX[idZ], projParticle);
206  vpImagePoint measPt(meas[sizePt2D * i + 1], meas[sizePt2D * i]);
207  double error = vpImagePoint::sqrDistance(projParticle, measPt);
208  sumError += error;
209  }
210  likelihood = std::exp(m_constantExpDenominator * sumError / static_cast<double>(nbMarkers)) * m_constantDenominator;
211  likelihood = std::min(likelihood, 1.0); // Clamp to have likelihood <= 1.
212  likelihood = std::max(likelihood, 0.); // Clamp to have likelihood >= 0.
213  return likelihood;
214  }
216 
224  {
225  unsigned int nbMarkers = static_cast<unsigned int>(m_markers.size());
226  vpColVector meas(2*nbMarkers);
228  vpTranslationVector wTo(x[0], x[1], x[2]);
229  wMo.build(wTo, m_wRo);
230  for (unsigned int i = 0; i < nbMarkers; ++i) {
231  vpColVector cX = m_cMw * wMo * m_markers[i];
232  double u = 0., v = 0.;
233  vpMeterPixelConversion::convertPoint(m_cam, cX[0] / cX[2], cX[1] / cX[2], u, v);
234  meas[2*i] = u;
235  meas[2*i + 1] = v;
236  }
237  return meas;
238  }
239 
241 
249  {
250  unsigned int nbMarkers = static_cast<unsigned int>(m_markers.size());
251  vpColVector meas(2*nbMarkers);
253  vpTranslationVector wTo(wX[0], wX[1], wX[2]);
254  wMo.build(wTo, m_wRo);
255  for (unsigned int i = 0; i < nbMarkers; ++i) {
256  vpColVector cX = m_cMw * wMo * m_markers[i];
257  double u = 0., v = 0.;
258  vpMeterPixelConversion::convertPoint(m_cam, cX[0] / cX[2], cX[1] / cX[2], u, v);
259  meas[2*i] = u;
260  meas[2*i + 1] = v;
261  }
262  return meas;
263  }
265 
267 
275  {
276  vpColVector measurementsGT = measureGT(wX);
277  vpColVector measurementsNoisy = measurementsGT;
278  unsigned int sizeMeasurement = measurementsGT.size();
279  for (unsigned int i = 0; i < sizeMeasurement; ++i) {
280  measurementsNoisy[i] += m_rng();
281  }
282  return measurementsNoisy;
283  }
285 
286 private:
287  vpCameraParameters m_cam; // The camera parameters
288  vpHomogeneousMatrix m_cMw; // The pose of the world frame with regard to the camera frame.
289  vpRotationMatrix m_wRo; // The rotation matrix that expresses the rotation between the world frame and object frame.
290  std::vector<vpColVector> m_markers; // The position of the markers in the object frame.
291  double m_constantDenominator; // Denominator of the Gaussian function used for the likelihood computation.
292  double m_constantExpDenominator; // Denominator of the exponential of the Gaussian function used for the likelihood computation.
293  vpGaussRand m_rng; // Noise simulator for the measurements
294 };
296 
298 
307 vpHomogeneousMatrix computePose(std::vector<vpPoint> &point, const std::vector<vpImagePoint> &ip, const vpCameraParameters &cam)
308 {
309  vpPose pose;
310  double x = 0, y = 0;
311  for (unsigned int i = 0; i < point.size(); i++) {
312  vpPixelMeterConversion::convertPoint(cam, ip[i], x, y);
313  point[i].set_x(x);
314  point[i].set_y(y);
315  pose.addPoint(point[i]);
316  }
317 
320  return cMo;
321 }
323 
325 {
326  // --- Main loop parameters---
327  static const int SOFTWARE_CONTINUE = 42;
329  unsigned int m_nbStepsWarmUp;
330  unsigned int m_nbSteps;
331  // --- PF parameters---
332  unsigned int m_N;
334  double m_ampliMaxX;
335  double m_ampliMaxY;
336  double m_ampliMaxZ;
338  long m_seedPF;
339  unsigned int m_nbThreads;
340 
342  : m_useDisplay(true)
343  , m_nbStepsWarmUp(200)
344  , m_nbSteps(300)
345  , m_N(500)
346  , m_maxDistanceForLikelihood(10.)
347  , m_ampliMaxX(0.02)
348  , m_ampliMaxY(0.02)
349  , m_ampliMaxZ(0.01)
350  , m_ampliMaxOmega(0.02)
351  , m_seedPF(4224)
352  , m_nbThreads(1)
353  { }
354 
355  int parseArgs(const int argc, const char *argv[])
356  {
357  int i = 1;
358  while (i < argc) {
359  std::string arg(argv[i]);
360  if ((arg == "--nb-steps-main") && ((i+1) < argc)) {
361  m_nbSteps = std::atoi(argv[i + 1]);
362  ++i;
363  }
364  else if ((arg == "--nb-steps-warmup") && ((i+1) < argc)) {
365  m_nbStepsWarmUp = std::atoi(argv[i + 1]);
366  ++i;
367  }
368  else if ((arg == "--max-distance-likelihood") && ((i+1) < argc)) {
369  m_maxDistanceForLikelihood = std::atof(argv[i + 1]);
370  ++i;
371  }
372  else if (((arg == "-N") || (arg == "--nb-particles")) && ((i+1) < argc)) {
373  m_N = std::atoi(argv[i + 1]);
374  ++i;
375  }
376  else if ((arg == "--seed") && ((i+1) < argc)) {
377  m_seedPF = std::atoi(argv[i + 1]);
378  ++i;
379  }
380  else if ((arg == "--nb-threads") && ((i+1) < argc)) {
381  m_nbThreads = std::atoi(argv[i + 1]);
382  ++i;
383  }
384  else if ((arg == "--ampli-max-X") && ((i+1) < argc)) {
385  m_ampliMaxX = std::atof(argv[i + 1]);
386  ++i;
387  }
388  else if ((arg == "--ampli-max-Y") && ((i+1) < argc)) {
389  m_ampliMaxY = std::atof(argv[i + 1]);
390  ++i;
391  }
392  else if ((arg == "--ampli-max-Z") && ((i+1) < argc)) {
393  m_ampliMaxZ = std::atof(argv[i + 1]);
394  ++i;
395  }
396  else if ((arg == "--ampli-max-omega") && ((i+1) < argc)) {
397  m_ampliMaxOmega = std::atof(argv[i + 1]);
398  ++i;
399  }
400  else if (arg == "-d") {
401  m_useDisplay = false;
402  }
403  else if ((arg == "-h") || (arg == "--help")) {
404  printUsage(std::string(argv[0]));
405  SoftwareArguments defaultArgs;
406  defaultArgs.printDetails();
407  return 0;
408  }
409  else {
410  std::cout << "WARNING: unrecognised argument \"" << arg << "\"";
411  if (i + 1 < argc) {
412  std::cout << " with associated value(s) { ";
413  int nbValues = 0;
414  int j = i + 1;
415  bool hasToRun = true;
416  while ((j < argc) && hasToRun) {
417  std::string nextValue(argv[j]);
418  if (nextValue.find("--") == std::string::npos) {
419  std::cout << nextValue << " ";
420  ++nbValues;
421  }
422  else {
423  hasToRun = false;
424  }
425  ++j;
426  }
427  std::cout << "}" << std::endl;
428  i += nbValues;
429  }
430  }
431  ++i;
432  }
433  return SOFTWARE_CONTINUE;
434  }
435 
436 private:
437  void printUsage(const std::string &softName)
438  {
439  std::cout << "SYNOPSIS" << std::endl;
440  std::cout << " " << softName << " [--nb-steps-main <uint>] [--nb-steps-warmup <uint>]" << std::endl;
441  std::cout << " [--max-distance-likelihood <double>] [-N, --nb-particles <uint>] [--seed <int>] [--nb-threads <int>]" << std::endl;
442  std::cout << " [--ampli-max-X <double>] [--ampli-max-Y <double>] [--ampli-max-Z <double>] [--ampli-max-omega <double>]" << std::endl;
443  std::cout << " [-d, --no-display] [-h]" << std::endl;
444  }
445 
446  void printDetails()
447  {
448  std::cout << std::endl << std::endl;
449  std::cout << "DETAILS" << std::endl;
450  std::cout << " --nb-steps-main" << std::endl;
451  std::cout << " Number of steps in the main loop." << std::endl;
452  std::cout << " Default: " << m_nbSteps << std::endl;
453  std::cout << std::endl;
454  std::cout << " --nb-steps-warmup" << std::endl;
455  std::cout << " Number of steps in the warmup loop." << std::endl;
456  std::cout << " Default: " << m_nbStepsWarmUp << std::endl;
457  std::cout << std::endl;
458  std::cout << " --max-distance-likelihood" << std::endl;
459  std::cout << " Maximum mean distance of the projection of the markers corresponding" << std::endl;
460  std::cout << " to a particle with the measurements. Above this value, the likelihood of the particle is 0." << std::endl;
461  std::cout << " Default: " << m_maxDistanceForLikelihood << std::endl;
462  std::cout << std::endl;
463  std::cout << " -N, --nb-particles" << std::endl;
464  std::cout << " Number of particles of the Particle Filter." << std::endl;
465  std::cout << " Default: " << m_N << std::endl;
466  std::cout << std::endl;
467  std::cout << " --seed" << std::endl;
468  std::cout << " Seed to initialize the Particle Filter." << std::endl;
469  std::cout << " Use a negative value makes to use the current timestamp instead." << std::endl;
470  std::cout << " Default: " << m_seedPF << std::endl;
471  std::cout << std::endl;
472  std::cout << " --nb-threads" << std::endl;
473  std::cout << " Set the number of threads to use in the Particle Filter (only if OpenMP is available)." << std::endl;
474  std::cout << " Use a negative value to use the maximum number of threads instead." << std::endl;
475  std::cout << " Default: " << m_nbThreads << std::endl;
476  std::cout << std::endl;
477  std::cout << " --ampli-max-X" << std::endl;
478  std::cout << " Maximum amplitude of the noise added to a particle along the X-axis." << std::endl;
479  std::cout << " Default: " << m_ampliMaxX << std::endl;
480  std::cout << std::endl;
481  std::cout << " --ampli-max-Y" << std::endl;
482  std::cout << " Maximum amplitude of the noise added to a particle along the Y-axis." << std::endl;
483  std::cout << " Default: " << m_ampliMaxY << std::endl;
484  std::cout << std::endl;
485  std::cout << " --ampli-max-Z" << std::endl;
486  std::cout << " Maximum amplitude of the noise added to a particle along the Z-axis." << std::endl;
487  std::cout << " Default: " << m_ampliMaxZ << std::endl;
488  std::cout << std::endl;
489  std::cout << " --ampli-max-omega" << std::endl;
490  std::cout << " Maximum amplitude of the noise added to a particle affecting the pulsation of the motion." << std::endl;
491  std::cout << " Default: " << m_ampliMaxOmega << std::endl;
492  std::cout << std::endl;
493  std::cout << " -d, --no-display" << std::endl;
494  std::cout << " Deactivate display." << std::endl;
495  std::cout << " Default: display is ";
496 #ifdef VISP_HAVE_DISPLAY
497  std::cout << "ON" << std::endl;
498 #else
499  std::cout << "OFF" << std::endl;
500 #endif
501  std::cout << std::endl;
502  std::cout << " -h, --help" << std::endl;
503  std::cout << " Display this help." << std::endl;
504  std::cout << std::endl;
505  }
506 };
507 
508 int main(const int argc, const char *argv[])
509 {
510  SoftwareArguments args;
511  int returnCode = args.parseArgs(argc, argv);
512  if (returnCode != SoftwareArguments::SOFTWARE_CONTINUE) {
513  return returnCode;
514  }
515 
517  const double dt = 0.001; // Period of 0.1s
518  const double sigmaMeasurements = 2.; // Standard deviation of the measurements: 2 pixels
519  const double radius = 0.25; // Radius of revolution of 0.25m
520  const double w = 2 * M_PI * 10; // Pulsation of the motion of revolution
521  const double phi = 2; // Phase of the motion of revolution
522  const long seedMeasurements = 42; // Seed for the measurements random generator
523  const std::vector<vpColVector> markers = { vpColVector({-0.05, 0.05, 0., 1.})
524  , vpColVector({0.05, 0.05, 0., 1.})
525  , vpColVector({0.05, -0.05, 0., 1.})
526  , vpColVector({-0.05, -0.05, 0., 1.}) }; // Vector of the markers sticked on the object
527  unsigned int nbMarkers = static_cast<unsigned int>(markers.size());
528  std::vector<vpPoint> markersAsVpPoint;
529  for (unsigned int i = 0; i < nbMarkers; ++i) {
530  vpColVector marker = markers[i];
531  markersAsVpPoint.push_back(vpPoint(marker[0], marker[1], marker[2]));
532  }
533 
534  vpHomogeneousMatrix cMw; // Pose of the world frame with regard to the camera frame
535  cMw[0][0] = 1.; cMw[0][1] = 0.; cMw[0][2] = 0.; cMw[0][3] = 0.2;
536  cMw[1][0] = 0.; cMw[1][1] = -1.; cMw[1][2] = 0.; cMw[1][3] = 0.3;
537  cMw[2][0] = 0.; cMw[2][1] = 0.; cMw[2][2] = -1.; cMw[2][3] = 1.;
538 
539  vpHomogeneousMatrix wMo; // Pose of the object frame with regard to the world frame
540  wMo[0][0] = 1.; wMo[0][1] = 0.; wMo[0][2] = 0.; wMo[0][3] = radius;
541  wMo[1][0] = 0.; wMo[1][1] = 1.; wMo[1][2] = 0.; wMo[1][3] = 0;
542  wMo[2][0] = 0.; wMo[2][1] = 0.; wMo[2][2] = 1.; wMo[2][3] = 0.2;
543  vpRotationMatrix wRo; // Rotation between the object frame and world frame
544  wMo.extract(wRo);
545  const double wZ = wMo[2][3];
547 
549  // Create a camera parameter container
550  // Camera initialization with a perspective projection without distortion model
551  const double px = 600., py = 600., u0 = 320., v0 = 240.;
552  vpCameraParameters cam;
553  cam.initPersProjWithoutDistortion(px, py, u0, v0);
555 
556  // Initialize the attributes of the PF
558  const double maxDistanceForLikelihood = args.m_maxDistanceForLikelihood; // The maximum allowed distance between a particle and the measurement, leading to a likelihood equal to 0..
559  const double sigmaLikelihood = maxDistanceForLikelihood / 3.; // The standard deviation of likelihood function.
560  const unsigned int nbParticles = args.m_N; // Number of particles to use
561  const double ampliMaxX = args.m_ampliMaxX, ampliMaxY = args.m_ampliMaxY, ampliMaxZ = args.m_ampliMaxZ;
562  const double ampliMaxOmega = args.m_ampliMaxOmega;
563  const std::vector<double> stdevsPF = { ampliMaxX/3., ampliMaxY/3., ampliMaxZ/3., ampliMaxOmega/3. }; // Standard deviation for each state component
564  const long seedPF = args.m_seedPF; // Seed for the random generators of the PF
565  const unsigned int nbThread = args.m_nbThreads;
567 
569  vpColVector X0(4U); // The initial guess for the state
570  X0[0] = radius; // wX = radius m
571  X0[1] = 0.; // wY = 0m
572  X0[2] = 0.95 * wZ; // Wrong estimation of the position along the z-axis: error of 5%
573  X0[3] = 0.95 * w * dt; // Wrong estimation of the pulsation: error of 5%
575 
578  vpMarkersMeasurements markerMeas(cam, cMw, wRo, markers, sigmaLikelihood, sigmaMeasurements, seedMeasurements);
579  using std::placeholders::_1;
580  using std::placeholders::_2;
585 
587  // Initialize the PF
588  vpParticleFilter<vpColVector> filter(nbParticles, stdevsPF, seedPF, nbThread);
589  filter.init(X0, processFunc, likelihoodFunc, checkResamplingFunc, resamplingFunc);
591 
593 #ifdef VISP_HAVE_DISPLAY
594  // Initialize the plot
595  vpPlot *plot = nullptr;
596  if (args.m_useDisplay) {
597  plot = new vpPlot(1);
598  plot->initGraph(0, 3);
599  plot->setTitle(0, "Position of the robot wX");
600  plot->setUnitX(0, "Position along x(m)");
601  plot->setUnitY(0, "Position along y (m)");
602  plot->setLegend(0, 0, "GT");
603  plot->setLegend(0, 1, "Filtered");
604  plot->setLegend(0, 2, "Measure");
605  plot->initRange(0, -1.25 * radius, 1.25 * radius, -1.25 * radius, 1.25 * radius);
606  plot->setColor(0, 0, vpColor::red);
607  plot->setColor(0, 1, vpColor::blue);
608  plot->setColor(0, 2, vpColor::black);
609  }
610 #endif
612 
614  // Initialize the display
615  // Depending on the detected third party libraries, we instantiate here the
616  // first video device which is available
617 #ifdef VISP_HAVE_DISPLAY
618  std::shared_ptr<vpDisplay> d;
619  vpImage<vpRGBa> Idisp(800, 800, vpRGBa(static_cast<unsigned char>(255)));
620  if (args.m_useDisplay) {
621  d = vpDisplayFactory::createDisplay(Idisp, 800, 50, "Projection of the markers");
622  }
623 #endif
625 
627  // Initialize the simulation
628  vpObjectSimulator object(radius, w, phi, wZ);
629  vpColVector object_pos(4U, 0.);
630  object_pos[3] = 1.;
632 
633  double averageFilteringTime = 0.;
634 
636  const unsigned int nbStepsWarmUp = args.m_nbStepsWarmUp;
637  for (unsigned int i = 0; i < nbStepsWarmUp; ++i) {
638  // Update object pose
639  object_pos = object.move(dt * static_cast<double>(i));
640 
641  // Perform the measurement
642  vpColVector z = markerMeas.measureWithNoise(object_pos);
643 
644  // Use the UKF to filter the measurement
645  double t0 = vpTime::measureTimeMicros();
646  filter.filter(z, dt);
647  averageFilteringTime += vpTime::measureTimeMicros() - t0;
648  }
650 
652  const unsigned int nbSteps = args.m_nbSteps;
653  const double invNbSteps = 1. / static_cast<double>(nbSteps);
654  double meanErrorFilter = 0.;
655  double meanErrorNoise = 0.;
656 
657  for (unsigned int i = 0; i < nbSteps; ++i) {
659  // Update object pose
660  object_pos = object.move(dt * static_cast<double>(i));
662 
664  // Perform the measurement
665  vpColVector z = markerMeas.measureWithNoise(object_pos);
667 
668  double t0 = vpTime::measureTimeMicros();
670  // Use the UKF to filter the measurement
671  filter.filter(z, dt);
673  averageFilteringTime += vpTime::measureTimeMicros() - t0;
674 
676  vpColVector Xest = filter.computeFilteredState();
678 
680  // Prepare the pose computation:
681  // the image points corresponding to the noisy markers are needed
682  std::vector<vpImagePoint> ip;
683  for (unsigned int id = 0; id < nbMarkers; ++id) {
684  vpImagePoint markerProjNoisy(z[2*id + 1], z[2*id]);
685  ip.push_back(markerProjNoisy);
686  }
687 
688  // Compute the pose using the noisy markers
689  vpHomogeneousMatrix cMo_noisy = computePose(markersAsVpPoint, ip, cam);
690  vpHomogeneousMatrix wMo_noisy = cMw.inverse() * cMo_noisy;
692 
694 #ifdef VISP_HAVE_DISPLAY
695  if (args.m_useDisplay) {
697  // Plot the ground truth
698  plot->plot(0, 0, object_pos[0], object_pos[1]);
699 
700  // Plot the filtered state
701  plot->plot(0, 1, Xest[0], Xest[1]);
702 
703  // Plot the noisy pose
704  double wXnoisy = wMo_noisy[0][3];
705  double wYnoisy = wMo_noisy[1][3];
706  plot->plot(0, 2, wXnoisy, wYnoisy);
708 
710  // Display the projection of the markers
711  vpDisplay::display(Idisp);
712  vpColVector zGT = markerMeas.measureGT(object_pos);
713  vpColVector zFilt = markerMeas.state_to_measurement(Xest);
714  for (unsigned int id = 0; id < nbMarkers; ++id) {
715  vpImagePoint markerProjGT(zGT[2*id + 1], zGT[2*id]);
716  vpDisplay::displayCross(Idisp, markerProjGT, 5, vpColor::red);
717 
718  vpImagePoint markerProjFilt(zFilt[2*id + 1], zFilt[2*id]);
719  vpDisplay::displayCross(Idisp, markerProjFilt, 5, vpColor::blue);
720 
721  vpImagePoint markerProjNoisy(z[2*id + 1], z[2*id]);
722  vpDisplay::displayCross(Idisp, markerProjNoisy, 5, vpColor::black);
723  }
724 
725  vpImagePoint ipText(20, 20);
726  vpDisplay::displayText(Idisp, ipText, std::string("GT"), vpColor::red);
727  ipText.set_i(ipText.get_i() + 20);
728  vpDisplay::displayText(Idisp, ipText, std::string("Filtered"), vpColor::blue);
729  ipText.set_i(ipText.get_i() + 20);
730  vpDisplay::displayText(Idisp, ipText, std::string("Measured"), vpColor::black);
731  vpDisplay::flush(Idisp);
732  vpTime::wait(40);
734  }
735 #endif
737 
739  double error = std::sqrt(std::pow(Xest[0] - object_pos[0], 2) + std::pow(Xest[1] - object_pos[1], 2) + std::pow(Xest[2] - object_pos[2], 2));
740  meanErrorFilter += invNbSteps * error;
741  error = std::sqrt(std::pow(wMo_noisy[0][3] - object_pos[0], 2) + std::pow(wMo_noisy[1][3] - object_pos[1], 2) + std::pow(wMo_noisy[2][3] - object_pos[2], 2));
742  meanErrorNoise += invNbSteps * error;
744  }
746 
747  averageFilteringTime = averageFilteringTime / (static_cast<double>(nbSteps) + static_cast<double>(nbStepsWarmUp));
748  std::cout << "Mean error filter = " << meanErrorFilter << std::endl;
749  std::cout << "Mean error noise = " << meanErrorNoise << std::endl;
750  std::cout << "Mean filtering time = " << averageFilteringTime << "us" << std::endl;
751 
752  if (args.m_useDisplay) {
753  std::cout << "Press Enter to quit..." << std::endl;
754  std::cin.get();
755  }
756 
758 #ifdef VISP_HAVE_DISPLAY
759  // Delete the plot if it was allocated
760  if (plot != nullptr) {
761  delete plot;
762  }
763 #endif
765 
766  if (meanErrorFilter > meanErrorNoise) {
767  return EXIT_FAILURE;
768  }
769 
770  return EXIT_SUCCESS;
771 }
772 #else
773 int main()
774 {
775  std::cout << "This example is only available if you compile ViSP in C++11 standard or higher." << std::endl;
776  return EXIT_SUCCESS;
777 }
778 #endif
unsigned int size() const
Return the number of elements of the 2D array.
Definition: vpArray2D.h:349
Generic class defining intrinsic camera parameters.
void initPersProjWithoutDistortion(double px, double py, double u0, double v0)
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
static void display(const vpImage< unsigned char > &I)
static void displayCross(const vpImage< unsigned char > &I, const vpImagePoint &ip, unsigned int size, const vpColor &color, unsigned int thickness=1)
static void flush(const vpImage< unsigned char > &I)
static void displayText(const vpImage< unsigned char > &I, const vpImagePoint &ip, const std::string &s, const vpColor &color)
Class for generating random number with normal probability density.
Definition: vpGaussRand.h:117
Implementation of an homogeneous matrix and operations on such kind of matrices.
vpHomogeneousMatrix & build(const vpTranslationVector &t, const vpRotationMatrix &R)
vpHomogeneousMatrix inverse() const
void extract(vpRotationMatrix &R) const
Class that defines a 2D point in an image. This class is useful for image processing and stores only ...
Definition: vpImagePoint.h:82
static double sqrDistance(const vpImagePoint &iP1, const vpImagePoint &iP2)
vpColVector state_to_measurement(const vpColVector &x)
[Likelihood_function]
vpMarkersMeasurements(const vpCameraParameters &cam, const vpHomogeneousMatrix &cMw, const vpRotationMatrix &wRo, const std::vector< vpColVector > &markers, const double &sigmaDistance, const double &noise_stdev, const long &seed)
Construct a new vpMarkersMeasurements object.
vpColVector measureGT(const vpColVector &wX)
[GT_measurements]
vpColVector measureWithNoise(const vpColVector &wX)
[GT_measurements]
double likelihoodParticle(const vpColVector &x, const vpColVector &meas)
[Likelihood_function]
static void convertPoint(const vpCameraParameters &cam, const double &x, const double &y, double &u, double &v)
[Process_function]
vpColVector move(const double &t)
Move the object to its new position, expressed in the world frame.
vpObjectSimulator(const double &R, const double &w, const double &phi, const double &wZ)
Construct a new vpObjectSimulator object.
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....
static void convertPoint(const vpCameraParameters &cam, const double &u, const double &v, double &x, double &y)
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 initRange(unsigned int graphNum, double xmin, double xmax, double ymin, double ymax)
Definition: vpPlot.cpp:215
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 defines a 3D point in the object frame and allows forward projection of a 3D point in the ...
Definition: vpPoint.h:79
Class used for pose computation from N points (pose from point only). Some of the algorithms implemen...
Definition: vpPose.h:77
void addPoint(const vpPoint &P)
Definition: vpPose.cpp:96
@ DEMENTHON_LAGRANGE_VIRTUAL_VS
Definition: vpPose.h:98
bool computePose(vpPoseMethodType method, vpHomogeneousMatrix &cMo, FuncCheckValidityPose func=nullptr)
Definition: vpPose.cpp:385
Definition: vpRGBa.h:65
Implementation of a rotation matrix and operations on such kind of matrices.
Class that consider the case of a translation vector.
std::shared_ptr< vpDisplay > createDisplay()
Return a smart pointer vpDisplay specialization if a GUI library is available or nullptr otherwise.
VISP_EXPORT int wait(double t0, double t)
VISP_EXPORT double measureTimeMicros()
[Pose_for_display]
bool m_useDisplay
If true, activate the plot and the renderer if VISP_HAVE_DISPLAY is defined.
unsigned int m_nbSteps
?umber of steps for the main loop.
static const int SOFTWARE_CONTINUE
unsigned int m_nbThreads
Number of thread to use in the Particle Filter.
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_maxDistanceForLikelihood
The maximum allowed distance between a particle and the measurement, leading to a likelihood equal to...
double m_ampliMaxZ
Amplitude max of the noise for the state component corresponding to the Z coordinate.
int parseArgs(const int argc, const char *argv[])
double m_ampliMaxOmega
Amplitude max of the noise for the state component corresponding to the pulsation.
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.