86#include <visp3/core/vpUKSigmaDrawerMerwe.h>
87#include <visp3/core/vpUnscentedKalman.h>
90#include <visp3/core/vpConfig.h>
91#include <visp3/core/vpGaussRand.h>
92#ifdef VISP_HAVE_DISPLAY
93#include <visp3/gui/vpPlot.h>
96#if (VISP_CXX_STANDARD >= VISP_CXX_STANDARD_11)
98#ifdef ENABLE_VISP_NAMESPACE
114 point[0] = chi[1] *
dt + chi[0];
116 point[2] = chi[3] *
dt + chi[2];
127double normalizeAngle(
const double &angle)
130 double angleInMinPiPi = angleIn0to2pi;
131 if (angleInMinPiPi > M_PI) {
133 angleInMinPiPi -= 2. * M_PI;
135 return angleInMinPiPi;
146vpColVector measurementMean(
const std::vector<vpColVector> &measurements,
const std::vector<double> &wm)
148 const unsigned int nbPoints =
static_cast<unsigned int>(measurements.size());
149 const unsigned int sizeMeasurement = measurements[0].
size();
153 for (
unsigned int i = 0;
i < nbPoints; ++
i) {
154 mean[0] += wm[
i] * measurements[
i][0];
155 sumCos += wm[
i] * std::cos(measurements[i][1]);
156 sumSin += wm[
i] * std::sin(measurements[i][1]);
159 mean[1] = std::atan2(sumSin, sumCos);
175 res[1] = normalizeAngle(res[1]);
195 vpRadarStation(
const double &x,
const double &y,
const double &range_std,
const double &elev_angle_std)
198 , m_rngRange(range_std, 0., 4224)
199 , m_rngElevAngle(elev_angle_std, 0., 2112)
211 double dx = chi[0] - m_x;
212 double dy = chi[2] - m_y;
213 meas[0] = std::sqrt(dx * dx + dy * dy);
214 meas[1] = std::atan2(dy, dx);
228 double dx = pos[0] - m_x;
229 double dy = pos[1] - m_y;
230 double range = std::sqrt(dx * dx + dy * dy);
231 double elevAngle = std::atan2(dy, dx);
233 measurements[0] = range;
234 measurements[1] = elevAngle;
250 measurementsNoisy[0] += m_rngRange();
251 measurementsNoisy[1] += m_rngElevAngle();
252 return measurementsNoisy;
278 , m_rngVel(vel_std, 0.)
293 dx[0] += m_rngVel() * dt;
294 dx[1] += m_rngVel() * dt;
305int main(
const int argc,
const char *argv[])
307 bool opt_useDisplay =
true;
308 bool opt_useUserInteraction =
true;
309 for (
int i = 1;
i < argc; ++
i) {
310 std::string arg(argv[i]);
312 opt_useDisplay =
false;
315 opt_useUserInteraction =
false;
317 else if ((arg ==
"-h") || (arg ==
"--help")) {
318 std::cout <<
"SYNOPSIS" << std::endl;
319 std::cout <<
" " << argv[0] <<
" [-d][-h]" << std::endl;
320 std::cout << std::endl << std::endl;
321 std::cout <<
"DETAILS" << std::endl;
322 std::cout <<
" -d" << std::endl;
323 std::cout <<
" Deactivate display." << std::endl;
324 std::cout <<
" -c" << std::endl;
325 std::cout <<
" Deactivate user interaction." << std::endl;
326 std::cout << std::endl;
327 std::cout <<
" -h, --help" << std::endl;
332 const double dt = 3.;
333 const double sigmaRange = 5;
335 const double stdevAircraftVelocity = 0.2;
342 std::shared_ptr<vpUKSigmaDrawerAbstract>
drawer = std::make_shared<vpUKSigmaDrawerMerwe>(4, 0.1, 2., -1.);
345 R[0][0] = sigmaRange*sigmaRange;
346 R[1][1] = sigmaElevAngle*sigmaElevAngle;
348 const double processVariance = 0.1;
351 Q1d[0][0] = std::pow(dt, 3) / 3.;
352 Q1d[0][1] = std::pow(dt, 2)/2.;
353 Q1d[1][0] = std::pow(dt, 2)/2.;
357 Q =
Q * processVariance;
361 P0[0][0] = std::pow(300, 2);
362 P0[1][1] = std::pow(30, 2);
363 P0[2][2] = std::pow(150, 2);
364 P0[3][3] = std::pow(30, 2);
374 using std::placeholders::_1;
380 ukf.setMeasurementMeanFunction(measurementMean);
381 ukf.setMeasurementResidualFunction(measurementResidual);
383#ifdef VISP_HAVE_DISPLAY
385 if (opt_useDisplay) {
388 plot->initGraph(0, 2);
389 plot->setTitle(0,
"Position along X-axis");
390 plot->setUnitX(0,
"Time (s)");
391 plot->setUnitY(0,
"Position (m)");
392 plot->setLegend(0, 0,
"GT");
393 plot->setLegend(0, 1,
"Filtered");
395 plot->initGraph(1, 2);
396 plot->setTitle(1,
"Velocity along X-axis");
397 plot->setUnitX(1,
"Time (s)");
398 plot->setUnitY(1,
"Velocity (m/s)");
399 plot->setLegend(1, 0,
"GT");
400 plot->setLegend(1, 1,
"Filtered");
402 plot->initGraph(2, 2);
403 plot->setTitle(2,
"Position along Y-axis");
404 plot->setUnitX(2,
"Time (s)");
405 plot->setUnitY(2,
"Position (m)");
406 plot->setLegend(2, 0,
"GT");
407 plot->setLegend(2, 1,
"Filtered");
409 plot->initGraph(3, 2);
410 plot->setTitle(3,
"Velocity along Y-axis");
411 plot->setUnitX(3,
"Time (s)");
412 plot->setUnitY(3,
"Velocity (m/s)");
413 plot->setLegend(3, 0,
"GT");
414 plot->setLegend(3, 1,
"Filtered");
417 (void)opt_useDisplay;
430 for (
int i = 0;
i < 500; ++
i) {
440#ifdef VISP_HAVE_DISPLAY
441 if (opt_useDisplay) {
443 plot->plot(0, 0, i, gt_X[0]);
444 plot->plot(0, 1, i, Xest[0]);
446 plot->plot(1, 0, i, gt_V[0]);
447 plot->plot(1, 1, i, Xest[1]);
449 plot->plot(2, 0, i, gt_X[1]);
450 plot->plot(2, 1, i, Xest[2]);
452 plot->plot(3, 0, i, gt_V[1]);
453 plot->plot(3, 1, i, Xest[3]);
461 if (opt_useUserInteraction) {
462 std::cout <<
"Press Enter to quit..." << std::endl;
466#ifdef VISP_HAVE_DISPLAY
467 if (opt_useDisplay) {
472 vpColVector X_GT({ gt_Xprec[0], gt_Vprec[0], gt_Xprec[1], gt_Vprec[1] });
474 const double maxError = 2.5;
475 if (finalError.frobeniusNorm() > maxError) {
476 std::cerr <<
"Error: max tolerated error = " << maxError <<
", final error = " << finalError.frobeniusNorm() << std::endl;
485 std::cout <<
"This example is only available if you compile ViSP in C++11 standard or higher." << std::endl;
Class to simulate a flying aircraft.
vpColVector update(const double &dt)
Compute the new position of the aircraft after dt seconds have passed since the last update.
vpACSimulator(const vpColVector &X0, const vpColVector &vel, const double &vel_std)
Construct a new vpACSimulator object.
unsigned int size() const
Return the number of elements of the 2D array.
Implementation of column vector and the associated operations.
Class for generating random number with normal probability density.
static double rad(double deg)
static float modulo(const float &value, const float &modulo)
Gives the rest of value divided by modulo when the quotient can only be an integer.
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...
Class that permits to convert the position of the aircraft into range and elevation angle measurement...
vpColVector state_to_measurement(const vpColVector &chi)
Convert the prior of the UKF into the measurement space.
vpRadarStation(const double &x, const double &y, const double &range_std, const double &elev_angle_std)
Construct a new vpRadarStation object.
vpColVector measureWithNoise(const vpColVector &pos)
Noisy measurement of the range and elevation angle that correspond to pos.
vpColVector measureGT(const vpColVector &pos)
Perfect measurement of the range and elevation angle that correspond to pos.
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...
ColVector measurementResidual(ColVector meas, ColVector to_subtract)