62#include <visp3/core/vpUKSigmaDrawerMerwe.h>
63#include <visp3/core/vpUnscentedKalman.h>
66#include <visp3/core/vpConfig.h>
67#include <visp3/core/vpGaussRand.h>
68#ifdef VISP_HAVE_DISPLAY
69#include <visp3/gui/vpPlot.h>
72#if (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11)
74#ifdef ENABLE_VISP_NAMESPACE
88 point[0] = chi[1] *
dt + chi[0];
90 point[2] = chi[3] *
dt + chi[2];
109int main(
const int argc,
const char *argv[])
111 bool opt_useDisplay =
true;
112 bool opt_useUserInteraction =
true;
113 for (
int i = 1;
i < argc; ++
i) {
114 std::string arg(argv[i]);
116 opt_useDisplay =
false;
119 opt_useUserInteraction =
false;
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;
136 const double dt = 0.01;
137 const double gt_dx = 0.01;
138 const double gt_dy = 0.005;
144 const double processVariance = 0.000004;
145 const double sigmaXmeas = 0.05;
146 const double sigmaYmeas = 0.05;
149 std::shared_ptr<vpUKSigmaDrawerAbstract>
drawer = std::make_shared<vpUKSigmaDrawerMerwe>(4, 0.3, 2., -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.;
164 Q =
Q * processVariance;
172#ifdef VISP_HAVE_DISPLAY
175 if (opt_useDisplay) {
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");
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");
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");
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");
210 (void)opt_useDisplay;
220 for (
int i = 0;
i < 100; ++
i) {
232#ifdef VISP_HAVE_DISPLAY
233 if (opt_useDisplay) {
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]);
240 plot->plot(1, 0, i, gt_vx);
241 plot->plot(1, 1, i, vX_meas);
242 plot->plot(1, 2, i, Xest[1]);
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]);
249 plot->plot(3, 0, i, gt_vy);
250 plot->plot(3, 1, i, vY_meas);
251 plot->plot(3, 2, i, Xest[3]);
260 if (opt_useUserInteraction) {
261 std::cout <<
"Press Enter to quit..." << std::endl;
265#ifdef VISP_HAVE_DISPLAY
266 if (opt_useDisplay) {
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;
283 std::cout <<
"This example is only available if you compile ViSP in C++11 standard or higher." << std::endl;
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...