Tutorial on how to use the Unscented Kalman Filter (UKF) on a complex non-linear use-case. The system is an object, whose coordinate frame origin is the point O, on which are sticked four markers. The object revolves in a plane parallel to the ground around a fixed point W whose coordinate frame is the world frame. The scene is observed by a pinhole camera whose coordinate frame has the origin C and which is fixed to the ceiling.
Some noise is added to the measurement vector to simulate measurements which are not perfect.
#include <visp3/core/vpConfig.h>
#include <visp3/core/vpCameraParameters.h>
#include <visp3/core/vpGaussRand.h>
#include <visp3/core/vpHomogeneousMatrix.h>
#include <visp3/core/vpMeterPixelConversion.h>
#include <visp3/core/vpPixelMeterConversion.h>
#ifdef VISP_HAVE_DISPLAY
#include <visp3/gui/vpPlot.h>
#include <visp3/gui/vpDisplayFactory.h>
#endif
#include <visp3/vision/vpPose.h>
#include <visp3/core/vpUKSigmaDrawerMerwe.h>
#include <visp3/core/vpUnscentedKalman.h>
#ifdef ENABLE_VISP_NAMESPACE
#endif
#if (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11)
{
x_kPlus1[0] = x[0] * std::cos(x[3]) - x[1] * std::sin(x[3]);
x_kPlus1[1] = x[0] * std::sin(x[3]) + x[1] * std::cos(x[3]);
x_kPlus1[2] = x[2];
x_kPlus1[3] = x[3];
return x_kPlus1;
}
{
public:
vpObjectSimulator(
const double &R,
const double &w,
const double &phi,
const double &wZ)
: m_R(R)
, m_w(w)
, m_phi(phi)
, m_wZ(wZ)
{ }
{
wX[0] = m_R * std::cos(m_w * t + m_phi);
wX[1] = m_R * std::sin(m_w * t + m_phi);
wX[2] = m_wZ;
return wX;
}
private:
double m_R;
double m_w;
double m_phi;
const double m_wZ;
};
{
public:
const std::vector<vpColVector> &markers, const double &noise_stdev, const long &seed)
: m_cam(cam)
, m_cMw(cMw)
, m_wRo(wRo)
, m_markers(markers)
, m_rng(noise_stdev, 0., seed)
{ }
{
unsigned int nbMarkers = static_cast<unsigned int>(m_markers.size());
for (unsigned int i = 0; i < nbMarkers; ++i) {
double u = 0., v = 0.;
meas[2*i] = u;
meas[2*i + 1] = v;
}
return meas;
}
{
unsigned int nbMarkers = static_cast<unsigned int>(m_markers.size());
for (unsigned int i = 0; i < nbMarkers; ++i) {
double u = 0., v = 0.;
meas[2*i] = u;
meas[2*i + 1] = v;
}
return meas;
}
{
unsigned int sizeMeasurement = measurementsGT.
size();
for (unsigned int i = 0; i < sizeMeasurement; ++i) {
measurementsNoisy[i] += m_rng();
}
return measurementsNoisy;
}
private:
std::vector<vpColVector> m_markers;
};
{
double x = 0, y = 0;
for (unsigned int i = 0; i < point.size(); i++) {
point[i].set_x(x);
point[i].set_y(y);
}
return cMo;
}
int main()
{
const double dt = 0.001;
const double sigmaMeasurements = 2.;
const double radius = 0.25;
const double w = 2 * M_PI * 10;
const double phi = 2;
const std::vector<vpColVector> markers = {
vpColVector({-0.05, 0.05, 0., 1.}),
const unsigned int nbMarkers = static_cast<unsigned int>(markers.size());
std::vector<vpPoint> markersAsVpPoint;
for (unsigned int i = 0; i < nbMarkers; ++i) {
markersAsVpPoint.push_back(
vpPoint(marker[0], marker[1], marker[2]));
}
const long seed = 42;
cMw[0][0] = 1.; cMw[0][1] = 0.; cMw[0][2] = 0.; cMw[0][3] = 0.2;
cMw[1][0] = 0.; cMw[1][1] = -1.; cMw[1][2] = 0.; cMw[1][3] = 0.3;
cMw[2][0] = 0.; cMw[2][1] = 0.; cMw[2][2] = -1.; cMw[2][3] = 1.;
wMo[0][0] = 1.; wMo[0][1] = 0.; wMo[0][2] = 0.; wMo[0][3] = radius;
wMo[1][0] = 0.; wMo[1][1] = 1.; wMo[1][2] = 0.; wMo[1][3] = 0;
wMo[2][0] = 0.; wMo[2][1] = 0.; wMo[2][2] = 1.; wMo[2][3] = 0.2;
const double wZ = wMo[2][3];
double px = 600; double py = 600; double u0 = 320; double v0 = 240;
std::shared_ptr<vpUKSigmaDrawerAbstract> drawer = std::make_shared<vpUKSigmaDrawerMerwe>(4, 0.001, 2., -1);
R1landmark[0][0] = sigmaMeasurements*sigmaMeasurements;
R1landmark[1][1] = sigmaMeasurements*sigmaMeasurements;
for (unsigned int i = 0; i < nbMarkers; ++i) {
R.insert(R1landmark, 2*i, 2*i);
}
const double processVariance = 0.000025;
Q = Q * processVariance;
P0.eye(4);
P0[0][0] = 1.;
P0[1][1] = 1.;
P0[2][2] = 1.;
P0[2][2] = 5.;
X0[0] = radius;
X0[1] = 0.;
X0[2] = 0.95 * wZ;
X0[3] = 0.75 * w * dt;
using std::placeholders::_1;
ukf.init(X0, P0);
#ifdef VISP_HAVE_DISPLAY
plot.initGraph(0, 3);
plot.setTitle(0, "Position of the robot wX");
plot.setUnitX(0, "Position along x(m)");
plot.setUnitY(0, "Position along y (m)");
plot.setLegend(0, 0, "GT");
plot.setLegend(0, 1, "Filtered");
plot.setLegend(0, 2, "Measure");
plot.initRange(0, -1.25 * radius, 1.25 * radius, -1.25 * radius, 1.25 * radius);
#endif
#ifdef VISP_HAVE_DISPLAY
#endif
object_pos[3] = 1.;
for (unsigned int i = 0; i < 200; ++i) {
object_pos = object.move(dt * static_cast<double>(i));
vpColVector z = markerMeas.measureWithNoise(object_pos);
ukf.filter(z, dt);
#ifdef VISP_HAVE_DISPLAY
std::vector<vpImagePoint> ip;
for (unsigned int id = 0; id < nbMarkers; ++id) {
ip.push_back(markerProjNoisy);
}
double wXnoisy = wMo_noisy[0][3];
double wYnoisy = wMo_noisy[1][3];
plot.plot(0, 0, object_pos[0], object_pos[1]);
plot.plot(0, 1, Xest[0], Xest[1]);
plot.plot(0, 2, wXnoisy, wYnoisy);
vpColVector zFilt = markerMeas.state_to_measurement(Xest);
for (unsigned int id = 0; id < nbMarkers; ++id) {
}
ipText.set_i(ipText.get_i() + 20);
ipText.set_i(ipText.get_i() + 20);
#endif
}
std::cout << "Press Enter to quit..." << std::endl;
std::cin.get();
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
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 & buildFrom(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 ...
vpColVector state_to_measurement(const vpColVector &x)
[Measurement_function]
Implementation of a matrix and operations on matrices.
static void convertPoint(const vpCameraParameters &cam, const double &x, const double &y, double &u, double &v)
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)