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];
109 int main(
const int argc,
const char *argv[])
111 bool opt_useDisplay =
true;
112 for (
int i = 1; i < argc; ++i) {
113 std::string arg(argv[i]);
115 opt_useDisplay =
false;
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;
130 const double dt = 0.01;
131 const double gt_dx = 0.01;
132 const double gt_dy = 0.005;
136 const double gt_vx = gt_dx / dt;
137 const double gt_vy = gt_dy / dt;
138 const double processVariance = 0.000004;
139 const double sigmaXmeas = 0.05;
140 const double sigmaYmeas = 0.05;
143 std::shared_ptr<vpUKSigmaDrawerAbstract> drawer = std::make_shared<vpUKSigmaDrawerMerwe>(4, 0.3, 2., -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.;
158 Q = Q * processVariance;
164 ukf.init(
vpColVector({ 0., 0.75 * gt_vx, 0., 0.75 * gt_vy }), P0);
166 #ifdef VISP_HAVE_DISPLAY
169 if (opt_useDisplay) {
172 plot->
setTitle(0,
"Position along X-axis");
180 plot->
setTitle(1,
"Velocity along X-axis");
182 plot->
setUnitY(1,
"Velocity (m/s)");
188 plot->
setTitle(2,
"Position along Y-axis");
196 plot->
setTitle(3,
"Velocity along Y-axis");
198 plot->
setUnitY(3,
"Velocity (m/s)");
212 for (
int i = 0; i < 100; ++i) {
214 double x_meas = gt_X[0] + rngX();
215 double y_meas = gt_X[1] + rngY();
224 #ifdef VISP_HAVE_DISPLAY
225 if (opt_useDisplay) {
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]);
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]);
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]);
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]);
252 if (opt_useDisplay) {
253 std::cout <<
"Press Enter to quit..." << std::endl;
257 #ifdef VISP_HAVE_DISPLAY
258 if (opt_useDisplay) {
263 vpColVector X_GT({ gt_X[0], gt_vx, gt_X[1], gt_vy });
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;
275 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.
double frobeniusNorm() const
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...
void initGraph(unsigned int graphNum, unsigned int curveNbr)
void setUnitY(unsigned int graphNum, const std::string &unity)
void setLegend(unsigned int graphNum, unsigned int curveNum, const std::string &legend)
void plot(unsigned int graphNum, unsigned int curveNum, double x, double y)
void setUnitX(unsigned int graphNum, const std::string &unitx)
void setTitle(unsigned int graphNum, const std::string &title)
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...