Example of a simple linear use-case of the Unscented Kalman Filter (UKF). Using a UKF in this case is not necessary, it is done for learning purpose only.
The system we are interested in is a system moving on a 2D-plane.
Some noise is added to the measurement vector to simulate a sensor which is not perfect.
#include <iostream>
#include <visp3/core/vpUKSigmaDrawerMerwe.h>
#include <visp3/core/vpUnscentedKalman.h>
#include <visp3/core/vpConfig.h>
#include <visp3/core/vpGaussRand.h>
#ifdef VISP_HAVE_DISPLAY
#include <visp3/gui/vpPlot.h>
#endif
#if (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11)
#ifdef ENABLE_VISP_NAMESPACE
#endif
{
point[0] = chi[1] * dt + chi[0];
point[1] = chi[1];
point[2] = chi[3] * dt + chi[2];
point[3] = chi[3];
return point;
}
{
point[0] = chi[0];
point[1] = chi[2];
return point;
}
int main(const int argc, const char *argv[])
{
bool opt_useDisplay = true;
bool opt_useUserInteraction = true;
for (
int i = 1;
i < argc; ++
i) {
std::string arg(argv[i]);
if (arg == "-d") {
opt_useDisplay = false;
}
if (arg == "-c") {
opt_useUserInteraction = false;
}
else if ((arg == "-h") || (arg == "--help")) {
std::cout << "SYNOPSIS" << std::endl;
std::cout << " " << argv[0] << " [-d][-h]" << std::endl;
std::cout << std::endl << std::endl;
std::cout << "DETAILS" << std::endl;
std::cout << " -d" << std::endl;
std::cout << " Deactivate display." << std::endl;
std::cout << " -c" << std::endl;
std::cout << " Deactivate user interaction." << std::endl;
std::cout << std::endl;
std::cout << " -h, --help" << std::endl;
return 0;
}
}
const double gt_dx = 0.01;
const double gt_dy = 0.005;
const double processVariance = 0.000004;
const double sigmaXmeas = 0.05;
const double sigmaYmeas = 0.05;
std::shared_ptr<vpUKSigmaDrawerAbstract>
drawer = std::make_shared<vpUKSigmaDrawerMerwe>(4, 0.3, 2., -1.);
Q1d[0][0] = std::pow(dt, 3) / 3.;
Q1d[0][1] = std::pow(dt, 2)/2.;
Q1d[1][0] = std::pow(dt, 2)/2.;
#ifdef VISP_HAVE_DISPLAY
if (opt_useDisplay) {
plot->setTitle(0,
"Position along X-axis");
plot->setUnitX(0,
"Time (s)");
plot->setUnitY(0,
"Position (m)");
plot->setLegend(0, 0,
"GT");
plot->setLegend(0, 1,
"Measure");
plot->setLegend(0, 2,
"Filtered");
plot->setTitle(1,
"Velocity along X-axis");
plot->setUnitX(1,
"Time (s)");
plot->setUnitY(1,
"Velocity (m/s)");
plot->setLegend(1, 0,
"GT");
plot->setLegend(1, 1,
"Measure");
plot->setLegend(1, 2,
"Filtered");
plot->setTitle(2,
"Position along Y-axis");
plot->setUnitX(2,
"Time (s)");
plot->setUnitY(2,
"Position (m)");
plot->setLegend(2, 0,
"GT");
plot->setLegend(2, 1,
"Measure");
plot->setLegend(2, 2,
"Filtered");
plot->setTitle(3,
"Velocity along Y-axis");
plot->setUnitX(3,
"Time (s)");
plot->setUnitY(3,
"Velocity (m/s)");
plot->setLegend(3, 0,
"GT");
plot->setLegend(3, 1,
"Measure");
plot->setLegend(3, 2,
"Filtered");
}
#else
(void)opt_useDisplay;
#endif
for (
int i = 0;
i < 100; ++
i) {
#ifdef VISP_HAVE_DISPLAY
if (opt_useDisplay) {
plot->plot(0, 0, i, gt_X[0]);
plot->plot(0, 1, i, x_meas);
plot->plot(0, 2, i, Xest[0]);
plot->plot(1, 0, i, gt_vx);
plot->plot(1, 1, i, vX_meas);
plot->plot(1, 2, i, Xest[1]);
plot->plot(2, 0, i, gt_X[1]);
plot->plot(2, 1, i, y_meas);
plot->plot(2, 2, i, Xest[2]);
plot->plot(3, 0, i, gt_vy);
plot->plot(3, 1, i, vY_meas);
plot->plot(3, 2, i, Xest[3]);
}
#endif
}
if (opt_useUserInteraction) {
std::cout << "Press Enter to quit..." << std::endl;
std::cin.get();
}
#ifdef VISP_HAVE_DISPLAY
if (opt_useDisplay) {
}
#endif
const double maxError = 0.12;
if (finalError.frobeniusNorm() > maxError) {
std::cerr << "Error: max tolerated error = " << maxError << ", final error = " << finalError.frobeniusNorm() << std::endl;
return -1;
}
return 0;
}
#else
int main()
{
std::cout << "This example is only available if you compile ViSP in C++11 standard or higher." << std::endl;
return 0;
}
#endif
Implementation of column vector and the associated operations.
Class for generating random number with normal probability density.
Implementation of a matrix and operations on matrices.
This class enables real time drawing of 2D or 3D graphics. An instance of the class open a window whi...
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...