Visual Servoing Platform  version 3.6.1 under development (2024-11-23)
ukf-linear-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 
59 #include <iostream>
60 
61 // UKF includes
62 #include <visp3/core/vpUKSigmaDrawerMerwe.h>
63 #include <visp3/core/vpUnscentedKalman.h>
64 
65 // ViSP includes
66 #include <visp3/core/vpConfig.h>
67 #include <visp3/core/vpGaussRand.h>
68 #ifdef VISP_HAVE_DISPLAY
69 #include <visp3/gui/vpPlot.h>
70 #endif
71 
72 #if (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11)
73 
74 #ifdef ENABLE_VISP_NAMESPACE
75 using namespace VISP_NAMESPACE_NAME;
76 #endif
77 
85 vpColVector fx(const vpColVector &chi, const double &dt)
86 {
87  vpColVector point(4);
88  point[0] = chi[1] * dt + chi[0];
89  point[1] = chi[1];
90  point[2] = chi[3] * dt + chi[2];
91  point[3] = chi[3];
92  return point;
93 }
94 
101 vpColVector hx(const vpColVector &chi)
102 {
103  vpColVector point(2);
104  point[0] = chi[0];
105  point[1] = chi[2];
106  return point;
107 }
108 
109 int main(const int argc, const char *argv[])
110 {
111  bool opt_useDisplay = true;
112  for (int i = 1; i < argc; ++i) {
113  std::string arg(argv[i]);
114  if (arg == "-d") {
115  opt_useDisplay = false;
116  }
117  else if ((arg == "-h") || (arg == "--help")) {
118  std::cout << "SYNOPSIS" << std::endl;
119  std::cout << " " << argv[0] << " [-d][-h]" << std::endl;
120  std::cout << std::endl << std::endl;
121  std::cout << "DETAILS" << std::endl;
122  std::cout << " -d" << std::endl;
123  std::cout << " Deactivate display." << std::endl;
124  std::cout << std::endl;
125  std::cout << " -h, --help" << std::endl;
126  return 0;
127  }
128  }
129 
130  const double dt = 0.01; // Period of 1s
131  const double gt_dx = 0.01; // Ground truth displacement along x axis between two measurements
132  const double gt_dy = 0.005; // Ground truth displacement along x axis between two measurements
133  vpColVector gt_dX(2); // Ground truth displacement between two measurements
134  gt_dX[0] = gt_dx;
135  gt_dX[1] = gt_dy;
136  const double gt_vx = gt_dx / dt; // Ground truth velocity along x axis
137  const double gt_vy = gt_dy / dt; // Ground truth velocity along y axis
138  const double processVariance = 0.000004;
139  const double sigmaXmeas = 0.05; // Standard deviation of the measure along the x-axis
140  const double sigmaYmeas = 0.05; // Standard deviation of the measure along the y-axis
141 
142  // Initialize the attributes of the UKF
143  std::shared_ptr<vpUKSigmaDrawerAbstract> drawer = std::make_shared<vpUKSigmaDrawerMerwe>(4, 0.3, 2., -1.);
144  vpMatrix P0(4, 4); // The initial guess of the process covariance
145  P0.eye(4, 4);
146  P0 = P0 * 1.;
147  vpMatrix R(2, 2); // The covariance of the noise introduced by the measurement
148  R.eye(2, 2);
149  R = R * 0.01;
150  vpMatrix Q(4, 4, 0.); // The covariance of the process
151  vpMatrix Q1d(2, 2); // The covariance of a process whose states are {x, dx/dt} and for which the variance is 1
152  Q1d[0][0] = std::pow(dt, 3) / 3.;
153  Q1d[0][1] = std::pow(dt, 2)/2.;
154  Q1d[1][0] = std::pow(dt, 2)/2.;
155  Q1d[1][1] = dt;
156  Q.insert(Q1d, 0, 0);
157  Q.insert(Q1d, 2, 2);
158  Q = Q * processVariance;
161 
162  // Initialize the UKF
163  vpUnscentedKalman ukf(Q, R, drawer, f, h);
164  ukf.init(vpColVector({ 0., 0.75 * gt_vx, 0., 0.75 * gt_vy }), P0);
165 
166 #ifdef VISP_HAVE_DISPLAY
167  vpPlot *plot = nullptr;
168  // Initialize the plot
169  if (opt_useDisplay) {
170  plot = new vpPlot(4);
171  plot->initGraph(0, 3);
172  plot->setTitle(0, "Position along X-axis");
173  plot->setUnitX(0, "Time (s)");
174  plot->setUnitY(0, "Position (m)");
175  plot->setLegend(0, 0, "GT");
176  plot->setLegend(0, 1, "Measure");
177  plot->setLegend(0, 2, "Filtered");
178 
179  plot->initGraph(1, 3);
180  plot->setTitle(1, "Velocity along X-axis");
181  plot->setUnitX(1, "Time (s)");
182  plot->setUnitY(1, "Velocity (m/s)");
183  plot->setLegend(1, 0, "GT");
184  plot->setLegend(1, 1, "Measure");
185  plot->setLegend(1, 2, "Filtered");
186 
187  plot->initGraph(2, 3);
188  plot->setTitle(2, "Position along Y-axis");
189  plot->setUnitX(2, "Time (s)");
190  plot->setUnitY(2, "Position (m)");
191  plot->setLegend(2, 0, "GT");
192  plot->setLegend(2, 1, "Measure");
193  plot->setLegend(2, 2, "Filtered");
194 
195  plot->initGraph(3, 3);
196  plot->setTitle(3, "Velocity along Y-axis");
197  plot->setUnitX(3, "Time (s)");
198  plot->setUnitY(3, "Velocity (m/s)");
199  plot->setLegend(3, 0, "GT");
200  plot->setLegend(3, 1, "Measure");
201  plot->setLegend(3, 2, "Filtered");
202  }
203 #endif
204 
205  // Initialize measurement noise
206  vpGaussRand rngX(sigmaXmeas, 0., 4224);
207  vpGaussRand rngY(sigmaYmeas, 0., 2112);
208 
209  // Main loop
210  vpColVector gt_X(2, 0.);
211  vpColVector z_prec(2, 0.);
212  for (int i = 0; i < 100; ++i) {
213  // Perform the measurement
214  double x_meas = gt_X[0] + rngX();
215  double y_meas = gt_X[1] + rngY();
216  vpColVector z(2);
217  z[0] = x_meas;
218  z[1] = y_meas;
219 
220  // Use the UKF to filter the measurement
221  ukf.filter(z, dt);
222  vpColVector Xest = ukf.getXest();
223 
224 #ifdef VISP_HAVE_DISPLAY
225  if (opt_useDisplay) {
226  // Plot the ground truth, measurement and filtered state
227  plot->plot(0, 0, i, gt_X[0]);
228  plot->plot(0, 1, i, x_meas);
229  plot->plot(0, 2, i, Xest[0]);
230 
231  double vX_meas = (x_meas - z_prec[0]) / dt;
232  plot->plot(1, 0, i, gt_vx);
233  plot->plot(1, 1, i, vX_meas);
234  plot->plot(1, 2, i, Xest[1]);
235 
236  plot->plot(2, 0, i, gt_X[1]);
237  plot->plot(2, 1, i, y_meas);
238  plot->plot(2, 2, i, Xest[2]);
239 
240  double vY_meas = (y_meas - z_prec[1]) / dt;
241  plot->plot(3, 0, i, gt_vy);
242  plot->plot(3, 1, i, vY_meas);
243  plot->plot(3, 2, i, Xest[3]);
244  }
245 #endif
246 
247  // Update
248  gt_X += gt_dX;
249  z_prec = z;
250  }
251 
252  if (opt_useDisplay) {
253  std::cout << "Press Enter to quit..." << std::endl;
254  std::cin.get();
255  }
256 
257 #ifdef VISP_HAVE_DISPLAY
258  if (opt_useDisplay) {
259  delete plot;
260  }
261 #endif
262 
263  vpColVector X_GT({ gt_X[0], gt_vx, gt_X[1], gt_vy });
264  vpColVector finalError = ukf.getXest() - X_GT;
265  const double maxError = 0.12;
266  if (finalError.frobeniusNorm() > maxError) {
267  std::cerr << "Error: max tolerated error = " << maxError << ", final error = " << finalError.frobeniusNorm() << std::endl;
268  return -1;
269  }
270  return 0;
271 }
272 #else
273 int main()
274 {
275  std::cout << "This example is only available if you compile ViSP in C++11 standard or higher." << std::endl;
276  return 0;
277 }
278 #endif
Implementation of column vector and the associated operations.
Definition: vpColVector.h:191
double frobeniusNorm() const
Class for generating random number with normal probability density.
Definition: vpGaussRand.h:117
Implementation of a matrix and operations on matrices.
Definition: vpMatrix.h:169
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 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 setTitle(unsigned int graphNum, const std::string &title)
Definition: vpPlot.cpp:510
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...