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>
71 #include <visp3/vision/vpPose.h>
74 #include <visp3/core/vpParticleFilter.h>
77 #ifdef ENABLE_VISP_NAMESPACE
81 #if (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11)
93 x_kPlus1[0] = x[0] * std::cos(x[3]) - x[1] * std::sin(x[3]);
94 x_kPlus1[1] = x[0] * std::sin(x[3]) + x[1] * std::cos(x[3]);
132 wX[0] = m_R * std::cos(m_w * t + m_phi);
133 wX[1] = m_R * std::sin(m_w * t + m_phi);
166 const std::vector<vpColVector> &markers,
const double &sigmaDistance,
167 const double &noise_stdev,
const long &seed)
172 , m_rng(noise_stdev, 0., seed)
174 double sigmaDistanceSquared = sigmaDistance * sigmaDistance;
175 m_constantDenominator = 1. / std::sqrt(2. * M_PI * sigmaDistanceSquared);
176 m_constantExpDenominator = -1. / (2. * sigmaDistanceSquared);
194 unsigned int nbMarkers =
static_cast<unsigned int>(m_markers.size());
195 double likelihood = 0.;
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) {
206 vpImagePoint measPt(meas[sizePt2D * i + 1], meas[sizePt2D * i]);
210 likelihood = std::exp(m_constantExpDenominator * sumError /
static_cast<double>(nbMarkers)) * m_constantDenominator;
211 likelihood = std::min(likelihood, 1.0);
212 likelihood = std::max(likelihood, 0.);
225 unsigned int nbMarkers =
static_cast<unsigned int>(m_markers.size());
229 wMo.
build(wTo, m_wRo);
230 for (
unsigned int i = 0; i < nbMarkers; ++i) {
232 double u = 0., v = 0.;
250 unsigned int nbMarkers =
static_cast<unsigned int>(m_markers.size());
254 wMo.
build(wTo, m_wRo);
255 for (
unsigned int i = 0; i < nbMarkers; ++i) {
257 double u = 0., v = 0.;
278 unsigned int sizeMeasurement = measurementsGT.
size();
279 for (
unsigned int i = 0; i < sizeMeasurement; ++i) {
280 measurementsNoisy[i] += m_rng();
282 return measurementsNoisy;
290 std::vector<vpColVector> m_markers;
291 double m_constantDenominator;
292 double m_constantExpDenominator;
311 for (
unsigned int i = 0; i < point.size(); i++) {
327 static const int SOFTWARE_CONTINUE = 42;
343 , m_nbStepsWarmUp(200)
346 , m_maxDistanceForLikelihood(10.)
350 , m_ampliMaxOmega(0.02)
359 std::string arg(argv[i]);
360 if ((arg ==
"--nb-steps-main") && ((i+1) < argc)) {
361 m_nbSteps = std::atoi(argv[i + 1]);
364 else if ((arg ==
"--nb-steps-warmup") && ((i+1) < argc)) {
365 m_nbStepsWarmUp = std::atoi(argv[i + 1]);
368 else if ((arg ==
"--max-distance-likelihood") && ((i+1) < argc)) {
369 m_maxDistanceForLikelihood = std::atof(argv[i + 1]);
372 else if (((arg ==
"-N") || (arg ==
"--nb-particles")) && ((i+1) < argc)) {
373 m_N = std::atoi(argv[i + 1]);
376 else if ((arg ==
"--seed") && ((i+1) < argc)) {
377 m_seedPF = std::atoi(argv[i + 1]);
380 else if ((arg ==
"--nb-threads") && ((i+1) < argc)) {
381 m_nbThreads = std::atoi(argv[i + 1]);
384 else if ((arg ==
"--ampli-max-X") && ((i+1) < argc)) {
385 m_ampliMaxX = std::atof(argv[i + 1]);
388 else if ((arg ==
"--ampli-max-Y") && ((i+1) < argc)) {
389 m_ampliMaxY = std::atof(argv[i + 1]);
392 else if ((arg ==
"--ampli-max-Z") && ((i+1) < argc)) {
393 m_ampliMaxZ = std::atof(argv[i + 1]);
396 else if ((arg ==
"--ampli-max-omega") && ((i+1) < argc)) {
397 m_ampliMaxOmega = std::atof(argv[i + 1]);
400 else if (arg ==
"-d") {
401 m_useDisplay =
false;
403 else if ((arg ==
"-h") || (arg ==
"--help")) {
404 printUsage(std::string(argv[0]));
406 defaultArgs.printDetails();
410 std::cout <<
"WARNING: unrecognised argument \"" << arg <<
"\"";
412 std::cout <<
" with associated value(s) { ";
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 <<
" ";
427 std::cout <<
"}" << std::endl;
433 return SOFTWARE_CONTINUE;
437 void printUsage(
const std::string &softName)
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;
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;
499 std::cout <<
"OFF" << std::endl;
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;
508 int main(
const int argc,
const char *argv[])
511 int returnCode = args.
parseArgs(argc, argv);
517 const double dt = 0.001;
518 const double sigmaMeasurements = 2.;
519 const double radius = 0.25;
520 const double w = 2 * M_PI * 10;
521 const double phi = 2;
522 const long seedMeasurements = 42;
523 const std::vector<vpColVector> markers = {
vpColVector({-0.05, 0.05, 0., 1.})
527 unsigned int nbMarkers =
static_cast<unsigned int>(markers.size());
528 std::vector<vpPoint> markersAsVpPoint;
529 for (
unsigned int i = 0; i < nbMarkers; ++i) {
531 markersAsVpPoint.push_back(
vpPoint(marker[0], marker[1], marker[2]));
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.;
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;
545 const double wZ = wMo[2][3];
551 const double px = 600., py = 600., u0 = 320., v0 = 240.;
559 const double sigmaLikelihood = maxDistanceForLikelihood / 3.;
560 const unsigned int nbParticles = args.
m_N;
563 const std::vector<double> stdevsPF = { ampliMaxX/3., ampliMaxY/3., ampliMaxZ/3., ampliMaxOmega/3. };
573 X0[3] = 0.95 * w * dt;
578 vpMarkersMeasurements markerMeas(cam, cMw, wRo, markers, sigmaLikelihood, sigmaMeasurements, seedMeasurements);
579 using std::placeholders::_1;
580 using std::placeholders::_2;
589 filter.init(X0, processFunc, likelihoodFunc, checkResamplingFunc, resamplingFunc);
593 #ifdef VISP_HAVE_DISPLAY
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)");
605 plot->
initRange(0, -1.25 * radius, 1.25 * radius, -1.25 * radius, 1.25 * radius);
617 #ifdef VISP_HAVE_DISPLAY
618 std::shared_ptr<vpDisplay> d;
633 double averageFilteringTime = 0.;
637 for (
unsigned int i = 0; i < nbStepsWarmUp; ++i) {
639 object_pos =
object.move(dt *
static_cast<double>(i));
642 vpColVector z = markerMeas.measureWithNoise(object_pos);
646 filter.filter(z, dt);
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.;
657 for (
unsigned int i = 0; i < nbSteps; ++i) {
660 object_pos =
object.move(dt *
static_cast<double>(i));
665 vpColVector z = markerMeas.measureWithNoise(object_pos);
671 filter.filter(z, dt);
682 std::vector<vpImagePoint> ip;
683 for (
unsigned int id = 0;
id < nbMarkers; ++id) {
685 ip.push_back(markerProjNoisy);
694 #ifdef VISP_HAVE_DISPLAY
698 plot->
plot(0, 0, object_pos[0], object_pos[1]);
701 plot->
plot(0, 1, Xest[0], Xest[1]);
704 double wXnoisy = wMo_noisy[0][3];
705 double wYnoisy = wMo_noisy[1][3];
706 plot->
plot(0, 2, wXnoisy, wYnoisy);
712 vpColVector zGT = markerMeas.measureGT(object_pos);
713 vpColVector zFilt = markerMeas.state_to_measurement(Xest);
714 for (
unsigned int id = 0;
id < nbMarkers; ++id) {
718 vpImagePoint markerProjFilt(zFilt[2*
id + 1], zFilt[2*
id]);
727 ipText.set_i(ipText.get_i() + 20);
729 ipText.set_i(ipText.get_i() + 20);
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;
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;
753 std::cout <<
"Press Enter to quit..." << std::endl;
758 #ifdef VISP_HAVE_DISPLAY
760 if (plot !=
nullptr) {
766 if (meanErrorFilter > meanErrorNoise) {
775 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.
static const vpColor blue
static const vpColor black
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 & 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 ...
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)
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...
void initGraph(unsigned int graphNum, unsigned int curveNbr)
void setUnitY(unsigned int graphNum, const std::string &unity)
void initRange(unsigned int graphNum, double xmin, double xmax, double ymin, double ymax)
void setLegend(unsigned int graphNum, unsigned int curveNum, const std::string &legend)
void plot(unsigned int graphNum, unsigned int curveNum, double x, double y)
void setUnitX(unsigned int graphNum, const std::string &unitx)
void setColor(unsigned int graphNum, unsigned int curveNum, vpColor color)
void setTitle(unsigned int graphNum, const std::string &title)
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::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()
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.