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