卡尔曼滤波——从理论分析到编程实现(包含C和MATLAB)

这篇文章的主要目的是电控组滤波专题培训,针对已经了解卡尔曼滤波的大致思想以及基本公式的原理但因为对其底层原理的理解不太到位导致实际编程实现上遇到困难的同学。本文章仅靠个人理解编写,如果有错误欢迎私信我指正。

首先,我们知道无论多高精度的传感器,它都是有噪声的,这也是我们为什么要进行滤波的原因。我们的目的就是要把噪声去除,使我们得到的值能更好地接近真实值。假设我们知道传感器的噪声是多少,那么是不是我们从测量值把噪声减掉就可以了呢?如果你觉得我上面说的没问题的话,就说明我后面讲的东西对你来说是有用的。

卡尔曼滤波器是一种有效的递归滤波器,可通过一系列噪声测量来估计线性动态系统的内部状态。我在线下培训中也提到过,可以把卡尔曼滤波看成是一个加权以及递归的过程。简单来说就是,我们把预测值与测量值进行行加权和得到本次的结果,而其中的加权和实际上就是基于卡尔曼增益的相关计算,每轮计算出的结果就是最优估计。由上一轮计算的最优估计得到下一轮计算的预测值。我们发现它形成了一个闭环。而我们把卡尔曼滤波看成是一个系统的话,我们设定一些初始参数,然后输入测量值,这个系统就可以不断递归输出最优估计值。实际上它一轮递归要做的内容很清晰,就是预测、更新。我本以为了解这些再配合公式就可以进行实际操作了。但实际还是不行,我认为主要问题出现在上述状态、时间以及其关系的理解上。

卡尔曼滤波器使用系统的动态模型作为其状态方程的来源,比如宏观的物理运动定律,或是根据实际需求开发的运动模型。我们用状态方程干啥?我记着上面提到了一个预测当前状态的操作,它就是用来干这个的。已知的系统控制输入,我们就可以通过我们自己建立的状态方程实际上就是系统方程,从上一个状态预测也可以说计算得到当前状态。那我们为神马不直接说系统方程非要整一个状态方程,说明他俩还是有区别的。其区别就在于状态方程有过程噪声。我们可以这样理解,例如我们在理论上做了一个底盘的模型,然后我们机械组进行加工。就算机械组再牛逼,做出来的底盘它可能和我们的理论模型完全一样吗?肯定不可能,所以这就导致这个底盘按照我们的运动模型跑的过程中有个噪声他是恒定且存在的。那么这时候又有大聪明可能会认为,终于有个恒定的噪声了,减掉不就行了吗?或者直接在系统模型中抵消掉。先不管我们不知道这个过程噪声它具体的量,就算知道实际上你做的工作是这样的:我们设计4x6,然后机械组做出来是25,我们的套路是设成4x6+1用,但是你要当成4x6.25用,所以这是没有意义的啊,就不多说了。而多个来自传感器的连续测量,形成系统变化量再有其状态方程就可以得到观测方程,可以把其理解成系统状态量以及观测量的汇合处。同样的,观测时肯定也是有噪声的,而这实际上就是我们平常所提到的噪声,也称作观测噪声。其中包含传感器的温漂以及各种由外部因素的影响。它与过程噪声的区别就是,它不可预测而且不稳定。那么我们卡尔曼滤波是由什么为基础的呢?可能很多同学也都看到过,它是把噪声看成是较为一般的高斯噪声才得以能进一步进行推导分析。这个就不再扩展,关于上面提到的两个方程即是状态空间表达式的组成。而这个表达式就是卡尔曼滤波预测公式的雏形。

卡尔曼滤波也是一种常见的传感器融合和数据融合算法。虽然它一轮计算所使用的参量在时间上的跨度较小,但是其滤波效果是整体的。因为卡尔曼滤波器递归地工作,并且仅需要系统状态的最后“最佳猜测”而不是整个历史来计算新状态,但每一个“最佳猜测”也是整个历史的作用结果。这也是其一大优点,直观上就是计算占用内存较小。

我们再回到滤波过程基本思想上进行分析,测量和当前状态估计的相对确定性是重要的考虑因素,并且通常在卡尔曼滤波器的增益方面讨论滤波器的响应。卡尔曼增益是给予测量和当前状态估计的相对权重,并且可以“调整”以实现特定性能。利用高增益,滤波器在最近的测量中放置更多的权重,因此更加响应地跟随它们。利用低增益,滤波器更紧密地遵循我们设计的模型预测。在极端情况下,接近1的高增益将导致更多跳跃的估计轨迹,而接近零的低增益将消除噪声但降低响应性。当执行滤波器的实际计算时,状态估计和协方差被编码到矩阵中以处理单组计算中涉及的多个维度。这就允 许在任何过渡模型或协方差中表示不同状态变量(例如位置,速度,角度以及加速度)之间的线性关系。

接下来就从理论逐渐步入实践的阶段。首先由公式开始,卡尔曼滤波器是基于在时域中离散化的线性动态系统。我们主要为了使用卡尔曼滤波器来估计仅给出一系列噪声观测的过程的系统内部状态,必须根据卡尔曼滤波器的框架对过程进行建 模。也就是意味要着指定以下矩阵:

F_{k},状态转移模型

 H_{k},观察模型

 Q_{k},过程噪声的协方差 

R_{k},观察噪声的协方差

 B_{k},控制输入模型

卡尔曼滤波器模型假定在时间 k 处的真实状态是 根据 k-1 处的状态演变而来的,就通过我上面讲的状态方程如下

x_{k}=F_{k}x_{k-1}+B_{k}u_{k}+w_{k}

F_{k}是应用于先前状态x_{k-1}的状态转移模型

 B_{k}是控制输入模型,应用于控制向量 u_{k}

w_{k}是假设从零均值多元正态分布中得出的过程噪声,有协方差Q_{k}

观测方程如下

z_{k}=H_{k}x_{k}+v_{k}

 H_{k}是将真实状态空间映射到观察空间的观测模型

 v_{k}是观测噪声,假设为零均值高斯白噪声,协方差是R_{k}

 初始状态和每个步骤的噪声矢量都被假定为相互独立,这样才会有后续的计算。

许多真正的运动系统或测量系统并不完全适合这种模型。实际上,未建模的动态特性会严重降低滤波器的性能,即使它应该与未知的随机信号一起作为输入。其原因在于未建模动态的影响取决于输入,因此可以使估计算法不稳定。另一方面,独立的白噪声信号不会使算法发散。区分测量噪声和未建模动态的问题是一个困难的问题,值得去思考探讨。

 我们到现在已经清楚卡尔曼滤波器是一种递归估计器。这意味着仅需要来自前一时间步长的估计状态和当前测量来计算当前状态的估计。这就要定义时间,状态变量。滤波器的状态可以用两个变量进行描述

\hat{x}_{k|k}  是在时间k的后验状态估计,给出观察直到并包括在时间k

P_{k|k}  后验误差协方差矩阵,它是状态估计的估计精度的度量

我们可以把卡尔曼滤波器写成单个方程,也就是看成迭代的一个轮次。但实际上它通常会被概念化为两个不同的阶段:预测更新,感觉这样更易于理解。预测阶段使用来自先前时间的状态估计来产生当前时间的状态估计。该预测状态估计也称为先验状态估计,因为尽管它是当前时间的状态估计,但它不包括来自当前时间的观测信息。在更新阶段,将当前先验预测与当前观测信息组合以细化状态估计。这种改进的估计被称为后验状态估计。 通常,两个阶段交替,预测推进状态直到下一个预定的观察,并且更新结合观察。但是,这不是必要的; 如果由于某种原因观察结果不可用,则可以跳过更新并执行多个预测步骤。同样地,如果同时可获得多个独立观察,则可以执行多个更新步骤,但这时通常具有不同的观察矩阵H_{k}

预测

   先验状态估计                        \hat{x}_{k|k-1}=F_{k}\hat{x}_{k-1|k-1}+B_{k}u_{k}

   先验误差协方差                    P_{k|k-1}=F_{k}P_{k-1|k-1}F_{k}^{T}+Q_{k}

更新

测量预拟合残差                                       \hat{y}_{k}=z_{k}-H_{k}\hat{x}_{k|k-1}

更新预先拟合残差协方差                       S_{k}=R_{k}+H_{k}P_{k|k-1}H_{k}^{T}

最佳卡尔曼增益                                      H_{k}=P_{k|k-1}H_{k}^{T}S_{k}^{-1}

更新后验状态估计                                 \hat{x}_{k|k}=\hat{x}_{k|k-1}+K_{k}\tilde{y}_{k}

更新后验估计协方差              P_{k|k}=(I-K_{k}H_{k})P_{k|k-1}(I-K_{k}H_{k})^{T}+K_{k}R_{k}K_{k}^{T}

测量后拟合残差                                           \tilde{y}_{k|k}=z_{k}-H_{k}\hat{x}_{k|k}

上述更新后验估计协方差的公式对任何增益K_{k}都有效,有时称为约瑟夫形式。为了获得最佳卡尔曼增益,该公式进一步简化为P_{k|k}=(I-K_{k}H_{k})P_{k|k-1},它在这种形式下应用较为广泛。但是必须记住它仅对最小化残余误差的最佳增益有效。关于流程中为何使用协方差矩阵有如下

 估计噪声协方差Q_{k}R_{k}

 这是我前面一直忽略的一个问题,因为我们实际也不太好估计。这个Q和R实际上是超参数,这样说可能不太明白,但如果我说PID参数大家可能都会明白,我们调车时最折磨的事情莫过于调电机PID参数了,调得一不小心电机就可能会原地冒烟。这种参数你就算有系统函数也是很难进行预测的,只能通过一些经验技巧在看实际系统反应的前提下进行调节。而Q和R也是如此。卡尔曼滤波器的实际实现通常是困难的,因为难以获得噪声协方差矩阵Q_{k}R_{k}的良好估计。很多学者在这个领域已经进行了广泛的研究以从数据估计这些协方差。实现此目的的一种实用方法是自协方差最小二乘(ALS)技术,该技术使用常规操作数据的时间滞后自协方差来估计协方差。但我们实际上并不太需要准确的一个估计。

 这里在附上一个从网上找到的公式中较为重要的后验估计协方差矩阵以及卡尔曼增益的推导,可以看看

 那么接下来我们进行编程的时候要如何思考呢?首先我们要进行滤波肯定是有一个参量的,例如速度,位移,角度等等。所以我们首先肯定要制定好状态量和观测量,一维,二维还是多维的。然后清楚这些之后直接建立相关公式,包括预测以及更新部分,写的时候要留意一定要实现闭环。这些公式中肯定会有一些参数的初始化。这些初始化是有一定技巧的,这里我就不多说了,因为网上有很多相关的资料,我也是从网上到处搜刮学习的,这个参数初始化的学习也算是一个任务吧。接下来就可以看看一些别人的代码实现,把代码以及内容对应起来。把别人的代码搞清楚之后就可以尝试着自己编写。这里附上我老早之前写的一段代码,可以参考一下。因为身边没有硬件,且这个代码是以前试过能用。

#ifndef __KALMAN_H
#define __KALMAN_H
#include "math.h"

#define Pi 	3.1415926
//噪声参数
#define dt           0.012   //kalman滤波器采样时间
#define R_angle      0.5
#define Q_angle      0.001   
#define Q_gyro       0.003   

static float Angle_x_temp;  
static float Angle_y_temp;  
static float Angle_z_temp;

static float Angle_X_Final; 
static float Angle_Y_Final; 
static float Angle_Z_Final; 


static short aacx, aacy, aacz;		//加速度传感器原始数据
static short gyrox, gyroy, gyroz;	//陀螺仪原始数据

double KalmanFilter(const double ResrcData, double ProcessNiose_Q, double MeasureNoise_R);
void Angle_Calculate(void);
void Kalman_Filter_X(float Accel,float Gyro);
void Kalman_Filter_Y(float Accel,float Gyro);
void Kalman_Filter_Z(float Accel, float Gyro);

#endif
/***********************卡尔曼滤波算法***************************/

#include "Kalman.h"

float Accel_x;	     
float Accel_y;	     
float Accel_z;	     

float Gyro_x;		 
float Gyro_y;            
float Gyro_z;		 

//其他地方已经定义
//float Angle_gy;    
//static float Angle_x_temp;  
//static float Angle_y_temp;  
//static float Angle_z_temp;

//static float Angle_X_Final; 
//static float Angle_Y_Final; 
//static float Angle_Z_Final; 


char  C_0 = 1;
float Q_bias_x, Q_bias_y, Q_bias_z;
float Angle_err_x, Angle_err_y, Angle_err_z;
float PCt_0, PCt_1, E;
float K_0, K_1, t_0, t_1;
float Pdot[4] = { 0,0,0,0 };
float PP[2][2] = { { 1, 0 },{ 0, 1 } };

//卡尔曼理论算法
double KalmanFilter(const double ResrcData, double ProcessNiose_Q, double MeasureNoise_R)
{
	double R = MeasureNoise_R;    //测量噪声  R 增大,动态响应变慢,收敛稳定性变好
	double Q = ProcessNiose_Q;    //过程噪声  Q 增大,动态响应变快,收敛稳定性变坏
	static double x_last;
	double x_mid = x_last;
	double x_now;
	static double p_last;
	double p_mid;
	double p_now;
	double kg;    //卡尔曼增益
        
        /*******预测过程*******/
	x_mid = x_last;           
	p_mid = p_last + Q;      
        
        /*******更新过程*******/
	kg = p_mid / (p_mid + R); 
	x_now = x_mid + kg*(ResrcData - x_mid);
	p_now = (1 - kg)*p_mid;
        
        
	p_last = p_now; 
	x_last = x_now; 
	return x_now;
}

//主调用函数
void Angle_Calculate(void)
{
	
	//deg = rad*180/3.14
	float x=0, y=0, z=0;

        //初始变量赋值给计算变量
	Accel_x = aacx; 
	Accel_y = aacy; 
	Accel_z = aacz; 
	Gyro_x = gyrox;  
	Gyro_y = gyroy;  
	Gyro_z = gyroz;  

	//根据实际给定的限制计算
        //MPU6050初始化设置范围为2g时,灵敏度 16384 LSB/g
	if (Accel_x<32764) x = Accel_x / 16384;
	else              x = 1 - (Accel_x - 49152) / 16384;

	
	if (Accel_y<32764) y = Accel_y / 16384;
	else              y = 1 - (Accel_y - 49152) / 16384;

	
	if (Accel_z<32764) z = Accel_z / 16384;
	else              z = (Accel_z - 49152) / 16384;

	//计算与x轴的夹角
	Angle_x_temp = (atan2(z , y)) * 180 / Pi;
	Angle_y_temp = (atan2(x , z)) * 180 / Pi;
	Angle_z_temp = (atan2(y , x)) * 180 / Pi;

	
	if (Accel_y<32764) Angle_y_temp = +Angle_y_temp;
	if (Accel_y>32764) Angle_y_temp = -Angle_y_temp;
	if (Accel_x<32764) Angle_x_temp = +Angle_x_temp;
	if (Accel_x>32764) Angle_x_temp = -Angle_x_temp;
	if (Accel_z<32764) Angle_z_temp = +Angle_z_temp;
	if (Accel_z>32764) Angle_z_temp = -Angle_z_temp;
	
	
        
	if (Gyro_x<32768) Gyro_x = -(Gyro_x / 16.4);    //去除零点偏移,计算角速度值,负号为方向处理 
	
	if (Gyro_x>32768) Gyro_x = +(65535 - Gyro_x) / 16.4;
	
	if (Gyro_y<32768) Gyro_y = -(Gyro_y / 16.4);
	
	if (Gyro_y>32768) Gyro_y = +(65535 - Gyro_y) / 16.4;
	
	if (Gyro_z<32768) Gyro_z = -(Gyro_z / 16.4);
	
	if (Gyro_z>32768) Gyro_z = +(65535 - Gyro_z) / 16.4;

	
	Kalman_Filter_X(Angle_x_temp, Gyro_x);  ;
	Kalman_Filter_Y(Angle_y_temp, Gyro_y);  
	Kalman_Filter_Z(Angle_z_temp, Gyro_z);  
}


void Kalman_Filter_X(float Accel, float Gyro) 
{
        /*****状态估计*****/
	Angle_X_Final += (Gyro - Q_bias_x) * dt;    //先验估计

	Pdot[0] = Q_angle - PP[0][1] - PP[1][0];   

	Pdot[1] = -PP[1][1];
	Pdot[2] = -PP[1][1];
	Pdot[3] = Q_gyro;

        /******方差估计*******/
	PP[0][0] += Pdot[0] * dt;      
	PP[0][1] += Pdot[1] * dt;   
	PP[1][0] += Pdot[2] * dt;
	PP[1][1] += Pdot[3] * dt;
        
        /*****残差*****/
	Angle_err_x = Accel - Angle_X_Final;	

	PCt_0 = C_0 * PP[0][0];
	PCt_1 = C_0 * PP[1][0];

	E = R_angle + C_0 * PCt_0;
        
        
        /*****最优增益*****/
	K_0 = PCt_0 / E;
	K_1 = PCt_1 / E;

	t_0 = PCt_0;
	t_1 = C_0 * PP[0][1];
        
        /*****数据更新*****/
	PP[0][0] -= K_0 * t_0;		 
	PP[0][1] -= K_0 * t_1;
	PP[1][0] -= K_1 * t_0;
	PP[1][1] -= K_1 * t_1;

	Angle_X_Final += K_0 * Angle_err_x;	 
	Q_bias_x += K_1 * Angle_err_x;	 
	Gyro_x = Gyro - Q_bias_x;	 
}

void Kalman_Filter_Y(float Accel, float Gyro) 		
{
	Angle_Y_Final += (Gyro - Q_bias_y) * dt; 

	Pdot[0] = Q_angle - PP[0][1] - PP[1][0];  

	Pdot[1] = -PP[1][1];
	Pdot[2] = -PP[1][1];
	Pdot[3] = Q_gyro;

	PP[0][0] += Pdot[0] * dt;    
	PP[0][1] += Pdot[1] * dt;    
	PP[1][0] += Pdot[2] * dt;
	PP[1][1] += Pdot[3] * dt;

	Angle_err_y = Accel - Angle_Y_Final;	

	PCt_0 = C_0 * PP[0][0];
	PCt_1 = C_0 * PP[1][0];

	E = R_angle + C_0 * PCt_0;

	K_0 = PCt_0 / E;
	K_1 = PCt_1 / E;

	t_0 = PCt_0;
	t_1 = C_0 * PP[0][1];

	PP[0][0] -= K_0 * t_0;		 
	PP[0][1] -= K_0 * t_1;
	PP[1][0] -= K_1 * t_0;
	PP[1][1] -= K_1 * t_1;

	Angle_Y_Final += K_0 * Angle_err_y;	 
	Q_bias_y += K_1 * Angle_err_y;	 
	Gyro_y = Gyro - Q_bias_y;	 
}

void Kalman_Filter_Z(float Accel, float Gyro) 
{
	Angle_Z_Final += (Gyro - Q_bias_z) * dt; 

	Pdot[0] = Q_angle - PP[0][1] - PP[1][0]; 

	Pdot[1] = -PP[1][1];
	Pdot[2] = -PP[1][1];
	Pdot[3] = Q_gyro;

	PP[0][0] += Pdot[0] * dt;   
	PP[0][1] += Pdot[1] * dt;    
	PP[1][0] += Pdot[2] * dt;
	PP[1][1] += Pdot[3] * dt;

	Angle_err_z = Accel - Angle_Z_Final;	

	PCt_0 = C_0 * PP[0][0];
	PCt_1 = C_0 * PP[1][0];

	E = R_angle + C_0 * PCt_0;

	K_0 = PCt_0 / E;
	K_1 = PCt_1 / E;

	t_0 = PCt_0;
	t_1 = C_0 * PP[0][1];

	PP[0][0] -= K_0 * t_0;		 
	PP[0][1] -= K_0 * t_1;
	PP[1][0] -= K_1 * t_0;
	PP[1][1] -= K_1 * t_1;

	Angle_Z_Final += K_0 * Angle_err_z;	 
	Q_bias_z += K_1 * Angle_err_z;	 
	Gyro_z = Gyro - Q_bias_z;	 
}

这里再附上MATLAB实现,虽然我们实际不用,但是可以增进理解。比较熟悉MATLAB的可以看看

% Process noise variance
Q = 0.001;

% Measurement noise variance
R = 0.02;

%
% Q and R estimation procedure
%
% 1. Specify a lookback window and EWMALength
EWMALength = 15;
lookbackWindow = 30;
% 2. Set use true variance flag to 'true' to reveal actual values to KF
UseTrueVariances = 'true';
%

% Number of iterations  
N = 500;

%--------------------------------------------------------------------------
% State variable initializations
%--------------------------------------------------------------------------
% True State
x = zeros(1,N);

% Apriori state estimates
x_apriori = zeros(1,N);

% Aposteriori state estimates
x_aposteriori = zeros(1,N);

% Apriori error covariance estimates
P_apriori = zeros(1,N);

% Aposteriori error covariance estimates
P_aposteriori = zeros(1,N);

% Measurements
z = zeros(1,N);

% Smoothed measurements
smoothed_z = zeros(1,N);

% Kalman Gain
K = zeros(1,N);
%--------------------------------------------------------------------------

%--------------------------------------------------------------------------
% Initializations
%--------------------------------------------------------------------------
% True initial state
x(1) = rand;

% EWMA lambda value
lambda = 1-2/(EWMALength+1);

% First measurement
z(1) = x(1) + sqrt(Q)*randn;

% First smoothed measurement
smoothed_z(1) = z(1);

% Initial aposteriori state estimate
x_aposteriori(1:lookbackWindow) = .5;

% Initial aposteriori error covariance estimate
P_aposteriori(1:lookbackWindow) = 1;
%--------------------------------------------------------------------------

%--------------------------------------------------------------------------
% Perform Kalman filtering
%--------------------------------------------------------------------------
for i = 2:N
    % Update true state
    x(i) = x(i-1) + sqrt(Q)*randn;

    % Update measurements
    z(i) = x(i) + sqrt(R)*randn;

    % Update smoothed measurement
    smoothed_z(i) = lambda * smoothed_z(i-1) + (1-lambda)*z(i);
    
    % Wait until lookback window is primed before applying Kalman filter
    if (i >= lookbackWindow)
        %-----------------------------------------------------------
        % Estimate noise/process covariance
        %-----------------------------------------------------------
        if strcmpi(UseTrueVariances,'true')
            Ri = R;
            Qi = Q;
        else
            [Ri Qi] = StandardCovEst(z,smoothed_z,i,lookbackWindow);
        end
        %-----------------------------------------------------------
        
        % Update Kalman filter
        [x_aposteriori(i) P_aposteriori(i)] = KalmanFilterIteration(z(i),Qi,Ri,x_aposteriori(i-1), P_aposteriori(i-1));
    end
end
%--------------------------------------------------------------------------

%--------------------------------------------------------------------------
% Plot Results
%--------------------------------------------------------------------------
figure
% Plot true state
b = plot(2:N,x(2:N),'b');
hold on
% Plot estimates
r = plot(lookbackWindow:N,x_aposteriori(lookbackWindow:N),'r');
% Plot measurements
g = plot(2:N,z(2:N),'g+');
title(['Kalman Filtering: Tracking a White Noise Process with Q = ' num2str(Q) ', R = ' num2str(R)]);
legend([b r g],'True Value','KF Estimate','Measurements');
xlabel('Time')
ylabel('Value')
grid on
%--------------------------------------------------------------------------
function [x_aposteriori P_aposteriori] = KalmanFilterIteration(z,Q,R,x_aposteriori_last,P_aposteriori_last)
%
% Performs one iteration of the standard Kalman filter update equations
% Note: this function is used ONLY by KalmanFilterDemo.m
%

% Update apriori estimate
x_apriori = x_aposteriori_last;

% Update apriori error covariance estimate
P_apriori = P_aposteriori_last + Q;

% Update Kalman gain
% Note: backslash denotes right matrix inversion in MATLAB
K = P_apriori / (P_apriori + R);

% Update aposteriori state estimate
x_aposteriori = x_apriori + K * (z - x_apriori);

% Update aposteriori error covariance estimate
P_aposteriori = (eye(length(x_aposteriori)) - K) * P_apriori;
function [R Q] = StandardCovEst(z,smoothed_z,i,N)
%
% Estimates the process covariance (Q) and noise covariance (R) of the data
% (z) at the current index (i) over a lookback window (N) using the
% smoothed data (smoothed_z) as a surrogate for the true process states.
%

DIM = size(z,1);

R = zeros(DIM);
Q = zeros(DIM);

if (DIM == 1)
    z = z(i-(N-1):i);
    smoothed_z = smoothed_z(i-(N-1):i);
    diffs = z - smoothed_z;

    mean1 = mean(smoothed_z);
    mean2 = mean(diffs);
    
    Q = sum((smoothed_z-mean1).^2) / (N-1);
    R = sum((diffs-mean2).^2) / (N-1);
else
    z = z(:,i-(N-1):i);
    smoothed_z = smoothed_z(:,i-(N-1):i);
    diffs = z - smoothed_z;

    for i = 1:DIM
        mean1i = mean(smoothed_z(i,:));
        mean2i = mean(diffs(i,:));
        for j = 1:DIM
            mean1j = mean(smoothed_z(j,:));
            Q(i,j) = sum((smoothed_z(i,:)-mean1i).*(smoothed_z(j,:)-mean1j))/(N-1);

            mean2j = mean(diffs(j,:));
            R(i,j) = sum((diffs(i,:)-mean2i).*(diffs(j,:)-mean2j))/(N-1);
        end
    end
end
function [R Q] = EWMACovEst(z,smoothed_z,i,N,Rold,Qold)
%
% Updates the process covariance (Q) and noise covariance (R) estimates of
% the data (z) at the current index (i) with memory length (N) using an
% exponentially weighted averaging of the current covariances and the
% previous process covariance (Qold) and noise covariance (Rold) estimates.
% The smoothed version (smoothed_z) of the data is used as a surrogate for
% the true process states.
%

if (i == (2*N-1))
    [R Q] = StandardCovEst(z,smoothed_z,i,N);
else
    DIM = size(z,1);
    lambda = 1-2/(N+1);

    if (DIM == 1)
        Qnew = smoothed_z(i) - mean(smoothed_z((i-(N-1)):i));
        Rnew = z(i) - smoothed_z(i);
    else
        Qnew = smoothed_z(:,i) - mean(smoothed_z(:,(i-(N-1)):i),2);
        Rnew = z(:,i) - smoothed_z(:,i);
    end

    Q = (1 - lambda) * (Qnew * Qnew') + lambda * Qold;
    R = (1 - lambda) * (Rnew * Rnew') + lambda * Rold;
end

以上是实现的.m代码以及所用到的函数代码,运行结果如下

 这是普通的卡尔曼滤波,卡尔曼滤波实现方法其实也有很多种,平方根滤波,频率加权滤波,混合卡尔曼滤波等等,下面就展示其中较为简单的平方根滤波的实现

function [x_kf varargout] = SquareRootKalmanFilter(z,MAlen,varargin)
%--------------------------------------------------------------------------
% Syntax:       x_kf = SquareRootKalmanFilter(z,MAlen,N);
%               x_kf = SquareRootKalmanFilter(z,MAlen,'EWMA');
%               x_kf = SquareRootKalmanFilter(z,MAlen,N,'EWMA');
%               x_kf = SquareRootKalmanFilter(z,MAlen,N,'UWMA');
%               [x_kf KF] = SquareRootKalmanFilter(z,MAlen,N);
%               [x_kf KF] = SquareRootKalmanFilter(z,MAlen,'EWMA');
%               [x_kf KF] = SquareRootKalmanFilter(z,MAlen,N,'EWMA');
%               [x_kf KF] = SquareRootKalmanFilter(z,MAlen,N,'UWMA');
%
% Inputs:       z is an m x n matrix containing n samples of an
%               m-dimensional signal
%
%               MAlen is the length of the moving average to apply to z
%               (used during covariance estimation)
%
%               N is the length of the lookback window to use during
%               covariance estimation. When N is specified and nargin == 3,
%               this function applies an exponentially weighted moving
%               average (with memory N) during covariance estimation
%
%               When nargin == 3, 'EWMA' instructs this function to use
%               exponentially weighted (recursive) covariance estimation
%
%               When nargin == 4, 'EWMA' instructs this function to apply
%               an exponentially weighted moving average with (memory N) to
%               z during covariance estimation. Alternatively, 'UWMA'
%               applies an unweighted moving average of length N to z
%
% Outputs:      x_kf is an m x n matrix containing the Kalman filter
%               "true state" estimate derived from noisy measurements z.
%
%               KF is a struct containing the following fields:
%
%               KF.x_pr - Apriori state estimates
%               KF.UP_pr - Apriori error covariance estimates (U)
%               KF.DP_pr - Apriori error covariance estimates (D)
%               KF.UP_po - Aposteriori error covariance estimates (U)
%               KF.DP_po - Aposteriori error covariance estimates (D)
%               KF.Q - Process covariance estimates
%               KF.UQ - Process covariance estimates (U)
%               KF.DQ - Process covariance estimates (D)
%               KF.R - Process covariance estimates
%               KF.UR - Process covariance estimates (U)
%               KF.DR - Noise covariance estimates (D)
%
% Description:  This function performs square root Kalman filtering on
%               noisy input data z. The assumed system model is that the
%               noisy measurements (z) = the true state (x) + white noise.
%               This function estimates the process/noise covariances of
%               the input data at each iteration using a smoothed version
%               of z as a surrogate for the true process state.
%
%               NOTE: This square root implementation of the Kalman filter
%               produces the same output as StandardKalmanFilter(), except
%               when the noisy measurements are poorly-conditioned, in
%               which case SquareRootKalmanFilter() prodcues a MORE
%               NUMERICALLY STABLE output (at the cost of greater
%               computational complexity.)
%
%               NOTE: "Square root" refers to the fact that, instead of
%               computing the error covariance P at each iteration, this
%               function computes U and D such that [U D] = myUD(P). This
%               strategy is known to be more numerically stable.
%
%--------------------------------------------------------------------------

% Parse user inputs
if (nargin == 3)
    if ~ischar(varargin{1})
        N = varargin{1};
        MAType = 'EWMA';
        CovMethod = 'Standard';
    else
        N = MAlen;
        MAType = 'EWMA';
        CovMethod = 'EWMA';
    end
elseif (nargin == 4)
    N = varargin{1};
    MAType = varargin{2};
    CovMethod = 'Standard';
else
    error('Input syntax error. Type ''help SquareRootKalmanFilter'' for assistance.');
end

%--------------------------------------------------------------------------
% State variable initializations
%--------------------------------------------------------------------------
% Data dimension
DIM = size(z,1);

% Number of iterations
n = size(z,2);

% Apriori state estimates
x_apriori = zeros(DIM,n);

% Aposteriori state estimates
x_aposteriori = zeros(DIM,n);

% Apriori error covariance estimates
UP_apriori = zeros(DIM,DIM,n);
DP_apriori = zeros(DIM,DIM,n);

% Aposteriori error covariance estimates
UP_aposteriori = zeros(DIM,DIM,n);
DP_aposteriori = zeros(DIM,DIM,n);

% Process variance estimates
Q = zeros(DIM,DIM,n);
UQ = zeros(DIM,DIM,n);
DQ = zeros(DIM,DIM,n);

% Measurement variance estimates
R = zeros(DIM,DIM,n);
UR = zeros(DIM,DIM,n);
DR = zeros(DIM,DIM,n);
%--------------------------------------------------------------------------

%--------------------------------------------------------------------------
% More initializations
%--------------------------------------------------------------------------
% MA smoothed measurements
eval(['smoothed_z = ' MAType '(z,MAlen);']);

% Simulation start index
startIndex = N + MAlen - 1;

% Initial aposteriori state estimate
x_aposteriori(:,startIndex-1) = smoothed_z(:,startIndex-1); %#ok

% Initial aposteriori error covariance estimate
UP_aposteriori(:,:,startIndex-1) = eye(DIM);
DP_aposteriori(:,:,startIndex-1) = eye(DIM);
%--------------------------------------------------------------------------

%--------------------------------------------------------------------------
% Now perform square root Kalman filtering
%--------------------------------------------------------------------------
for i = startIndex:n
    % Estimate noise/process covariance
    if strcmpi(CovMethod,'Standard')
        [R(:,:,i) Q(:,:,i)] = StandardCovEst(z,smoothed_z,i,N);
    else
        [R(:,:,i) Q(:,:,i)] = EWMACovEst(z,smoothed_z,i,N,R(:,:,i-1),Q(:,:,i-1));
    end
    try
        % Update UD decompositions
        [UQ(:,:,i) DQ(:,:,i)] = myUD(Q(:,:,i));
        [UR(:,:,i) DR(:,:,i)] = myUD(R(:,:,i));
        
        % Time update
        [x_apriori(:,i) UP_apriori(:,:,i) DP_apriori(:,:,i)] = thornton(x_aposteriori(:,i-1),UP_aposteriori(:,:,i-1),DP_aposteriori(:,:,i-1),UQ(:,:,i),DQ(:,:,i));
        
        % Decorrelate measurements
        z_ind = myUnitTriSysSol(UR(:,:,i),z(:,i),'upper');
        H_ind = myUnitTriSysSol(UR(:,:,i),eye(DIM),'upper');

        % Measurement Update
        x_aposteriori(:,i) = x_apriori(:,i);
        UP_aposteriori(:,:,i) = UP_apriori(:,:,i);
        DP_aposteriori(:,:,i) = DP_apriori(:,:,i);
        for j = 1:DIM
            [x_aposteriori(:,i) UP_aposteriori(:,:,i) DP_aposteriori(:,:,i)] = bierman(z_ind(j),DR(j,j,i),H_ind(j,:),x_aposteriori(:,i),UP_aposteriori(:,:,i),DP_aposteriori(:,:,i));
        end
    catch e
        %disp(e.message);
        x_aposteriori(:,i) = z(:,i);
        UP_aposteriori(:,:,i)  = eye(DIM);
        DP_aposteriori(:,:,i) = eye(DIM);
    end 
end
%--------------------------------------------------------------------------

% Return user requested data
x_kf = x_aposteriori;
if (nargout == 2)
    varargout{1} = struct('x_pr',x_apriori, ...
                          'UP_pr',UP_apriori, ...
                          'DP_pr',DP_apriori, ...
                          'UP_po',UP_aposteriori, ...
                          'DP_po',DP_aposteriori, ...
                          'Q',Q, ...
                          'UQ',UQ, ...
                          'DQ',DQ, ...
                          'R',R, ...
                          'UR',UR, ...
                          'DR',DR);
end
function [x_kf varargout] = StandardKalmanFilter(z,MAlen,varargin)
%--------------------------------------------------------------------------
% Syntax:       x_kf = StandardKalmanFilter(z,MAlen,N);
%               x_kf = StandardKalmanFilter(z,MAlen,'EWMA');
%               x_kf = StandardKalmanFilter(z,MAlen,N,'EWMA');
%               x_kf = StandardKalmanFilter(z,MAlen,N,'UWMA');
%               [x_kf KF] = StandardKalmanFilter(z,MAlen,N);
%               [x_kf KF] = StandardKalmanFilter(z,MAlen,'EWMA');
%               [x_kf KF] = StandardKalmanFilter(z,MAlen,N,'EWMA');
%               [x_kf KF] = StandardKalmanFilter(z,MAlen,N,'UWMA');
%
% Inputs:       z is an m x n matrix containing n samples of an
%               m-dimensional signal
%
%               MAlen is the length of the moving average to apply to z
%               (used during covariance estimation)
%
%               N is the length of the lookback window to use during
%               covariance estimation. When N is specified and nargin == 3,
%               this function applies an exponentially weighted moving
%               average (with memory N) during covariance estimation
%
%               When nargin == 3, 'EWMA' instructs this function to use
%               exponentially weighted (recursive) covariance estimation
%
%               When nargin == 4, 'EWMA' instructs this function to apply
%               an exponentially weighted moving average with (memory N) to
%               z during covariance estimation. Alternatively, 'UWMA'
%               applies an unweighted moving average of length N to z
%
% Outputs:      x_kf is an m x n matrix containing the Kalman filter
%               "true state" estimate derived from noisy measurements z.
%
%               KF is a struct containing the following fields:
%
%               KF.x_pr - Apriori state estimates
%               KF.P_pr - Apriori error covariance estimates
%               KF.P_po - Aposteriori error covariance estimates
%               KF.K - Kalman gains
%               KF.Q - Process covariance estimates
%               KF.R - Noise covariance estimates
%
% Description:  This function performs standard Kalman filtering on noisy
%               input data z. The assumed system model is that the noisy
%               measurements (z) = the true state (x) + white noise. This
%               function estimates the process/noise covariances of the
%               input data at each iteration using a smoothed version of z
%               as a surrogate for the true process state.
%--------------------------------------------------------------------------

% Parse user inputs
if (nargin == 3)
    if ~ischar(varargin{1})
        N = varargin{1};
        MAType = 'EWMA';
        CovMethod = 'Standard';
    else
        N = MAlen;
        MAType = 'EWMA';
        CovMethod = 'EWMA';
    end
elseif (nargin == 4)
    N = varargin{1};
    MAType = varargin{2};
    CovMethod = 'Standard';
else
    error('Input syntax error. Type ''help StandardKalmanFilter'' for assistance.');
end

% Kalman gain computation method
KalmanGainMethod = 'pinv'; % 'pinv' or 'UD'

%--------------------------------------------------------------------------
% State variable initializations
%--------------------------------------------------------------------------
% Data dimension
DIM = size(z,1);

% Number of iterations
n = size(z,2);

% Apriori state estimates
x_apriori = zeros(DIM,n);

% Aposteriori state estimates
x_aposteriori = zeros(DIM,n);

% Apriori error covariance estimates
P_apriori = zeros(DIM,DIM,n);

% Aposteriori error covariance estimates
P_aposteriori = zeros(DIM,DIM,n);

% Kalman Gain
K = zeros(DIM,DIM,n);

% Process variance estimates
Q = zeros(DIM,DIM,n);

% Measurement variance estimates
R = zeros(DIM,DIM,n);
%--------------------------------------------------------------------------

%--------------------------------------------------------------------------
% More initializations
%--------------------------------------------------------------------------
% MA smoothed measurements
eval(['smoothed_z = ' MAType '(z,MAlen);']);

% Simulation start index
startIndex = N + MAlen - 1;

% Initial aposteriori state estimate
x_aposteriori(:,startIndex-1) = smoothed_z(:,startIndex-1); %#ok

% Initial aposteriori error covariance estimate
P_aposteriori(:,:,startIndex-1) = eye(DIM);
%--------------------------------------------------------------------------

%--------------------------------------------------------------------------
% Now perform Kalman filtering
%--------------------------------------------------------------------------
for i = startIndex:n
    % Update apriori estimate
    x_apriori(:,i) = x_aposteriori(:,i-1);

    % Estimate noise/process covariance
    if strcmpi(CovMethod,'Standard')
        [R(:,:,i) Q(:,:,i)] = StandardCovEst(z,smoothed_z,i,N);
    else
        [R(:,:,i) Q(:,:,i)] = EWMACovEst(z,smoothed_z,i,N,R(:,:,i-1),Q(:,:,i-1));
    end
    
    % Update apriori error covariance estimate
    P_apriori(:,:,i) = P_aposteriori(:,:,i-1) + Q(:,:,i);

    %----------------------------------------------------------------------
    % Compute Kalman Gain
    %----------------------------------------------------------------------
    if strcmpi(KalmanGainMethod,'pinv')
        % PInv method
        [inv isSingular] = myPInv(P_apriori(:,:,i) + R(:,:,i));
        K(:,:,i) = P_apriori(:,:,i) * inv;
    else
        % UD method
        [K(:,:,i) isSingular] = KalmanGainCalc(P_apriori(:,:,i),R(:,:,i));
    end
    %----------------------------------------------------------------------
    
    % Measurement Update
    if sum(sum(isnan(K(:,:,i)))) || strcmpi(isSingular,'true')
        x_aposteriori(:,i) = z(:,i);
        P_aposteriori(:,:,i) = eye(DIM);
    else
        % Update aposteriori state estimate
        x_aposteriori(:,i) = x_apriori(:,i) + K(:,:,i) * (z(:,i) - x_apriori(:,i));

        % Update aposteriori error covariance estimate
        P_aposteriori(:,:,i) = (eye(DIM) - K(:,:,i)) * P_apriori(:,:,i);
    end
end
%--------------------------------------------------------------------------

% Return user requested data
x_kf = x_aposteriori;
if (nargout == 2)
    varargout{1} = struct('x_pr',x_apriori, ...
                          'P_pr',P_apriori, ...
                          'P_po',P_aposteriori, ...
                          'K',K, ...
                          'Q',Q, ...
                          'R',R);
end

可以与标准卡尔曼滤波比较,学习其区别以及优点。

  • 8
    点赞
  • 30
    收藏
    觉得还不错? 一键收藏
  • 打赏
    打赏
  • 3
    评论

“相关推荐”对你有帮助么?

  • 非常没帮助
  • 没帮助
  • 一般
  • 有帮助
  • 非常有帮助
提交
评论 3
添加红包

请填写红包祝福语或标题

红包个数最小为10个

红包金额最低5元

当前余额3.43前往充值 >
需支付:10.00
成就一亿技术人!
领取后你会自动成为博主和红包主的粉丝 规则
hope_wisdom
发出的红包

打赏作者

古城凉梦

你的鼓励将是我创作的最大动力

¥1 ¥2 ¥4 ¥6 ¥10 ¥20
扫码支付:¥1
获取中
扫码支付

您的余额不足,请更换扫码支付或充值

打赏作者

实付
使用余额支付
点击重新获取
扫码支付
钱包余额 0

抵扣说明:

1.余额是钱包充值的虚拟货币,按照1:1的比例进行支付金额的抵扣。
2.余额无法直接购买下载,可以购买VIP、付费专栏及课程。

余额充值