65 #include <visp3/core/vpConfig.h>
66 #include <visp3/core/vpCameraParameters.h>
67 #include <visp3/core/vpGaussRand.h>
68 #include <visp3/core/vpHomogeneousMatrix.h>
69 #include <visp3/core/vpMeterPixelConversion.h>
70 #include <visp3/core/vpPixelMeterConversion.h>
72 #ifdef VISP_HAVE_DISPLAY
73 #include <visp3/gui/vpPlot.h>
74 #include <visp3/gui/vpDisplayFactory.h>
77 #include <visp3/vision/vpPose.h>
80 #include <visp3/core/vpUKSigmaDrawerMerwe.h>
81 #include <visp3/core/vpUnscentedKalman.h>
85 #include <visp3/core/vpParticleFilter.h>
88 #ifdef ENABLE_VISP_NAMESPACE
92 #if (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11)
104 x_kPlus1[0] = x[0] * std::cos(x[3]) - x[1] * std::sin(x[3]);
105 x_kPlus1[1] = x[0] * std::sin(x[3]) + x[1] * std::cos(x[3]);
126 for (
unsigned int i = 0; i < point.size(); i++) {
156 vpObjectSimulator(
const double &R,
const double &w,
const double &phi,
const double &wZ,
const double &stdevRng)
161 , m_rng(stdevRng, 0.)
173 double tNoisy = (m_w + m_rng())* t + m_phi;
174 wX[0] = m_R * std::cos(tNoisy);
175 wX[1] = m_R * std::sin(tNoisy);
209 const std::vector<vpColVector> &markers,
const double &noise_stdev,
const long &seed,
210 const double &likelihood_stdev)
215 , m_rng(noise_stdev, 0., seed)
217 double sigmaDistanceSquared = likelihood_stdev * likelihood_stdev;
218 m_constantDenominator = 1. / std::sqrt(2. * M_PI * sigmaDistanceSquared);
219 m_constantExpDenominator = -1. / (2. * sigmaDistanceSquared);
221 const unsigned int nbMarkers =
static_cast<unsigned int>(m_markers.size());
222 for (
unsigned int i = 0; i < nbMarkers; ++i) {
224 m_markersAsVpPoint.push_back(
vpPoint(marker[0], marker[1], marker[2]));
237 unsigned int nbMarkers =
static_cast<unsigned int>(m_markers.size());
242 for (
unsigned int i = 0; i < nbMarkers; ++i) {
244 double u = 0., v = 0.;
263 unsigned int nbMarkers =
static_cast<unsigned int>(m_markers.size());
268 for (
unsigned int i = 0; i < nbMarkers; ++i) {
270 double u = 0., v = 0.;
291 unsigned int sizeMeasurement = measurementsGT.
size();
292 for (
unsigned int i = 0; i < sizeMeasurement; ++i) {
293 measurementsNoisy[i] += m_rng();
295 return measurementsNoisy;
314 unsigned int nbMarkers =
static_cast<unsigned int>(m_markers.size());
315 double likelihood = 0.;
319 const unsigned int sizePt2D = 2;
320 const unsigned int idX = 0, idY = 1, idZ = 2;
321 double sumError = 0.;
325 for (
unsigned int i = 0; i < nbMarkers; ++i) {
329 vpImagePoint measPt(meas[sizePt2D * i + 1], meas[sizePt2D * i]);
334 likelihood = std::exp(m_constantExpDenominator * sumError /
static_cast<double>(nbMarkers)) * m_constantDenominator;
335 likelihood = std::min(likelihood, 1.0);
336 likelihood = std::max(likelihood, 0.);
344 std::vector<vpColVector> m_markers;
345 std::vector<vpPoint> m_markersAsVpPoint;
347 double m_constantDenominator;
348 double m_constantExpDenominator;
356 static const int SOFTWARE_CONTINUE = 42;
358 unsigned int m_nbStepsWarmUp;
359 unsigned int m_nbSteps;
362 double m_maxDistanceForLikelihood;
372 , m_nbStepsWarmUp(200)
375 , m_maxDistanceForLikelihood(10.)
379 , m_ampliMaxOmega(0.02)
388 std::string arg(argv[i]);
389 if ((arg ==
"--nb-steps-main") && ((i+1) < argc)) {
390 m_nbSteps = std::atoi(argv[i + 1]);
393 else if ((arg ==
"--nb-steps-warmup") && ((i+1) < argc)) {
394 m_nbStepsWarmUp = std::atoi(argv[i + 1]);
397 else if ((arg ==
"--max-distance-likelihood") && ((i+1) < argc)) {
398 m_maxDistanceForLikelihood = std::atof(argv[i + 1]);
401 else if (((arg ==
"-N") || (arg ==
"--nb-particles")) && ((i+1) < argc)) {
402 m_N = std::atoi(argv[i + 1]);
405 else if ((arg ==
"--seed") && ((i+1) < argc)) {
406 m_seedPF = std::atoi(argv[i + 1]);
409 else if ((arg ==
"--nb-threads") && ((i+1) < argc)) {
410 m_nbThreads = std::atoi(argv[i + 1]);
413 else if ((arg ==
"--ampli-max-X") && ((i+1) < argc)) {
414 m_ampliMaxX = std::atof(argv[i + 1]);
417 else if ((arg ==
"--ampli-max-Y") && ((i+1) < argc)) {
418 m_ampliMaxY = std::atof(argv[i + 1]);
421 else if ((arg ==
"--ampli-max-Z") && ((i+1) < argc)) {
422 m_ampliMaxZ = std::atof(argv[i + 1]);
425 else if ((arg ==
"--ampli-max-omega") && ((i+1) < argc)) {
426 m_ampliMaxOmega = std::atof(argv[i + 1]);
429 else if (arg ==
"-d") {
430 m_useDisplay =
false;
432 else if ((arg ==
"-h") || (arg ==
"--help")) {
433 printUsage(std::string(argv[0]));
435 defaultArgs.printDetails();
439 std::cout <<
"WARNING: unrecognised argument \"" << arg <<
"\"";
441 std::cout <<
" with associated value(s) { ";
444 bool hasToRun =
true;
445 while ((j < argc) && hasToRun) {
446 std::string nextValue(argv[j]);
447 if (nextValue.find(
"--") == std::string::npos) {
448 std::cout << nextValue <<
" ";
456 std::cout <<
"}" << std::endl;
462 return SOFTWARE_CONTINUE;
466 void printUsage(
const std::string &softName)
468 std::cout <<
"SYNOPSIS" << std::endl;
469 std::cout <<
" " << softName <<
" [--nb-steps-main <uint>] [--nb-steps-warmup <uint>]" << std::endl;
470 std::cout <<
" [--max-distance-likelihood <double>] [-N, --nb-particles <uint>] [--seed <int>] [--nb-threads <int>]" << std::endl;
471 std::cout <<
" [--ampli-max-X <double>] [--ampli-max-Y <double>] [--ampli-max-Z <double>] [--ampli-max-omega <double>]" << std::endl;
472 std::cout <<
" [-d, --no-display] [-h]" << std::endl;
477 std::cout << std::endl << std::endl;
478 std::cout <<
"DETAILS" << std::endl;
479 std::cout <<
" --nb-steps-main" << std::endl;
480 std::cout <<
" Number of steps in the main loop." << std::endl;
481 std::cout <<
" Default: " << m_nbSteps << std::endl;
482 std::cout << std::endl;
483 std::cout <<
" --nb-steps-warmup" << std::endl;
484 std::cout <<
" Number of steps in the warmup loop." << std::endl;
485 std::cout <<
" Default: " << m_nbStepsWarmUp << std::endl;
486 std::cout << std::endl;
487 std::cout <<
" --max-distance-likelihood" << std::endl;
488 std::cout <<
" Maximum mean distance of the projection of the markers corresponding" << std::endl;
489 std::cout <<
" to a particle with the measurements. Above this value, the likelihood of the particle is 0." << std::endl;
490 std::cout <<
" Default: " << m_maxDistanceForLikelihood << std::endl;
491 std::cout << std::endl;
492 std::cout <<
" -N, --nb-particles" << std::endl;
493 std::cout <<
" Number of particles of the Particle Filter." << std::endl;
494 std::cout <<
" Default: " << m_N << std::endl;
495 std::cout << std::endl;
496 std::cout <<
" --seed" << std::endl;
497 std::cout <<
" Seed to initialize the Particle Filter." << std::endl;
498 std::cout <<
" Use a negative value makes to use the current timestamp instead." << std::endl;
499 std::cout <<
" Default: " << m_seedPF << std::endl;
500 std::cout << std::endl;
501 std::cout <<
" --nb-threads" << std::endl;
502 std::cout <<
" Set the number of threads to use in the Particle Filter (only if OpenMP is available)." << std::endl;
503 std::cout <<
" Use a negative value to use the maximum number of threads instead." << std::endl;
504 std::cout <<
" Default: " << m_nbThreads << std::endl;
505 std::cout << std::endl;
506 std::cout <<
" --ampli-max-X" << std::endl;
507 std::cout <<
" Maximum amplitude of the noise added to a particle along the X-axis." << std::endl;
508 std::cout <<
" Default: " << m_ampliMaxX << std::endl;
509 std::cout << std::endl;
510 std::cout <<
" --ampli-max-Y" << std::endl;
511 std::cout <<
" Maximum amplitude of the noise added to a particle along the Y-axis." << std::endl;
512 std::cout <<
" Default: " << m_ampliMaxY << std::endl;
513 std::cout << std::endl;
514 std::cout <<
" --ampli-max-Z" << std::endl;
515 std::cout <<
" Maximum amplitude of the noise added to a particle along the Z-axis." << std::endl;
516 std::cout <<
" Default: " << m_ampliMaxZ << std::endl;
517 std::cout << std::endl;
518 std::cout <<
" --ampli-max-omega" << std::endl;
519 std::cout <<
" Maximum amplitude of the noise added to a particle affecting the pulsation of the motion." << std::endl;
520 std::cout <<
" Default: " << m_ampliMaxOmega << std::endl;
521 std::cout << std::endl;
522 std::cout <<
" -d, --no-display" << std::endl;
523 std::cout <<
" Deactivate display." << std::endl;
524 std::cout <<
" Default: display is ";
525 #ifdef VISP_HAVE_DISPLAY
526 std::cout <<
"ON" << std::endl;
528 std::cout <<
"OFF" << std::endl;
530 std::cout << std::endl;
531 std::cout <<
" -h, --help" << std::endl;
532 std::cout <<
" Display this help." << std::endl;
533 std::cout << std::endl;
538 int main(
const int argc,
const char *argv[])
541 int returnCode = args.
parseArgs(argc, argv);
547 const unsigned int nbIter = 200;
548 const double dt = 0.001;
549 const double sigmaMeasurements = 2.;
550 const double radius = 0.25;
551 const double w = 2 * M_PI * 10;
552 const double phi = 2;
555 const std::vector<vpColVector> markers = {
vpColVector({-0.05, 0.05, 0., 1.}),
559 const unsigned int nbMarkers =
static_cast<unsigned int>(markers.size());
560 std::vector<vpPoint> markersAsVpPoint;
561 for (
unsigned int i = 0; i < nbMarkers; ++i) {
563 markersAsVpPoint.push_back(
vpPoint(marker[0], marker[1], marker[2]));
566 const long seed = 42;
568 cMw[0][0] = 1.; cMw[0][1] = 0.; cMw[0][2] = 0.; cMw[0][3] = 0.2;
569 cMw[1][0] = 0.; cMw[1][1] = -1.; cMw[1][2] = 0.; cMw[1][3] = 0.3;
570 cMw[2][0] = 0.; cMw[2][1] = 0.; cMw[2][2] = -1.; cMw[2][3] = 1.;
573 wMo[0][0] = 1.; wMo[0][1] = 0.; wMo[0][2] = 0.; wMo[0][3] = radius;
574 wMo[1][0] = 0.; wMo[1][1] = 1.; wMo[1][2] = 0.; wMo[1][3] = 0;
575 wMo[2][0] = 0.; wMo[2][1] = 0.; wMo[2][2] = 1.; wMo[2][3] = 0.2;
578 const double wZ = wMo[2][3];
584 double px = 600;
double py = 600;
double u0 = 320;
double v0 = 240;
591 X0[0] = 0.95 * radius * std::cos(phi);
592 X0[1] = 0.95 * radius * std::sin(phi);
594 X0[3] = 0.95 * w * dt;
599 const double sigmaLikelihood = maxDistanceForLikelihood / 3.;
600 const unsigned int nbParticles = args.
m_N;
603 const std::vector<double> stdevsPF = { ampliMaxX/3., ampliMaxY/3., ampliMaxZ/3., ampliMaxOmega/3. };
616 using std::placeholders::_1;
617 using std::placeholders::_2;
626 pfFilter.init(X0, processFunc, likelihoodFunc, checkResamplingFunc, resamplingFunc);
632 std::shared_ptr<vpUKSigmaDrawerAbstract> drawer = std::make_shared<vpUKSigmaDrawerMerwe>(4, 0.001, 2., -1);
636 R1landmark[0][0] = sigmaMeasurements*sigmaMeasurements;
637 R1landmark[1][1] = sigmaMeasurements*sigmaMeasurements;
638 vpMatrix R(2*nbMarkers, 2 * nbMarkers);
639 for (
unsigned int i = 0; i < nbMarkers; ++i) {
640 R.insert(R1landmark, 2*i, 2*i);
644 const double processVariance = 0.000025;
647 Q = Q * processVariance;
667 #ifdef VISP_HAVE_DISPLAY
670 plot.initGraph(0, 4);
671 plot.setTitle(0,
"Position of the robot wX");
672 plot.setUnitX(0,
"Position along x(m)");
673 plot.setUnitY(0,
"Position along y (m)");
674 plot.setLegend(0, 0,
"GT");
675 plot.setLegend(0, 1,
"PF");
676 plot.setLegend(0, 2,
"UKF");
677 plot.setLegend(0, 3,
"Measure");
678 plot.initRange(0, -1.25 * radius, 1.25 * radius, -1.25 * radius, 1.25 * radius);
684 vpPlot plotError(1, 350, 700, 700, 700,
"Error w.r.t. GT");
685 plotError.initGraph(0, 3);
686 plotError.setUnitX(0,
"Time (s)");
687 plotError.setUnitY(0,
"Error (m)");
688 plotError.setLegend(0, 0,
"PF");
689 plotError.setLegend(0, 1,
"UKF");
690 plotError.setLegend(0, 2,
"Measure");
691 plotError.initRange(0, 0, nbIter * dt, 0, radius / 2.);
702 #ifdef VISP_HAVE_DISPLAY
716 for (
unsigned int i = 0; i < nbIter; ++i) {
717 double t = dt *
static_cast<double>(i);
718 std::cout <<
"[Timestep" << i <<
", t = " << t <<
"]" << std::endl;
721 object_pos =
object.move(t);
726 vpColVector z = markerMeas.measureWithNoise(object_pos);
732 pfFilter.filter(z, dt);
744 vpColVector XestPF = pfFilter.computeFilteredState();
751 for (
unsigned int i = 0; i < 3; ++i) {
752 wX_PF[i] = XestPF[i];
753 wX_UKF[i] = XestUKF[i];
761 std::cout <<
" [Particle Filter method] " << std::endl;
762 std::cout <<
" Norm of the error = " << error_PF.
frobeniusNorm() <<
" m^2" << std::endl;
763 std::cout <<
" Fitting duration = " << dtPF <<
" ms" << std::endl;
765 std::cout <<
" [Unscented Kalman Filter method] " << std::endl;
766 std::cout <<
" Norm of the error = " << error_UKF.
frobeniusNorm() <<
" m^2" << std::endl;
767 std::cout <<
" Fitting duration = " << dtUKF <<
" ms" << std::endl;
770 #ifdef VISP_HAVE_DISPLAY
774 std::vector<vpImagePoint> ip;
775 for (
unsigned int id = 0;
id < nbMarkers; ++id) {
777 ip.push_back(markerProjNoisy);
783 double wXnoisy = wMo_noisy[0][3];
784 double wYnoisy = wMo_noisy[1][3];
789 plot.plot(0, 0, object_pos[0], object_pos[1]);
792 plot.plot(0, 1, XestPF[0], XestPF[1]);
796 plot.plot(0, 2, XestUKF[0], XestUKF[1]);
799 plot.plot(0, 3, wXnoisy, wYnoisy);
814 vpColVector zGT = markerMeas.measureGT(object_pos);
815 vpColVector zFiltUkf = markerMeas.state_to_measurement(XestUKF);
816 vpColVector zFiltPF = markerMeas.state_to_measurement(XestPF);
817 for (
unsigned int id = 0;
id < nbMarkers; ++id) {
821 vpImagePoint markerProjFiltPF(zFiltPF[2*
id + 1], zFiltPF[2*
id]);
824 vpImagePoint markerProjFiltUKF(zFiltUkf[2*
id + 1], zFiltUkf[2*
id]);
833 ipText.set_i(ipText.get_i() + 20);
835 ipText.set_i(ipText.get_i() + 20);
837 ipText.set_i(ipText.get_i() + 20);
846 std::cout <<
"Press Enter to quit..." << std::endl;
854 std::cout <<
"This example is only available if you compile ViSP in C++11 standard or higher." << std::endl;
unsigned int size() const
Return the number of elements of the 2D array.
Generic class defining intrinsic camera parameters.
void initPersProjWithoutDistortion(double px, double py, double u0, double v0)
Implementation of column vector and the associated operations.
double frobeniusNorm() const
static const vpColor blue
static const vpColor black
static const vpColor green
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.
Implementation of an homogeneous matrix and operations on such kind of matrices.
vpHomogeneousMatrix & buildFrom(const vpTranslationVector &t, const vpRotationMatrix &R)
vpHomogeneousMatrix inverse() const
vpTranslationVector getTranslationVector() 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 ...
static double sqrDistance(const vpImagePoint &iP1, const vpImagePoint &iP2)
vpMarkersMeasurements(const vpCameraParameters &cam, const vpHomogeneousMatrix &cMw, const vpRotationMatrix &wRo, const std::vector< vpColVector > &markers, const double &noise_stdev, const long &seed, const double &likelihood_stdev)
Construct a new vpMarkersMeasurements object.
vpColVector state_to_measurement(const vpColVector &x)
[Measurement_function]
double likelihood(const vpColVector &x, const vpColVector &meas)
[Noisy_measurements]
vpColVector measureGT(const vpColVector &wX)
[Measurement_function]
vpColVector measureWithNoise(const vpColVector &wX)
[GT_measurements]
Implementation of a matrix and operations on matrices.
static void convertPoint(const vpCameraParameters &cam, const double &x, const double &y, double &u, double &v)
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, const double &stdevRng)
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...
Class that defines a 3D point in the object frame and allows forward projection of a 3D point in the ...
Class used for pose computation from N points (pose from point only). Some of the algorithms implemen...
void addPoint(const vpPoint &P)
@ DEMENTHON_LAGRANGE_VIRTUAL_VS
bool computePose(vpPoseMethodType method, vpHomogeneousMatrix &cMo, FuncCheckValidityPose func=nullptr)
Implementation of a rotation matrix and operations on such kind of matrices.
Class that consider the case of a translation vector.
std::function< vpColVector(const vpColVector &)> vpMeasurementFunction
Measurement function, which converts the prior points in the measurement space. The argument is a poi...
std::function< vpColVector(const vpColVector &, const double &)> vpProcessFunction
Process model function, which projects the sigma points forward in time. The first argument is a sigm...
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()
VISP_EXPORT double measureTimeMs()
int m_nbThreads
Number of thread to use in the Particle Filter.
static const int SOFTWARE_CONTINUE
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.
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.