Here we use an example with a nonlinear measurement function. The x and y values are measured by a distance and an elevation, giving a nonlinear measure function h(x)=[sqrt(x^2+y^2),atan(y,x)]. The function vector/matrix is specified using a lambda function wrapped into a convenience macro; FCN_XUW
using namespace std;
{
arma::uword Nsamp = 120;
arma::uword N = 6;
arma::uword M = 2;
arma::uword L = 0;
double P0 = 50;
double Q0 = 0.001;
double R0 = 8;
double dT = 0.1;
arma::mat x = { 0, 5, 10, 50, -0.5, -9.8 };
arma::inplace_trans( x );
arma::mat x_init( x * 0.5 );
arma::mat A = { { 1, 0, dT, 0, dT * dT / 2, 0 }, { 0, 1, 0, dT, 0, dT * dT / 2 }, { 0, 0, 1, 0, dT, 0 }, { 0, 0, 0, 1, 0, dT }, { 0, 0, 0, 0, 1, 0 }, { 0, 0, 0, 0, 0, 1 } };
arma::mat Q = Q0 * arma::diagmat( arma::vec( "1 1 0.1 0.1 0.01 0.01" ) );
{
return sqrt( x( 0 ) * x( 0 ) + x( 1 ) * x( 1 ) );
};
{
return atan2( x( 1 ), x( 0 ) );
};
arma::mat P = P0 * arma::eye<arma::mat>( N, N );
arma::mat R = { { 1, 0 }, { 0, 0.005 } };
R *= R0;
arma::mat z( M, Nsamp, arma::fill::zeros );
arma::mat z0( M, Nsamp, arma::fill::zeros );
for( arma::uword n = 0; n < Nsamp; n++ )
{
arma::mat v0( N, 1, arma::fill::zeros );
x = A * x + Q * arma::randn( N, 1 );
z0( 0, n ) = x( 0 );
z0( 1, n ) = x( 1 );
z.col( n ) = eval_fcn( h, z0.col( n ) ) + 0.5 * R * arma::randn( M, 1 );
}
arma::mat xhat_log( N, Nsamp );
arma::mat e_log( M, Nsamp );
arma::cube P_log( N, N, Nsamp );
arma::mat xs_log( M, Nsamp );
arma::cube Ps_log( N, N, Nsamp );
arma::cube K_log( N, M, Nsamp );
for( arma::uword n = 0; n < Nsamp; n++ )
{
}
kalman.
rts_smooth( xhat_log, P_log, xs_log, Ps_log );
gp0.
window(
"Plot", 10, 10, 500, 500 );
gp0.
plot_add( z0.row( 0 ), z0.row( 1 ),
"True Y",
"lines dashtype 2 linecolor \"black\"" );
gp0.
plot_add( arma::mat( z.row( 0 ) % cos( z.row( 1 ) ) ), arma::mat( z.row( 0 ) % sin( z.row( 1 ) ) ),
"Meas Y",
"points" );
gp0.
plot_add( xhat_log.row( 0 ), xhat_log.row( 1 ),
"Kalman x hat" );
gp0.
plot_add( xs_log.row( 0 ), xs_log.row( 1 ),
"RTS smooth" );
gp1.
window(
"Plot", 800, 10, 500, 500 );
gp1.
plot_add( xhat_log.row( 4 ),
"Acc x" );
gp1.
plot_add( xhat_log.row( 5 ),
"Acc y" );
gp2.
window(
"Plot", 800, 10, 500, 500 );
arma::mat ppp = P_log.tube( 0, 0 );
ppp = P_log.tube( 1, 1 );
ppp = P_log.tube( 2, 2 );
ppp = P_log.tube( 3, 3 );
ppp = P_log.tube( 4, 4 );
ppp = P_log.tube( 5, 5 );
return 0;
}
Unscented Kalman filter class.
void plot_show(void)
Show plots.
void set_term(const char *ttype)
Set output terminal.
void plot_add(const T1 &x, const T2 &y, const std::string lb, const std::string ls="lines")
Push plot y vs. x with label and linespec.
void window(const int fig, const char *name, const int x, const int y, const int width, const int height)
Configure the figure used Windows environment.
void rts_smooth(const arma::mat &Xf, const arma::cube &Pf, arma::mat &Xs, arma::cube &Ps)
Rauch-Tung-Striebel smoother. See https://users.aalto.fi/~ssarkka/course_k2012/full_course_booklet_20...
arma::mat get_err_cov(void)
arma::mat get_state_vec(void)
void set_meas_noise(const arma::mat &_R)
void set_state_vec(const arma::mat &_x)
void set_meas_fcn(fcn_v _h)
void set_err_cov(const arma::mat &_P)
void set_trans_mat(const arma::mat &_A)
void update(const arma::mat z)
Correct and update the internal states. UKF.
arma::mat get_kalman_gain(void)
void set_proc_noise(const arma::mat &_Q)
void predict(const arma::mat u)
Predict the internal states using a control input.
std::function< double(arma::mat, arma::mat, arma::mat)> fcn_t
std::vector< fcn_t > fcn_v