EKF SLAM学习笔记03

2023-05-16

3 EKF SLAM

在上一节中我们看到的是扩展卡尔曼滤波在定位中的应用,EKF同样可以应用于SLAM问题中。在定位问题中,机器人接收到的观测值是其在二维空间中的x-y位置。如果机器人接收到的是跟周围环境有关的信息,例如机器人某时刻下距离某路标点的距离和角度,那么我们可以根据此时机器人自身位置的估计值,推测出该路标点在二维空间中的位置,将路标点的空间位置也作为待修正的状态量放入整个的状态向量中。

由此又引出了两个子问题:数据关联和状态扩增。

我们将通过以下python实例来理解ekf slam的原理(完整代码见原链接,有中文注释的附在了最后):

slam

  • 黑色星号: 路标点真实位置(代码中RFID数组代表真实位置)
  • 绿色×: 路标点位置估计值
  • 黑色线: 航迹推测方法得出的机器人轨迹
  • 蓝色线: 轨迹真值
  • 红色线: EKF SLAM得出的机器人轨迹

回想上一节的扩展卡尔曼滤波的公式:

=== Predict ===

x P r e d = F x t + B u t x_{Pred} = Fx_t+Bu_t xPred=Fxt+But

P P r e d = J F P t J F T + Q P_{Pred} = J_FP_t J_F^T + Q PPred=JFPtJFT+Q

=== Update ===

z P r e d = H x P r e d z_{Pred} = Hx_{Pred} zPred=HxPred

y = z − z P r e d y = z - z_{Pred} y=zzPred

S = J H P P r e d . J H T + R S = J_H P_{Pred}.J_H^T + R S=JHPPred.JHT+R

K = P P r e d . J H T S − 1 K = P_{Pred}.J_H^T S^{-1} K=PPred.JHTS1

x t + 1 = x P r e d + K y x_{t+1} = x_{Pred} + Ky xt+1=xPred+Ky

P t + 1 = ( I − K J H ) P P r e d P_{t+1} = ( I - K J_H) P_{Pred} Pt+1=(IKJH)PPred

EKF SLAM 使用一个EKF滤波器来解决SLAM问题,EKF SLAM的状态向量包括了机器人位姿 ( x , y , θ ) (x, y, \theta) (x,y,θ) 和观测到的各个路标点的坐标 [ ( m 1 x , m 1 y ) , ( m 2 x , m 2 y ) , . . . , ( m n x , m n y ) ] [(m_1x, m_1y), (m_2x, m_2y), ... , (m_nx, m_ny)] [(m1x,m1y),(m2x,m2y),...,(mnx,mny)] ,路标点与机器人位姿间的协方差矩阵也在更新。

vec

相应的协方差矩阵:

cov

可以简写作:

cov2

需要注意的是,由于状态向量中包含路标点位置坐标,所以随着机器人运动,观测到的路标点会越来越多,因此状态向量和状态协方差矩阵会不断变化。

运动模型

状态向量预测 在状态向量中,只有机器人位姿状态 ( x , y , θ ) (x, y, \theta) (x,y,θ)是随着机器人运动改变的,所以运动模型影响下的状态向量预测这步中只改变状态向量中的这三个值和协方差矩阵中对应的区域。以下是本实例中使用的运动模型,控制输入向量为机器人线速度和角速度 ( v , w ) (v,w) (v,w)

F = [ 1 0 0 0 1 0 0 0 1 ] \begin{aligned} F= \begin{bmatrix} 1 & 0 & 0 \\ 0 & 1 & 0 \\ 0 & 0 & 1 \end{bmatrix} \end{aligned} F=100010001

B = [ Δ t c o s ( θ ) 0 Δ t s i n ( θ ) 0 0 Δ t ] \begin{aligned} B= \begin{bmatrix} \Delta t cos(\theta) & 0\\ \Delta t sin(\theta) & 0\\ 0 & \Delta t \end{bmatrix} \end{aligned} B=Δtcos(θ)Δtsin(θ)000Δt

U = [ v t w t ] \begin{aligned} U= \begin{bmatrix} v_t\\ w_t\\ \end{bmatrix} \end{aligned} U=[vtwt]

X = F X + B U \begin{aligned} X = FX + BU \end{aligned} X=FX+BU

[ x t + 1 y t + 1 θ t + 1 ] = [ 1 0 0 0 1 0 0 0 1 ] [ x t y t θ t ] + [ Δ t c o s ( θ ) 0 Δ t s i n ( θ ) 0 0 Δ t ] [ v t + σ v w t + σ w ] \begin{aligned} \begin{bmatrix} x_{t+1} \\ y_{t+1} \\ \theta_{t+1} \end{bmatrix}= \begin{bmatrix} 1 & 0 & 0 \\ 0 & 1 & 0 \\ 0 & 0 & 1 \end{bmatrix}\begin{bmatrix} x_{t} \\ y_{t} \\ \theta_{t} \end{bmatrix}+ \begin{bmatrix} \Delta t cos(\theta) & 0\\ \Delta t sin(\theta) & 0\\ 0 & \Delta t \end{bmatrix} \begin{bmatrix} v_{t} + \sigma_v\\ w_{t} + \sigma_w\\ \end{bmatrix} \end{aligned} xt+1yt+1θt+1=100010001xtytθt+Δtcos(θ)Δtsin(θ)000Δt[vt+σvwt+σw]

可以看出运动模型与上一节中的并无不同(只是状态向量有区别), U U U 是包含线速度角速度 v t v_t vt w t w_t wt的控制输入向量, + σ v +\sigma_v +σv + σ w +\sigma_w +σw 表示控制输入也包含噪声。

协方差预测 对机器人位姿状态的协方差进行预测,本质上是加上运动模型误差,位姿的不确定性通过加上运动模型的协方差 Q Q Q而增加了。

P = G T P G + Q P = G^TPG + Q P=GTPG+Q

注意:这里的 G G G就是上一节公式中的雅克比矩阵 J F J_F JF,为与python代码保持一致,这里不再改动。

在这一步骤中,协方差矩阵 P P P里只有与机器人位姿相关的部分被修改,与路标点相关的部分没有改动。

def motion_model(x, u):
    """
    根据控制预测机器人位姿
    """
    F = np.array([[1.0, 0, 0],
                  [0, 1.0, 0],
                  [0, 0, 1.0]])

    B = np.array([[DT * math.cos(x[2, 0]), 0],
                  [DT * math.sin(x[2, 0]), 0],
                  [0.0, DT]])

    x = (F @ x) + (B @ u)
    # 返回3x1
    return x

# 计算雅克比矩阵,与上一节相比并无不同,只不过因为机器人位姿状态向量少了一个元素,jF是3×3:
def jacob_motion(x, u):
    Fx = np.hstack((np.eye(STATE_SIZE), np.zeros(
        (STATE_SIZE, LM_SIZE * calc_n_lm(x)))))

    jF = np.array([[0.0, 0.0, -DT * u[0] * math.sin(x[2, 0])],
                   [0.0, 0.0, DT * u[0] * math.cos(x[2, 0])],
                   [0.0, 0.0, 0.0]], dtype=np.float64)

    G = np.eye(STATE_SIZE) + Fx.T @ jF @ Fx
    # 返回雅克比矩阵G(3x3),和对角矩阵Fx(实际上的np.eye(3))
    return G, Fx,

观测模型

在这个实例中,观测模型比上一节要复杂,因为实例模拟的是激光雷达检测路标点获得的与机器人距离和角度的信息。观测值向量 z z z包含的两个元素就是机器人与路标点的相对距离和角度,因此单个路标点在二维空间内的坐标就可以通过机器人在二维空间内的坐标得出:

o1

等式左边就是第j个路标点在二维空间内的坐标。

相应地,可以得到机器人位姿状态与单个路标点观测值之间的转换关系,也就是观测模型:

o2
所以单个路标点的雅克比矩阵表示为:
o3

(说明: H t H_t Ht矩阵左上角的low表示这是针对单个路标点的雅克比矩阵,右上角的i表示这是对应第i组观测值的雅克比矩阵)

对于每个路标点,观测雅克比矩阵需要进行偏微分的有以下5个元素:

( μ ‾ t , x , μ ‾ t , y , μ ‾ t , θ , μ ‾ j , x , μ ‾ j , y ) (\overline\mu_{t,x}, \overline\mu_{t,y}, \overline\mu_{t,\theta}, \overline\mu_{j,x},\overline\mu_{j,y}) (μt,x,μt,y,μt,θ,μj,x,μj,y)

分别是机器人位姿状态和该路标点的二维x-y空间位置。

推导可得:

o4
o5

单个路标点的雅克比矩阵作用于整个观测模型雅克比矩阵上需要乘以一个矩阵 F x , j F_{x,j} Fx,j,来把单个雅克比矩阵的元素放到对应位置上,j就表示是第几个路标点。

o6
2 j − 2 = 2 ( j − 1 ) 2j-2=2(j-1) 2j2=2(j1)表示第j个路标点前的j-1个路标点的位置, 2 N − 2 j = 2 ( N − j ) 2N-2j=2(N-j) 2N2j=2(Nj)表示第j个路标点之后的N-j个路标点(N在此表示一共有N个路标点)的位置,这些位置都是0,因为该路标点不会作用于其他路标点。

def calc_innovation(lm, xEst, PEst, z, LMid):
    """
    Calculates the innovation based on expected position and landmark position
    
    :param lm:   landmark position
    :param xEst: estimated position/state
    :param PEst: estimated covariance
    :param z:    read measurements
    :param LMid: landmark id
    :returns:    returns the innovation y, and the jacobian H, and S, used to calculate the Kalman Gain
    """
    delta = lm - xEst[0:2]
    q = (delta.T @ delta)[0, 0]
    z_angle = math.atan2(delta[1, 0], delta[0, 0]) - xEst[2, 0]
    zp = np.array([[math.sqrt(q), pi_2_pi(z_angle)]]) # 对应以上的观测模型 
    y = (z - zp).T
    y[1] = pi_2_pi(y[1])
    # 放入delta的平方(标量),delta(2x1),状态向量和lm在状态向量中的序号+1
    H = jacob_h(q, delta, xEst, LMid + 1)
    S = H @ PEst @ H.T + R

    return y, S, H

def jacob_h(q, delta, x, i):
    """
    Calculates the jacobian of the measurement function
    
    :param q:     the range from the system pose to the landmark
    :param delta: the difference between a landmark position and the estimated system position
    :param x:     the state, including the estimated system position
    :param i:     landmark id + 1
    :returns:     the jacobian H
    """
    sq = math.sqrt(q)
    G = np.array([[-sq * delta[0, 0], - sq * delta[1, 0], 0, sq * delta[0, 0], sq * delta[1, 0]],
                  [delta[1, 0], - delta[0, 0], - q, - delta[1, 0], delta[0, 0]]]) # 单个路标点的雅克比矩阵
    G = G / q # 单个路标点的雅克比矩阵
    nLM = calc_n_lm(x) # 路标点总数
    F1 = np.hstack((np.eye(3), np.zeros((3, 2 * nLM))))

    F2 = np.hstack((np.zeros((2, 3)), np.zeros((2, 2 * (i - 1))),
                    np.eye(2), np.zeros((2, 2 * nLM - 2 * i))))
    F = np.vstack((F1, F2))
    H = G @ F

    return H

其中jacob_h函数中的这几行代码:

F1 = np.hstack((np.eye(3), np.zeros((3, 2 * nLM))))
F2 = np.hstack((np.zeros((2, 3)), np.zeros((2, 2 * (i - 1))),
                    np.eye(2), np.zeros((2, 2 * nLM - 2 * i))))
F = np.vstack((F1, F2))

就是在构建上面推导的算式中的 F x , j F_{x,j} Fx,j矩阵,在代码中,nLM表示路标点总数,i表示路标点的id,运行几个例子来看看 F x , j F_{x,j} Fx,j矩阵的细节:

import numpy as np
nLM = 3 # 假设共有三个路标点
i = 1
F1 = np.hstack((np.eye(3), np.zeros((3, 2 * nLM))))
F2 = np.hstack((np.zeros((2, 3)), np.zeros((2, 2 * (i - 1))),np.eye(2), np.zeros((2, 2 * nLM - 2 * i))))
F = np.vstack((F1, F2))
print(F1)
print(F2)
print(F)
[[ 1.  0.  0.  0.  0.  0.  0.  0.  0.]
 [ 0.  1.  0.  0.  0.  0.  0.  0.  0.]
 [ 0.  0.  1.  0.  0.  0.  0.  0.  0.]]
[[ 0.  0.  0.  1.  0.  0.  0.  0.  0.]
 [ 0.  0.  0.  0.  1.  0.  0.  0.  0.]]
[[ 1.  0.  0.  0.  0.  0.  0.  0.  0.]
 [ 0.  1.  0.  0.  0.  0.  0.  0.  0.]
 [ 0.  0.  1.  0.  0.  0.  0.  0.  0.]
 [ 0.  0.  0.  1.  0.  0.  0.  0.  0.]
 [ 0.  0.  0.  0.  1.  0.  0.  0.  0.]]
i = 2
F1 = np.hstack((np.eye(3), np.zeros((3, 2 * nLM))))
F2 = np.hstack((np.zeros((2, 3)), np.zeros((2, 2 * (i - 1))),np.eye(2), np.zeros((2, 2 * nLM - 2 * i))))
F = np.vstack((F1, F2))
print(F1)
print(F2)
print(F)
[[ 1.  0.  0.  0.  0.  0.  0.  0.  0.]
 [ 0.  1.  0.  0.  0.  0.  0.  0.  0.]
 [ 0.  0.  1.  0.  0.  0.  0.  0.  0.]]
[[ 0.  0.  0.  0.  0.  1.  0.  0.  0.]
 [ 0.  0.  0.  0.  0.  0.  1.  0.  0.]]
[[ 1.  0.  0.  0.  0.  0.  0.  0.  0.]
 [ 0.  1.  0.  0.  0.  0.  0.  0.  0.]
 [ 0.  0.  1.  0.  0.  0.  0.  0.  0.]
 [ 0.  0.  0.  0.  0.  1.  0.  0.  0.]
 [ 0.  0.  0.  0.  0.  0.  1.  0.  0.]]
i = 3
F1 = np.hstack((np.eye(3), np.zeros((3, 2 * nLM))))
F2 = np.hstack((np.zeros((2, 3)), np.zeros((2, 2 * (i - 1))),np.eye(2), np.zeros((2, 2 * nLM - 2 * i))))
F = np.vstack((F1, F2))
print(F1)
print(F2)
print(F)
[[ 1.  0.  0.  0.  0.  0.  0.  0.  0.]
 [ 0.  1.  0.  0.  0.  0.  0.  0.  0.]
 [ 0.  0.  1.  0.  0.  0.  0.  0.  0.]]
[[ 0.  0.  0.  0.  0.  0.  0.  1.  0.]
 [ 0.  0.  0.  0.  0.  0.  0.  0.  1.]]
[[ 1.  0.  0.  0.  0.  0.  0.  0.  0.]
 [ 0.  1.  0.  0.  0.  0.  0.  0.  0.]
 [ 0.  0.  1.  0.  0.  0.  0.  0.  0.]
 [ 0.  0.  0.  0.  0.  0.  0.  1.  0.]
 [ 0.  0.  0.  0.  0.  0.  0.  0.  1.]]

在实例中,机器人在每个时刻t都会得到若干组观测值,就像在现实中,每隔一定时间,机器人都会得到传感器的一系列测量值一样。那么如何知道一组观测值 z t i = ( r t i , ϕ t i ) T z_t^i=(r_t^i,\phi_t^i)^T zti=(rti,ϕti)T 对应的是第几个路标点呢?也就是说,上面第j个路标点的j是怎么得到的?下面简述本python实例中的方案:

对于每一组观测值 z t i = ( r t i , ϕ t i ) T z_t^i=(r_t^i,\phi_t^i)^T zti=(rti,ϕti)T,计算对应此时刻的机器人位姿,已有的状态向量:

o7
中的从landmark 1到landmark n的每一个路标点的观测值,也就是从此时刻机器人的位置向四周看去,landmark 1到landmark n的观测值,计算这些观测值与观测值 z t i = ( r t i , ϕ t i ) T z_t^i=(r_t^i,\phi_t^i)^T zti=(rti,ϕti)T残差,如果这些残差的马哈拉诺比斯距离均大于某一个阈值,则判定这是一个没观测过的新的路标点;如果这些距离不是都大于某个阈值,则我们简单地认为距离最短的那个路标点landmark就是观测值 z t i = ( r t i , ϕ t i ) T z_t^i=(r_t^i,\phi_t^i)^T zti=(rti,ϕti)T对应的路标点。简单来说,找跟观测值 z t i = ( r t i , ϕ t i ) T z_t^i=(r_t^i,\phi_t^i)^T zti=(rti,ϕti)T差别最小的那个路标点,如果差别都挺大,那就认为看到了个新的路标点。

马哈拉诺比斯距离的阈值在代码中的值为2.0:

M_DIST_TH = 2.0  # Threshold of Mahalanobis distance for data association.
## 注:马哈拉诺比斯距离Mahalanobis distance是由印度统计学家马哈拉诺比斯提出的,表示数据的协方差距离。
## 它是一种有效的计算两个未知样本集的相似度的方法。与欧氏距离不同的是它考虑到各种特性之间的联系并且是尺度无关的,
## 即独立于测量尺度(来自wiki)。

在实例中寻找匹配的路标点编号id的对应代码是:

def search_correspond_landmark_id(xAug, PAug, zi):
    """
    Landmark association with Mahalanobis distance
    """
    # 此时已有的LM的个数:
    nLM = calc_n_lm(xAug)

    min_dist = []

    for i in range(nLM):
        # 返回第i个已有LM的坐标lm:
        lm = get_landmark_position_from_state(xAug, i)
        # 放入第i个已有LM的坐标lm、机器人位姿预测过的状态向量xAug和variance PAug、待比较的新观测zi
        y, S, H = calc_innovation(lm, xAug, PAug, zi, i)
        # 由残差y计算Mahalanobis distance:y.T @ np.linalg.inv(S) @ y
        min_dist.append(y.T @ np.linalg.inv(S) @ y)

    min_dist.append(M_DIST_TH)  # new landmark

    min_id = min_dist.index(min(min_dist))

    return min_id

这种根据残差的马哈拉诺比斯距离最小来寻找匹配的路标点只是一种理想化的简单处理方式,实际应用中的“data association”会复杂得多。

接下来还有一步需要注意,如果 z t i = ( r t i , ϕ t i ) T z_t^i=(r_t^i,\phi_t^i)^T zti=(rti,ϕti)T是一个未观测过的路标点的观测值,那么需要对状态向量和状态协方差矩阵进行扩增,对应的python代码为:

# Extend state and covariance matrix
xAug = np.vstack((xEst, calc_landmark_position(xEst, z[iz, :])))
PAug = np.vstack((np.hstack((PEst, np.zeros((len(xEst), LM_SIZE)))),
                  np.hstack((np.zeros((LM_SIZE, len(xEst))), initP))))
xEst = xAug
PEst = PAug

其中的initP是一个对角元素为1的2×2矩阵,代表给新增的一个路标点的状态量协方差一个初始值。

至此,我们了解了机器人对路标点的观测模型,以及如何计算观测模型的雅克比矩阵,接下来就可以继续计算卡尔曼增益 K K K,执行EKF中的更新步骤了。整个更新步骤的算法总结如下:

o8
o9
最后再说一点此实例中有关仿真数据生成的内容,在observation函数中,根据机器人位姿真值决定机器人可以看到哪几个路标点,再将这几个路标点的观测值人为加上噪声。

参考链接:
SLAM笔记五——EKF-SLAM
PythonRobotics/SLAM/EKFSLAM

附上带中文注释的完整代码:

"""
Extended Kalman Filter SLAM example

author: Atsushi Sakai (@Atsushi_twi)

https://github.com/AtsushiSakai/PythonRobotics/tree/master/SLAM/EKFSLAM
"""

import math

import matplotlib.pyplot as plt
import numpy as np

# 在这里我对代码做了一些改动,原代码的Cx不太便于读者理解:
# EKF state covariance: 3x3 size
Q = np.diag([0.5, 0.5, np.deg2rad(30.0)]) ** 2
# landmark observation covariance: 2x2 size
R = np.diag([0.5, 0.5])**2

#  Simulation parameter
Q_sim = np.diag([0.2, np.deg2rad(1.0)]) ** 2
R_sim = np.diag([1.0, np.deg2rad(10.0)]) ** 2

DT = 0.1  # time tick [s]
SIM_TIME = 50.0  # simulation time [s]
MAX_RANGE = 20.0  # maximum observation range
M_DIST_TH = 2.0  # Threshold of Mahalanobis distance for data association.
## 注:马哈拉诺比斯距离是由印度统计学家马哈拉诺比斯提出的,表示数据的协方差距离。它是一种有效的计算两个未知样本集的相似度的方法。与欧氏距离不同的是它考虑到各种特性之间的联系并且是尺度无关的,即独立于测量尺度(来自wiki)。 
STATE_SIZE = 3  # State size [x,y,yaw]
LM_SIZE = 2  # LM state size [x,y]

show_animation = True


def ekf_slam(xEst, PEst, u, z):
    # Predict
    # 预测过程只与运动模型有关
    S = STATE_SIZE
    # 返回运动模型雅克比G和对角矩阵Fx
    G, Fx = jacob_motion(xEst[0:S], u)
    # 返回机器人位姿的在含噪控制下的预测:
    xEst[0:S] = motion_model(xEst[0:S], u)
    # 更新机器人位姿的P
    PEst[0:S, 0:S] = G.T @ PEst[0:S, 0:S] @ G + Fx.T @ Q @ Fx
    # 给Landmark准备的variance
    initP = np.eye(2) 

    # Update
    # 对在此时刻新得到的一组z含噪观测,对z中的每一个元素做操作:
    for iz in range(len(z[:, 0])):  # for each observation
        min_id = search_correspond_landmark_id(xEst, PEst, z[iz, 0:2])

        nLM = calc_n_lm(xEst)
        # 在函数search_correspond_landmark_id中,把M_DIST_TH放在了最后一个,
        # 又因为已有的LM的序号值范围是(0至(nLM-1)),所以最后一个值M_DIST_TH的序号就是nLM,
        # 所以如果min_id等于nLM,意味着新观测z[iz, 0:2]与所有已有观测的马哈拉诺比斯距离都超过了M_DIST_TH,
        # 即这是一个以前没看到过的LM:
        if min_id == nLM:
            print("New LM")
            # Extend state and covariance matrix
            xAug = np.vstack((xEst, calc_landmark_position(xEst, z[iz, :])))
            PAug = np.vstack((np.hstack((PEst, np.zeros((len(xEst), LM_SIZE)))),
                              np.hstack((np.zeros((LM_SIZE, len(xEst))), initP))))
            xEst = xAug
            PEst = PAug
        # 如果min_id不等于nLM,则认为这是一个已经观测过的LM,
        # 马哈拉诺比斯距离最小的那个,也就是min_id指向的那个就是对应的已观测LM:
        lm = get_landmark_position_from_state(xEst, min_id)
        y, S, H = calc_innovation(lm, xEst, PEst, z[iz, 0:2], min_id)

        K = (PEst @ H.T) @ np.linalg.inv(S)
        xEst = xEst + (K @ y)
        PEst = (np.eye(len(xEst)) - (K @ H)) @ PEst

    xEst[2] = pi_2_pi(xEst[2])

    return xEst, PEst


def calc_input():
    v = 1.0  # [m/s]
    yaw_rate = 0.1  # [rad/s]
    u = np.array([[v, yaw_rate]]).T
    return u


def observation(xTrue, xd, u, RFID):
    """
    仿真过程
    """
    xTrue = motion_model(xTrue, u)

    z = np.zeros((0, 3))

    for i in range(len(RFID[:, 0])):

        dx = RFID[i, 0] - xTrue[0, 0]
        dy = RFID[i, 1] - xTrue[1, 0]
        # 计算机器人位姿真值与路标点的距离d
        d = math.hypot(dx, dy)
        angle = pi_2_pi(math.atan2(dy, dx) - xTrue[2, 0])
        # 如果距离d小于阈值,代表机器人可以看到这个路标点:
        if d <= MAX_RANGE:
            dn = d + np.random.randn() * Q_sim[0, 0] ** 0.5  # add noise
            angle_n = angle + np.random.randn() * Q_sim[1, 1] ** 0.5  # add noise
            zi = np.array([dn, angle_n, i])
            z = np.vstack((z, zi))

    # add noise to input
    ud = np.array([[
        u[0, 0] + np.random.randn() * R_sim[0, 0] ** 0.5,
        u[1, 0] + np.random.randn() * R_sim[1, 1] ** 0.5]]).T

    xd = motion_model(xd, ud)
    # 返回xTrue(3x1), z含噪观测(3xnLM含RFID的id),xd(3x1),ud含噪控制(2x1)
    return xTrue, z, xd, ud


def motion_model(x, u):
    """
    根据控制预测机器人位姿
    """
    F = np.array([[1.0, 0, 0],
                  [0, 1.0, 0],
                  [0, 0, 1.0]])

    B = np.array([[DT * math.cos(x[2, 0]), 0],
                  [DT * math.sin(x[2, 0]), 0],
                  [0.0, DT]])

    x = (F @ x) + (B @ u)
    # 返回3x1
    return x


def calc_n_lm(x):
    """
    返回Landmark的个数
    """
    n = int((len(x) - STATE_SIZE) / LM_SIZE)
    return n


def jacob_motion(x, u):
    Fx = np.hstack((np.eye(STATE_SIZE), np.zeros(
        (STATE_SIZE, LM_SIZE * calc_n_lm(x)))))

    jF = np.array([[0.0, 0.0, -DT * u[0] * math.sin(x[2, 0])],
                   [0.0, 0.0, DT * u[0] * math.cos(x[2, 0])],
                   [0.0, 0.0, 0.0]], dtype=np.float64)

    G = np.eye(STATE_SIZE) + Fx.T @ jF @ Fx
    # 返回雅克比矩阵G(3x3),和对角矩阵Fx(实际上的np.eye(3))
    return G, Fx,


def calc_landmark_position(x, z):
    """
    根据观测z和预测后的x状态向量,计算LM的坐标位置
    """
    zp = np.zeros((2, 1))

    zp[0, 0] = x[0, 0] + z[0] * math.cos(x[2, 0] + z[1])
    zp[1, 0] = x[1, 0] + z[0] * math.sin(x[2, 0] + z[1])

    return zp


def get_landmark_position_from_state(x, ind):
    """
    根据lm在状态向量中的id查找lm的坐标:
    """
    lm = x[STATE_SIZE + LM_SIZE * ind: STATE_SIZE + LM_SIZE * (ind + 1), :]

    return lm


def search_correspond_landmark_id(xAug, PAug, zi):
    """
    Landmark association with Mahalanobis distance
    """
    # 此时已有的LM的个数:
    nLM = calc_n_lm(xAug)

    min_dist = []

    for i in range(nLM):
        # 返回第i个已有LM的坐标lm:
        lm = get_landmark_position_from_state(xAug, i)
        # 放入第i个已有LM的坐标lm、机器人位姿预测过的状态向量xAug和variance PAug、待比较的新观测zi
        y, S, H = calc_innovation(lm, xAug, PAug, zi, i)
        # 由残差y计算Mahalanobis distance:y.T @ np.linalg.inv(S) @ y
        min_dist.append(y.T @ np.linalg.inv(S) @ y)

    min_dist.append(M_DIST_TH)  # new landmark

    min_id = min_dist.index(min(min_dist))

    return min_id


def calc_innovation(lm, xEst, PEst, z, LMid):
    """
    Calculates the innovation based on expected position and landmark position
    
    :param lm:   landmark position
    :param xEst: estimated position/state
    :param PEst: estimated covariance
    :param z:    read measurements
    :param LMid: landmark id
    :returns:    returns the innovation y, and the jacobian H, and S, used to calculate the Kalman Gain
    """
    delta = lm - xEst[0:2]
    q = (delta.T @ delta)[0, 0]
    z_angle = math.atan2(delta[1, 0], delta[0, 0]) - xEst[2, 0]
    zp = np.array([[math.sqrt(q), pi_2_pi(z_angle)]])
    y = (z - zp).T
    y[1] = pi_2_pi(y[1])
    # 放入delta的平方(标量),delta(2x1),状态向量和lm在状态向量中的序号+1
    H = jacob_h(q, delta, xEst, LMid + 1)
    S = H @ PEst @ H.T + R

    return y, S, H


def jacob_h(q, delta, x, i):
    """
    Calculates the jacobian of the measurement function
    
    :param q:     the range from the system pose to the landmark
    :param delta: the difference between a landmark position and the estimated system position
    :param x:     the state, including the estimated system position
    :param i:     landmark id + 1
    :returns:     the jacobian H
    """
    sq = math.sqrt(q)
    G = np.array([[-sq * delta[0, 0], - sq * delta[1, 0], 0, sq * delta[0, 0], sq * delta[1, 0]],
                  [delta[1, 0], - delta[0, 0], - q, - delta[1, 0], delta[0, 0]]])
    G = G / q
    nLM = calc_n_lm(x)
    F1 = np.hstack((np.eye(3), np.zeros((3, 2 * nLM))))

    F2 = np.hstack((np.zeros((2, 3)), np.zeros((2, 2 * (i - 1))),
                    np.eye(2), np.zeros((2, 2 * nLM - 2 * i))))
    F = np.vstack((F1, F2))
    H = G @ F

    return H


def pi_2_pi(angle):
    """
    将角度范围限定在[-pi,pi]
    """
    return (angle + math.pi) % (2 * math.pi) - math.pi


def main():
    print(__file__ + " start!!")

    time = 0.0

    # RFID positions [x, y]
    RFID = np.array([[10.0, -2.0],
                     [15.0, 10.0],
                     [3.0, 15.0],
                     [-5.0, 20.0]])

    # State Vector [x y yaw]'
    xEst = np.zeros((STATE_SIZE, 1))
    xTrue = np.zeros((STATE_SIZE, 1))
    PEst = np.eye(STATE_SIZE)

    xDR = np.zeros((STATE_SIZE, 1))  # Dead reckoning

    # history
    hxEst = xEst
    hxTrue = xTrue
    hxDR = xTrue

    while SIM_TIME >= time:
        time += DT
        u = calc_input() #真值

        xTrue, z, xDR, ud = observation(xTrue, xDR, u, RFID)
        # 返回xTrue(3x1), z含噪观测(3xnLM含RFID的id),xDR(3x1),ud含噪控制(2x1)

        xEst, PEst = ekf_slam(xEst, PEst, ud, z)

        x_state = xEst[0:STATE_SIZE]

        # store data history
        hxEst = np.hstack((hxEst, x_state))
        hxDR = np.hstack((hxDR, xDR))
        hxTrue = np.hstack((hxTrue, xTrue))

        if show_animation:  # pragma: no cover
            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(RFID[:, 0], RFID[:, 1], "*k")
            plt.plot(xEst[0], xEst[1], ".r")

            # plot landmark
            for i in range(calc_n_lm(xEst)):
                plt.plot(xEst[STATE_SIZE + i * 2],
                         xEst[STATE_SIZE + i * 2 + 1], "xg")

            plt.plot(hxTrue[0, :],
                     hxTrue[1, :], "-b")
            plt.plot(hxDR[0, :],
                     hxDR[1, :], "-k")
            plt.plot(hxEst[0, :],
                     hxEst[1, :], "-r")
            plt.axis("equal")
            plt.grid(True)
            plt.pause(0.001)


if __name__ == '__main__':
    main()

本文内容由网友自发贡献,版权归原作者所有,本站不承担相应法律责任。如您发现有涉嫌抄袭侵权的内容,请联系:hwhale#tublm.com(使用前将#替换为@)

EKF SLAM学习笔记03 的相关文章

  • PHP八大设计模式

    PHP命名空间 转自http blog csdn net flitrue article details 52614599 reload 可以更好地组织代码 xff0c 与Java中的包类似 Test1 php span class php
  • DataTables 详细设置(1)

    转自http blog csdn net arsiya jerry article details 50505294 并不是所有的后台开发都有美工和前端工程师来配合做页面 xff0c 为了显示数据并有一定的美感 xff0c jQuery的D
  • dataTables-使用详细说明整理

    转自 http blog csdn net mickey miki article details 8240477 本文共四部分 xff1a 官网 基本使用 遇到的问题 属性表 一 xff1a 官方网站 xff1a http www dat
  • 关于Xshell过期,需要采购问题

    1 卸载电脑中过期的xshell 2 http www netsarang com download free license html 去官网下载免费版 Home amp School 家庭和学校版本 注意邮箱要填写正确 填写完提交后会收
  • genromfs的使用及nuttx下romfs制作

    61 61 61 61 61 gt 我的博客目录导航 前言 这篇文章仅仅是为了记录如何使用genromfs制作romfs然后在nuttx上直接应用 xff0c 不会去详细介绍romfs的一系列特性 genromfs 首先去下载genromf
  • STM32智能小车系列教程(一)小车介绍及基本搭建

    大家收到小车包裹后 xff0c 想必都已经跃跃欲试了 xff0c 接下来关注我们的系列教程 xff0c 教你从零搭建一辆STM32F103智能小车 xff0c 本教程面向零基础 xff08 当然基本的单片机知识和C语言知识还是需要具备的 x
  • PHP上传图片 (从html到JS再到php onclick方式提交)

    1 首先form表单必须是post方式提交 xff0c 并且含有enctype 61 34 multipart form data 34 属性 如图 2 JS代码 利用formdata接收html中form表单的数据 利用append将其他
  • MongoDB Windows系统各个64位版本下载地址: http://dl.mongodb.org/dl/win32/x86_64

    MongoDB Windows系统各个64位版本下载地址 xff1a http dl mongodb org dl win32 x86 64
  • PostgreSQL表空间、数据库、模式、表、用户/角色之间的关系

    看PostgreSQL9的官方文档 xff0c 我越看越迷糊 xff0c 这表空间 xff0c 数据库 xff0c 模式 xff0c 表 xff0c 用户 xff0c 角色之间的关系怎么在PostgreSQL里这么混乱呢 xff1f 经过中
  • 关于phpExcel的使用

    execl数据导出 应用场景 xff1a 订单导出 64 param string title 模型名 xff08 如Member xff09 xff0c 用于导出生成文件名的前缀 64 param array cellName 表头及字段
  • phpExcel的使用方法以及导入导出实例【转载】

    一 下载PHPExcel 下载地址 xff1a https github com PHPOffice PHPExcel 二 读取Excel文件内容插入数据库 lt php require once 39 Classes PHPExcel p
  • 关于git 、初识git (fatal: Not a valid object name: 'master'.)

    主要错误原因是因为没有master分支 必须要commit一次 才可以有master分支 才可以创建别的分支 具体步骤 1 打开命令行 git add index html 2 git commit m 34 this is a test
  • 关于git的使用

    查看https blog csdn net qq 42072311 article details 80696886 https blog csdn net kevindgk article details 51606925 查看这两个博客
  • php使用upload封装类上传文件

    原文https blog csdn net navioo article details 51777799
  • phpStorm2018安装与破解(免安装打包版)

    首先将我为大家事先准备好的打包文件拷贝至软件安装盘 xff0c 本人安装于D盘 xff0c 所以这里已本人安装破解的过程进行讲述 1 gt phpStorm2018 2 2下载请转至链接 https pan baidu com s 1Kno
  • 最简洁的麦克纳姆轮原理与控制方法

    最简洁的麦克纳姆轮控制原理与控制方法 0 写在前面 对于第一次接触麦轮的小伙伴们肯定是没办法十分清晰地想象出麦轮底盘的各种运动该如何控制的 而在实际使用中 xff0c 麦轮的运动灵活性与控制难度之比又非常高 xff0c 可以说是在比较平整的
  • Nuttx下移植uorb笔记

    Nuttx下移植uorb笔记 之前接触过ros下的消息机制 xff08 生产者 消费者 xff09 模型 xff0c 第一感觉是灵活好用 xff0c 但是在资源有限的嵌入式环境里面 xff0c 邮箱 消息 显得就有点不那么灵活 xff0c
  • 关于ADRC算法以及参数整定(调参)的一些心得体会

    关于ADRC算法以及参数整定 xff08 调参 xff09 的一些心得体会 ADRC xff0c 全称叫做Active Disturbance Rejection Control xff0c 中文名是自抗扰控制技术 这项控制算法是由中科院的
  • boa-0.94.13:CGI中文问题

    为什么中文乱码 用win7 自带的浏览器ie 打开服务器的cgi form html xff0c 在Name 输入框输入 汉字 两个字 xff0c 提交服务器 如图1 图1 返回的是结果为 xff1a Server Got you para
  • 跑通VINS-Fusion全流程

    跑通VINS Fusion全流程 常规安装步骤详见官方1 ROS安装2 ceres solver安装3 VINS Fusion安装4 KITTI数据集下载5 跑通KITTI数据集 常规安装步骤详见官方 https github com HK

随机推荐

  • 带GPS的SLAM数据集汇总

    1 带GPS的相关SLAM数据集 Kitti 部分带部分不带 xff0c 看网站写的很详细 xff0c 数据集很常用 http www cvlibs net datasets kitti eval odometry php CMU Visu
  • 跑通GVINS——港科大新作

    跑通GVINS 港科大新作 0 简介1 环境2 跑通GVINS3 数据集4 相关资料打包下载 xff08 不包括数据集 xff09 6 泡泡机器人解读 港科大又一力作 xff01 vins mono以及vins fusion升级版GVINS
  • GVINS文章暴力翻译(仅供自学)

    GVINS文章暴力翻译 xff08 仅供自学 xff09 摘要1 介绍2 相关工作3 符号和定义A 框架b 状态 4 GNSS基本介绍A GNSS 概述B 伪距测量C 多普勒测量D SPP算法 5 系统概述6 概率公式A 地图估计B 惯性因
  • Vins-fusion用到的kitti数据集轨迹对不齐,使用evo -a转换

    kitti数据集基准问题 下面两个图一个是转换前 xff0c 一个是evo a 转换后的 问题描述 xff1a 现在遇到的问题是groundtruth和估计的位姿没有在一个坐标系中 xff0c 生成的轨迹对不齐 xff0c 需要首先根据位姿
  • 怎样用美图秀秀制作一寸照片

    有些时候 xff0c 老是会埋怨自己的http jingyan baidu com article 73c3ce28c852b7e50243d945 html证件照很难看 xff0c 自己拍的照片又不合格 xff0c 该怎么办呢 这里和大家
  • Realsense D435i关闭IR结构光

    Realsense D435i 关闭IR光 前言环境一次性关闭IR光从源码修改 前言 由于要做Realsense D435i的双目结构光相机标定 xff0c 其中用到了ROS来录制数据包 xff0c 但是结构光会影响标定 xff0c 所以得
  • vins-mono保存、重载地图、evo工具测试

    vins mono保存 重载地图 evo工具测试 地图保存与加载先跑起来修改地图保存的路径保存地图重载地图 evo测评evo工具修改数据格式使用evo绘制轨迹与双目ORB SLAM2进行对比 下面咱们来对vins mono地图进行简单测试
  • C++11新特性简介

    目录 功能扩展与增强 右值概念 类中右值扩展 标准库中右值扩展 内联命名空间 初始化 initialzier list 原始字符串 自定义字面值 类型自动推导 auto decltype 常量表达式函数constexpr 变长模板 空指针n
  • Realsense D435i单目跑ORB_SLAM2(无ROS版)

    主要参考mono euroc这个文件修改 xff0c 把数据源改成realsense的就可以了 如何获取realsense数据 xff0c 在之前的博客也阐述过 Realsense D435i 43 Opencv 获取彩色 深度 IMU数据
  • QGC开发 显示双GPS/RTK信息以及自定义页面(ubuntu)

    一 QGC开发 显示双GPS RTK信息 1 在sitl中进行仿真 xff0c 虚拟出第二个GPS mavlink发送到地面站 如下图中 xff0c 在mavlink msg gps2 raw h中找到发送第二组gps rtk数据函数mav
  • 03_FreeRTOS 二进制信号量

    03 FreeRTOS 二进制信号量 本文介绍 xff1a 二进制信号量的使用方法 简介信号量 信号量基本上用于将任务与系统中的其他事件同步 在FreeRTOS中 xff0c 信号量是基于队列机制实现的 FreeRTOS中有4种信号量 xf
  • 【首发】 ubuntu20.04安装matlab2021b/matlab2020b

    文章目录 一 下载地址1 1 2021b下载链接 BT 1 2 2021a下载链接1 3 2020b CSDN下载链接 二 MATLAB2021b安装方法2 1 Mount iso文件2 2 通过 install 启动安装程序2 3 输入正
  • 无人机右手定则以及角度大小方向粗判断

    无人机右手定则 xff1a 左力右场 xff0c 知道z轴方向 xff0c 然后就知道了xy轴方向 xff0c 其中x轴为大拇指指向的方向 四旋翼无人机欧拉角角度大小与其状态的关系 xff1a 设大地坐标系为 xff1a E xff08 O
  • NuttX RTOS

    目录 综述 NuttX是什么 看看这些文件和功能 它怎么会是一个小小的操作系统呢 xff1f NuttX讨论组 你想谈谈NuttX的特性吗 xff1f 你需要帮助吗 xff1f 问题吗 错误吗 下载 我在哪里可以买到NuttX xff1f
  • Arducopter Yaw角分析

    Arducopter Yaw 现梳理一遍Poshold模式下的yaw的情况 xff1a 首先从 Copter fast loop gt update flight mode gt Copter ModePosHold run span cl
  • TortoiseGit

    TortoiseGit用法 ubuntu16 04 18 04部署gitlab服务器 xff1a https blog csdn net qq 28263253 article details 80469203 一 如何安装 xff1a 下
  • 如何生成gazebo仿真环境的二维地图真值

    在移动机器人仿真中 xff0c 二维地图真值可以用来评价slam建图结果 xff0c 也可以直接给路径规划算法提供输入 利用gazebo进行仿真时 xff0c 有很多方法都可以获取静态仿真环境的二维地图真值 xff0c 本文将对以下链接 x
  • gazebo仿真环境加载模型方式

    我们都知道 xff0c gazebo可以在自带的gui中创建模型 导入模型 xff0c 然后将一批模型组成的仿真环境保存为一个world文件 xff1a 例如上图所示的场景 xff0c 我们可以从模型库中导入一些模型 xff0c 然后或直接
  • libCurl实现HTTP请求

    目录 接口说明使用步骤setopt函数部分选项说明 示例写数据回调GET请求POST请求 libCurl是一个多协议 跨平台的客户端URL传输库 xff1b 使用libCurl可方便地进行HTTP请求 接口说明 libCurl提供easy
  • EKF SLAM学习笔记03

    3 EKF SLAM 在上一节中我们看到的是扩展卡尔曼滤波在定位中的应用 xff0c EKF同样可以应用于SLAM问题中 在定位问题中 xff0c 机器人接收到的观测值是其在二维空间中的x y位置 如果机器人接收到的是跟周围环境有关的信息