1、卡尔曼滤波器定义式的变形
(1)新息过程
a
n
=
y
n
−
b
n
(
x
^
n
∣
n
−
1
)
a_n = y_n-b_n(\hat x_{n|n-1})
an=yn−bn(x^n∣n−1)
(2)状态空间
X
n
+
1
=
A
n
+
1
,
n
X
n
+
w
n
+
ε
n
X_{n+1} = A_{n+1,n}X_n+w_n+ \varepsilon_n
Xn+1=An+1,nXn+wn+εn
y
n
=
B
n
X
n
+
v
n
y_n=B_nX_n+v_n
yn=BnXn+vn
(3)表述形式
x
^
n
+
1
∣
n
=
A
n
+
1
,
n
x
^
n
∣
n
+
ε
n
\hat x_{n+1|n}=A_{n+1,n}\hat x_{n|n} + \varepsilon_n
x^n+1∣n=An+1,nx^n∣n+εn
2、实现扩展卡尔曼滤波器的预备步骤
扩展卡尔曼滤波的基本思想是在没个时间点,围绕最近状态估计结果中的状态空间模型线性化
(1)阶段1 新矩阵的构建
A
n
+
1
,
n
=
∂
a
n
(
X
)
∂
X
∣
X
=
x
^
n
∣
n
A_{n+1,n}=\frac{\partial a_n(X)}{\partial X}|_{X=\hat{x}_{n|n}}
An+1,n=∂X∂an(X)∣X=x^n∣n
B
n
=
∂
b
n
∂
x
∣
x
=
x
n
∣
n
−
1
^
B_n=\frac{\partial b_n}{\partial x}|_{x=\hat{x_{n|n-1}}}
Bn=∂x∂bn∣x=xn∣n−1^
(2) 阶段2 空间模型线性化
3、扩展卡尔曼滤波器的实现
输入过程:
[
y
1
,
y
2
,
.
.
.
,
y
n
]
[y_1,y_2,...,y_n]
[y1,y2,...,yn]
已知参数:
非线性状态向量函数=
a
n
(
x
n
)
a_n(x_n)
an(xn)
非线性测量向量函数=
b
n
(
x
n
)
b_n(x_n)
bn(xn)
过程噪声向量的协方差矩阵=
Q
w
,
n
Q_{w,n}
Qw,n
测量噪声向量的协方差矩阵=
Q
v
,
n
Q_{v,n}
Qv,n
计算:n=1,2,3…
G
n
=
P
n
,
n
−
1
B
n
T
[
B
n
P
n
,
n
−
1
B
n
T
+
Q
v
,
n
]
G_n = P_{n,n-1} B_n ^T[B_nP_{n,n-1}B_n^T + Q_{v,n}]
Gn=Pn,n−1BnT[BnPn,n−1BnT+Qv,n]
a
n
=
y
n
−
b
n
(
x
^
n
∣
n
−
1
)
a_n = y_n-b_n(\hat x_{n|n-1})
an=yn−bn(x^n∣n−1)
x
^
n
∣
n
=
x
^
n
∣
n
−
1
+
G
n
a
n
\hat x_{n|n}=\hat x_{n|n-1} + G_n a_n
x^n∣n=x^n∣n−1+Gnan
x
^
n
+
1
∣
n
=
a
n
(
x
^
n
∣
n
)
\hat x_{n+1|n} = a_n(\hat x_{n|n})
x^n+1∣n=an(x^n∣n)
P
n
∣
n
=
P
n
∣
n
−
1
−
G
n
B
n
P
n
∣
n
+
1
P_{n|n} = P_{n|n-1}-G_nB_nP_{n|n+1}
Pn∣n=Pn∣n−1−GnBnPn∣n+1
P
n
+
1
∣
n
=
A
n
+
1
,
n
P
n
∣
n
A
n
+
1
,
n
T
+
Q
w
,
n
P_{n+1|n} = A_{n+1,n}P_{n|n}A_{n+1,n}^T+Q_{w,n}
Pn+1∣n=An+1,nPn∣nAn+1,nT+Qw,n
4、代码实现
该代码来源于https://github.com/AtsushiSakai/PythonRobotics
"""
Extended kalman filter (EKF) localization sample
author: Atsushi Sakai (@Atsushi_twi)
"""
import math
import matplotlib.pyplot as plt
import numpy as np
from scipy.spatial.transform import Rotation as Rot
# Covariance for EKF simulation
Q = np.diag([
0.1, # variance of location on x-axis
0.1, # variance of location on y-axis
np.deg2rad(1.0), # variance of yaw angle
1.0 # variance of velocity
]) ** 2 # predict state covariance
R = np.diag([1.0, 1.0]) ** 2 # Observation x,y position covariance
# Simulation parameter
INPUT_NOISE = np.diag([1.0, np.deg2rad(30.0)]) ** 2
GPS_NOISE = np.diag([0.5, 0.5]) ** 2
DT = 0.1 # time tick [s]
SIM_TIME = 50.0 # simulation time [s]
show_animation = True
def calc_input():
v = 1.0 # [m/s]
yawrate = 0.1 # [rad/s]
u = np.array([[v], [yawrate]])
return u
def observation(xTrue, xd, u):
xTrue = motion_model(xTrue, u)
# add noise to gps x-y
z = observation_model(xTrue) + GPS_NOISE @ np.random.randn(2, 1)
# add noise to input
ud = u + INPUT_NOISE @ np.random.randn(2, 1)
xd = motion_model(xd, ud)
return xTrue, z, xd, ud
def motion_model(x, u):
F = np.array([[1.0, 0, 0, 0],
[0, 1.0, 0, 0],
[0, 0, 1.0, 0],
[0, 0, 0, 0]])
B = np.array([[DT * math.cos(x[2, 0]), 0],
[DT * math.sin(x[2, 0]), 0],
[0.0, DT],
[1.0, 0.0]])
x = F @ x + B @ u
return x
def observation_model(x):
H = np.array([
[1, 0, 0, 0],
[0, 1, 0, 0]
])
z = H @ x
return z
def jacob_f(x, u):
"""
Jacobian of Motion Model
motion model
x_{t+1} = x_t+v*dt*cos(yaw)
y_{t+1} = y_t+v*dt*sin(yaw)
yaw_{t+1} = yaw_t+omega*dt
v_{t+1} = v{t}
so
dx/dyaw = -v*dt*sin(yaw)
dx/dv = dt*cos(yaw)
dy/dyaw = v*dt*cos(yaw)
dy/dv = dt*sin(yaw)
"""
yaw = x[2, 0]
v = u[0, 0]
jF = np.array([
[1.0, 0.0, -DT * v * math.sin(yaw), DT * math.cos(yaw)],
[0.0, 1.0, DT * v * math.cos(yaw), DT * math.sin(yaw)],
[0.0, 0.0, 1.0, 0.0],
[0.0, 0.0, 0.0, 1.0]])
return jF
def jacob_h():
# Jacobian of Observation Model
jH = np.array([
[1, 0, 0, 0],
[0, 1, 0, 0]
])
return jH
def ekf_estimation(xEst, PEst, z, u):
# Predict
xPred = motion_model(xEst, u)
jF = jacob_f(xEst, u)
PPred = jF @ PEst @ jF.T + Q
# Update
jH = jacob_h()
zPred = observation_model(xPred)
y = z - zPred
S = jH @ PPred @ jH.T + R
K = PPred @ jH.T @ np.linalg.inv(S)
xEst = xPred + K @ y
PEst = (np.eye(len(xEst)) - K @ jH) @ PPred
return xEst, PEst
def plot_covariance_ellipse(xEst, PEst): # pragma: no cover
Pxy = PEst[0:2, 0:2]
eigval, eigvec = np.linalg.eig(Pxy)
if eigval[0] >= eigval[1]:
bigind = 0
smallind = 1
else:
bigind = 1
smallind = 0
t = np.arange(0, 2 * math.pi + 0.1, 0.1)
a = math.sqrt(eigval[bigind])
b = math.sqrt(eigval[smallind])
x = [a * math.cos(it) for it in t]
y = [b * math.sin(it) for it in t]
angle = math.atan2(eigvec[1, bigind], eigvec[0, bigind])
rot = Rot.from_euler('z', angle).as_matrix()[0:2, 0:2]
fx = rot @ (np.array([x, y]))
px = np.array(fx[0, :] + xEst[0, 0]).flatten()
py = np.array(fx[1, :] + xEst[1, 0]).flatten()
plt.plot(px, py, "--r")
def main():
print(__file__ + " start!!")
time = 0.0
# State Vector [x y yaw v]'
xEst = np.zeros((4, 1))
xTrue = np.zeros((4, 1))
PEst = np.eye(4)
xDR = np.zeros((4, 1)) # Dead reckoning
# history
hxEst = xEst
hxTrue = xTrue
hxDR = xTrue
hz = np.zeros((2, 1))
while SIM_TIME >= time:
time += DT
u = calc_input()
xTrue, z, xDR, ud = observation(xTrue, xDR, u)
xEst, PEst = ekf_estimation(xEst, PEst, z, ud)
# store data history
hxEst = np.hstack((hxEst, xEst))
hxDR = np.hstack((hxDR, xDR))
hxTrue = np.hstack((hxTrue, xTrue))
hz = np.hstack((hz, z))
if show_animation:
plt.cla()
# for stopping simulation with the esc key.
plt.gcf().canvas.mpl_connect('key_release_event',
lambda event: [exit(0) if event.key == 'escape' else None])
plt.plot(hz[0, :], hz[1, :], ".g")
plt.plot(hxTrue[0, :].flatten(),
hxTrue[1, :].flatten(), "-b")
plt.plot(hxDR[0, :].flatten(),
hxDR[1, :].flatten(), "-k")
plt.plot(hxEst[0, :].flatten(),
hxEst[1, :].flatten(), "-r")
plot_covariance_ellipse(xEst, PEst)
plt.axis("equal")
plt.grid(True)
plt.pause(0.001)
if __name__ == '__main__':
main()