{ "cells": [ { "cell_type": "markdown", "metadata": {}, "source": [ "# Extended Kalman Filter (EKF)\n", "\n", "Let us summarize first Kalman filtering using notation of [Welch and Bishop (2006)](http://www.cs.unc.edu/~welch/media/pdf/kalman_intro.pdf).\n", "\n", "Parts of linear system model:\n", "\n", "* state transition matrix: $\\mathbf{A}$\n", "* inital state and its covariance matrix: $\\mathbf{x}_0$, $\\mathbf{P}_0$\n", "* control matrix: $\\mathbf{B}$\n", "* system noise covariance matrix: $\\mathbf{Q}$\n", "* measurement matrix: $\\mathbf{H}$\n", "* measurement noise covariance matrix: $\\mathbf{R}$\n", "\n", "Update estimate of system's state vector $\\hat{\\mathbf{x}}_k$ from equations of the filter: \n", "\n", "1. previous state and its covariance: $\\hat{\\mathbf{x}}_{k-1}$, $\\mathbf{P}_{k-1}$\n", "\n", "2. prediction of state for the next epoch\n", "\n", " 1. prediction of system state: $ \\hat{\\mathbf{x}}_{k}^{-} = \\mathbf{A}\\hat{\\mathbf{x}}_{k-1} + \\mathbf{B}\\mathbf{u}_{k-1} $\n", " \n", " 2. prediction of system state covariance: $ \\mathbf{P}_{k}^{-} = \\mathbf{A}\\mathbf{P}_{k-1}\\mathbf{A}^T + \\mathbf{Q} $\n", "\n", "3. measurement update of system state\n", "\n", " 1. Kalman gain matrix: $ \\mathbf{K}_k = \\mathbf{P}_k^-{} \\mathbf{H}_k^T (\\mathbf{H} \\mathbf{P}_k^-{} \\mathbf{H}^T + \\mathbf{R})^{-1} $\n", " \n", " 2. system state update from measurements $\\mathbf{z}_k$: $\\hat{\\mathbf{x}}_k = \\hat{\\mathbf{x}}_k^-{} + \\mathbf{K}_k (\\mathbf{z}_k - \\mathbf{H}(\\hat{\\mathbf{x}}_k^-{})) $\n", " \n", " 3. covariance matrix of updated system state: $\\mathbf{P}_k = (\\mathbf{I} - \\mathbf{K}_k \\mathbf{H}) \\mathbf{P}_k^-{}$\n", " \n", "As it was mentioned the most difficult part is to set up a correct model of the system under study. In the following we try to create the system model for a simple navigation problem." ] }, { "cell_type": "markdown", "metadata": {}, "source": [ "## Odometry from wheel-mounted two-axis accelerometry\n", "\n", "We have the following problem: determine distance traveled by a wheel from the data of a wheel-mounted two-axis accelerometer sensor. Let us assume that the wheel is rolling without slipping on a horizontal surface.\n", "\n", "Rolling *without slipping* consists of linear motion plus rolling. The instantaneous point of contact has zero velocity, see the following figure:\n", "\n", "\n", "\n", "In the following figure the two-axis accelerometer S is shown attached to the wheel of radius $r_w$ at a distance $r_s$ from its centre O. The first axis of the sensor is perpendicular to the radius pointing along in the positive (clockwise) direction of rotation, while its second axis points to the centre radially inwards. \n", "\n", "\n", "\n", "Components of the vector of gravity $\\mathbf{g}$ along the axes of the sensor are:\n", "\n", "$$a_1=-g\\sin(\\theta)$$\n", "$$a_2=-g\\cos(\\theta)$$." ] }, { "cell_type": "markdown", "metadata": {}, "source": [ "If the centre O of the wheel has linear acceleration $\\ddot{p}$, proof mass of the sensor S experiences an acceleration in the opposite direction according to the figure\n", "\n", "\n", "\n", "the components of which are:\n", "\n", "$$a_1=\\ddot{p}\\cos(\\theta)$$\n", "$$a_2=-\\ddot{p}\\sin(\\theta)$$.\n", "\n" ] }, { "cell_type": "markdown", "metadata": {}, "source": [ "Finally, accelerated rotation of the wheel causes centripetal and centrifugal accelerations along $a_1$ and $a_2$, respectively.\n", "\n", "\n", "\n", "Due to the no-slip condition of the wheel rotation angle $\\theta$, angular velocity $\\dot\\theta$ and angular acceleration $\\ddot\\theta$ are related to distance $p$, velocity $\\dot{p}$ and linear acceleration $\\ddot{p}$:\n", "\n", "$$\\theta=\\frac{p}{r_w}$$\n", "$$\\dot\\theta=\\frac{\\dot{p}}{r_w}$$\n", "$$\\ddot\\theta=\\frac{\\ddot{p}}{r_w}$$\n", "\n", "Therefore, accelerations along sensor axes are\n", "\n", "$$a_1=-r_s \\ddot\\theta = -\\frac{r_s}{r_w}\\ddot{p}$$\n", "$$a_2=-r_s \\dot\\theta^2 = -\\frac{r_s}{r_w^2}\\dot{p}^2$$\n", "\n", "Components of the *full* sensor acceleration thus may be written as:\n", "\n", "$$a_1=-g\\sin(\\frac{p}{r_w})+\\ddot{p}\\cos(\\frac{p}{r_w})-\\frac{r_s}{r_w}\\ddot{p}$$\n", "$$a_2=-g\\cos(\\frac{p}{r_w})-\\ddot{p}\\sin(\\frac{p}{r_w})-\\frac{r_s}{r_w^2}\\dot{p}^2$$\n" ] }, { "cell_type": "markdown", "metadata": {}, "source": [ "### State and measurement function\n", "\n", "System *state vector* $\\mathbf{x}$ for Kalman filtering is composed of position, velocity and acceleration of the wheel\n", "\n", "$$\\mathbf{x} = \\begin{bmatrix}\n", "p\\\\ \n", "\\dot p\\\\ \n", "\\ddot p\n", "\\end{bmatrix} .$$\n", "\n", "Measurement function $h(\\mathbf{x},\\mathbf{v})$ is a function of measured accelerations \n", "\n", "$$ h(\\mathbf{x},\\mathbf{v}) = \\begin{bmatrix}\n", "-g\\sin\\left(\\frac{p}{r_w}\\right)+\\ddot{p}\\cos\\left(\\frac{p}{r_w}\\right)-\\frac{r_s}{r_w}\\ddot{p} + v_1\\\\ \n", "-g\\cos\\left(\\frac{p}{r_w}\\right)-\\ddot{p}\\sin\\left(\\frac{p}{r_w}\\right)-\\frac{r_s}{r_w^2}\\dot{p}^2 + v_2\n", "\\end{bmatrix} $$\n", "\n", "where $\\mathbf{v}=(v_1,v_2)$ denotes measurement noise, which is a Gaussian distributed random variable with zero mean.\n", "\n", "The above function is nonlinear , hence the basic Kalman filter cannot be used for this problem. Instead the **Extended Kalman Filter** will be used. This involves linearization of nonlinear equations at measurements and system state estimation.\n", "\n", "First we define in Python the measurement function for later use:" ] }, { "cell_type": "code", "execution_count": 1, "metadata": {}, "outputs": [], "source": [ "def h(x,rs,rw):\n", " ## measurement function\n", " ## x = state vector (p,pdot,pdotdot)\n", " ## rs = distance of sensor from wheel axis\n", " ## rw = wheel radius\n", " g = 9.81\n", " h1 = -g*np.sin(x[0]/rw) + x[2]*np.cos(x[0]/rw) - x[2]*rs/rw\n", " h2 = -g*np.cos(x[0]/rw) - x[2]*np.sin(x[0]/rw) - (x[1])**2*rs/(rw**2)\n", " return np.array([h1,h2]).flatten()" ] }, { "cell_type": "markdown", "metadata": {}, "source": [ "State transition matrix $A$ is already linear:\n", "\n", "$$ A = \\begin{bmatrix}\n", "1 & \\Delta t & \\frac{1}{2}\\Delta t^2 \\\\ \n", "0 & 1 & \\Delta t\\\\ \n", "0 & 0 & 1\n", "\\end{bmatrix}$$\n", "\n", "It is thus easy to define the state propagation function in Python:" ] }, { "cell_type": "code", "execution_count": 2, "metadata": {}, "outputs": [], "source": [ "def f(x,dt):\n", " \"\"\" state propagation function\n", " x = state vector (p,pdot,pdotdot)\n", " dt = time difference\n", " \"\"\"\n", " f1 = x[0] + x[1]*dt + 0.5*x[2]*dt**2\n", " f2 = x[1] + x[2]*dt\n", " f3 = x[2]\n", " return np.array([f1,f2,f3]).flatten()" ] }, { "cell_type": "markdown", "metadata": {}, "source": [ "## Equations of the Extended Kalman Filter (EKF)\n", "\n", "\n", "In cases where either the measurement or state update equation or both are nonlinear, we need formulas of extended Kalman filtering.\n", "\n", "State of the system changes according to the nonlinear function $f$:\n", "\n", "$$ x_k = f(\\mathbf{x}_{k-1}, \\mathbf{u}_{k-1}, \\mathbf{w}_{k-1})$$\n", "\n", "where $\\mathbf{w}$ denotes system noise. Moreover, measurements $\\mathbf{z}$ are connected with system state $x$ through the following nonlinear function $f$:\n", "\n", "$$z_k = h(\\mathbf{x}_k, \\mathbf{v}_k),$$\n", "\n", "where $\\mathbf{v}$ denotes measurement noise. Generally, of course, these noises are unknown, hence system state and vector of measurements are calculated without these noises:\n", "\n", "$$ \\tilde{\\mathbf{x}_k} = f(\\hat{\\mathbf{x}}_{k-1}, \\mathbf{u}_{k-1}, \\mathbf{0})$$\n", "$$ \\tilde{\\mathbf{z}_k} = h(\\tilde{\\mathbf{x}}_k, \\mathbf{0})$$\n", "\n", "where $\\hat{\\mathbf{x}}_{k-1}$ denotes estimate of previous system state vector. It is important to make a remark: a basic flaw of the extended Kalman filter is that since transformed Gaussian PDFs of random variables become non-Gaussian, the estimate cannot be optimal.\n", "\n", "Linearization of the equations yields\n", "\n", "$$ \\mathbf{x}_k \\approx \\tilde{\\mathbf{x}}_k + \\mathbf{A}(\\mathbf{x}_{k-1} - \\hat{\\mathbf{x}}_{k-1}) + \\mathbf{W}\\mathbf{w}_{k-1}$$\n", "\n", "$$ \\mathbf{z}_k \\approx \\tilde{\\mathbf{z}}_k + \\mathbf{H}(\\mathbf{x}_k - \\tilde{\\mathbf{x}}_{k}) + \\mathbf{V}\\mathbf{v}_{k},$$\n", "\n", "where\n", "\n", "* $\\mathbf{x}_k$ and $\\mathbf{z}_k$ are current state and measurement vectors,\n", "* $\\tilde{\\mathbf{x}}_k$ and $\\tilde{\\mathbf{z}}_k$ vectors of state and measurement estimates,\n", "* $\\hat{\\mathbf{x}}_{k}$ final state estimate at epoch $k$,\n", "* a $\\mathbf{w}_{k}$ and $\\mathbf{v}_{k}$ are process and measurement noise,\n", "* $\\mathbf{A}$ denotes Jacobian of the function $f$ with respect to $\\mathbf{x}$,\n", "* $\\mathbf{W}$ denotes Jacobian of the function $f$ with respect to $\\mathbf{w}$,\n", "* $\\mathbf{H}$ denotes Jacobian of the function $h$ with respect to $\\mathbf{x}$,\n", "* $\\mathbf{v}$ denotes Jacobian of the function $h$ with respect to $\\mathbf{v}$.\n", "\n", "EKF filter equations provide estimate of system state $\\hat{\\mathbf{x}}_k$: \n", "\n", "1. estimation of previous system state and covariance: $\\hat{\\mathbf{x}}_{k-1}$, $\\mathbf{P}_{k-1}$\n", "\n", "2. prediction to the next epoch\n", "\n", " 1. prediction of system state: $ \\hat{\\mathbf{x}}_k^{-}=f(\\hat{\\mathbf{x}}_{k-1}, \\mathbf{u}_{k-1}, \\mathbf{0}) $\n", " \n", " 2. prediction of system state covariance: $ \\mathbf{P}_{k}^{-} = \\mathbf{A}_k\\mathbf{P}_{k-1}\\mathbf{A}_k^T + \\mathbf{W}_k\\mathbf{Q}_{k-1}\\mathbf{W}_k^T $\n", "\n", "3. system state prediction update from measurements\n", "\n", " 1. calculate Kalman gain: $ \\mathbf{K}_k = \\mathbf{P}_k^-{} \\mathbf{H}_k^T (\\mathbf{H} \\mathbf{P}_k^-{} \\mathbf{H}^T + \\mathbf{V}_k\\mathbf{R}_{k}\\mathbf{v}_k^T)^{-1} $\n", " \n", " 2. system state update from measurements $\\mathbf{z}_k$: $\\hat{\\mathbf{x}}_k = \\hat{\\mathbf{x}}_k^-{} + \\mathbf{K}_k (\\mathbf{z}_k - h(\\hat{\\mathbf{x}}_k^{-}, \\mathbf{0})) $\n", " \n", " 3. calculate covariance of updated system state: $\\mathbf{P}_k = (\\mathbf{I} - \\mathbf{K}_k \\mathbf{H}) \\mathbf{P}_k^-{}$\n", " " ] }, { "cell_type": "markdown", "metadata": {}, "source": [ "The extended filter in our problem requires writing the **Jacobian** of the nonlinear measurement equation. Jacobian $H$ of measurement function $h(\\mathbf{x},\\mathbf{v})$ is composed of partial derivatives of the state vector $\\mathbf{x}$ according to components ($p$, $\\dot{p}$, $\\ddot{p}$):\n", "\n", "$$ H = \\begin{bmatrix}\n", "-\\frac{g}{r_w}\\cos\\left(\\frac{p}{r_w}\\right)-\\frac{\\ddot{p}}{r_w}\\sin\\left(\\frac{p}{r_w}\\right) & 0 & \\cos\\left(\\frac{p}{r_w}\\right)-\\frac{r_s}{r_w}\\\\ \n", "\\frac{g}{r_w}\\sin\\left(\\frac{p}{r_w}\\right)-\\frac{\\ddot{p}}{r_w}\\cos\\left(\\frac{p}{r_w}\\right) & -2\\frac{r_s}{r_w^2}\\dot{p} & -\\sin\\left(\\frac{p}{r_w}\\right)\n", "\\end{bmatrix} .$$\n", "\n", "For the stochastic model we define state noise variance as $q=0.07 m/s^2$, measurement noise variances as $r_1=r_2=5 m/s^2$.\n", "\n", "The following Python function is used for calculating the matrix $H$:" ] }, { "cell_type": "code", "execution_count": 3, "metadata": {}, "outputs": [], "source": [ "def H(x,rs,rw):\n", " ## Jacobian of the measurement function\n", " ## x = state vector (p,pdot,pdotdot)\n", " ## distance of sensor from wheel axis\n", " ## rw = wheel radius\n", " g = 9.81\n", " H = np.zeros((2,3))\n", " H[0,0] = -g/rw*np.cos(x[0]/rw) - x[2]/rw*np.sin(x[0]/rw)\n", " H[0,1] = 0.0\n", " H[0,2] = np.cos(x[0]/rw)- rs/rw\n", " H[1,0] = g/rw*np.sin(x[0]/rw) - x[2]/rw*np.cos(x[0]/rw)\n", " H[1,1] = -2*x[1]*rs/(rw**2)\n", " H[1,2] = -np.sin(x[0]/rw)\n", " return H" ] }, { "cell_type": "markdown", "metadata": {}, "source": [ "### Acceleration sensor test data\n", "\n", "Paper by [Gersdorf B., Frese U. (2013)](https://pdfs.semanticscholar.org/ab65/2f5c812b580f1c6b154161317b2bb9434655.pdf) contains accelerometer [test data](./dat/a.txt) suitable for extended Kalman filtering. Numerical values are extracted from the figure in the PDF file. Opening PDF in `LibreOffice Draw` the figure in vector format can be saved to `.odg` compressed XML. Using `Notepad++` macros an `Excel` file can be created and used for transforming acceleration data to proper units (m/s2). Finally, the `Excel` data file can be exported to ASCII. " ] }, { "cell_type": "code", "execution_count": 4, "metadata": {}, "outputs": [ { "data": { "image/png": "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", "text/plain": [ "
" ] }, "metadata": { "needs_background": "light" }, "output_type": "display_data" } ], "source": [ "# -*- coding:utf-8 -*-\n", "import numpy as np\n", "import matplotlib.pyplot as plt\n", "\n", "data = np.loadtxt(\"./dat/a.txt\")\n", "t = data[:,0]\n", "a1= data[:,1]\n", "a2= data[:,2]\n", "\n", "# Plot acceleration data\n", "plt.figure(figsize=(10,5))\n", "plt.plot(t,a1, 'r-', label='acceleration 1, m/s^2', lw=1)\n", "plt.plot(t,a2, 'b-', label='acceleration 2, m/s^2', lw=1)\n", "#plt.xlim(30,52)\n", "plt.grid(color='grey')\n", "plt.title('Galaxy S2 sensor data', fontweight='bold')\n", "plt.xlabel('time (s)')\n", "plt.ylabel('acceleration (m/s^2)')\n", "plt.legend(loc='upper right', shadow=False, prop={'size':8}) \n", "plt.show()" ] }, { "cell_type": "markdown", "metadata": {}, "source": [ "As we have already seen in the first step of extended Kalman filtering the system state is predicted, then it is updated with a new measurement $\\mathbf{z}_k$.\n", "\n", "prediction:\n", "\n", "$$ \\hat{\\mathbf{x}}_k^-{} = f(\\mathbf{x}_k)$$\n", "$$ \\mathbf{P}_k^-{} = \\mathbf{A} \\mathbf{P}_k \\mathbf{A}^T + \\mathbf{Q} $$\n", "\n", "update:\n", "\n", "$$ \\mathbf{K}_k = \\mathbf{P}_k^-{} \\mathbf{H}_k^T (\\mathbf{H} \\mathbf{P}_k^-{} \\mathbf{H}^T + \\mathbf{R})^{-1} $$\n", "$$ \\hat{\\mathbf{x}}_k = \\hat{\\mathbf{x}}_k^-{} + \\mathbf{K}_k (\\mathbf{z}_k - h(\\hat{\\mathbf{x}}_k^-{})) $$\n", "$$ \\mathbf{P}_k = \\mathbf{P}_k^-{} - \\mathbf{K}_k \\mathbf{H} \\mathbf{P}_k^-{} $$\n", "\n", "Python function of one step:" ] }, { "cell_type": "code", "execution_count": 5, "metadata": {}, "outputs": [], "source": [ "def EKFstep(xk,Pk,A,H,Q,R,zk,dt,rs,rw):\n", " \"\"\"one step of the extended Kalman filter\n", " \"\"\"\n", " # system state transition (prediction)\n", " xkm = f(xk,dt)\n", " Pkm = np.dot(np.dot(A,Pk),A.T) + Q\n", " # measurement update\n", " Kk = np.dot(Pkm,np.dot(H.T,np.linalg.pinv(np.dot(np.dot(H,Pkm),H.T) + R)))\n", " xk1 = xkm + np.dot(Kk,(zk - h(xkm,rs,rw)))\n", " Pk1 = Pkm - np.dot(np.dot(Kk,H),Pkm)\n", "\n", " return xk1,Pk1" ] }, { "cell_type": "markdown", "metadata": {}, "source": [ "The filtering is implemented in the function **EKFWheel**(t,a1,a2,q,r). Arguments of this function are:\n", "* t: vector of measurement epochs\n", "* a1, a2: acceleration sensor data at epochs defined by t\n", "* q: process noise\n", "* r: measurement noise\n", "\n", "The function returns in matrix xe the estimated system state and angular position in the interval $-\\pi \\le \\theta \\le \\pi$.\n", "\n", "Python implementation:" ] }, { "cell_type": "code", "execution_count": 6, "metadata": {}, "outputs": [], "source": [ "def EKFwheel(t,a1,a2,q=0.07,r=5):\n", " \"\"\"\n", " Odometry using two-axis accelerometer sensor by extended Kalman filtering\n", " t - vector of measurement epochs\n", " a1, a2 - measured centrifugal and centripetal accelerations (m/s**2)\n", " q - process noise variance (m/s**2)\n", " r - measurement noise variance (m/s**2)\n", " \"\"\"\n", " # sensor offset from wheel axis and wheel radius (Samsung Galaxy S2, bycicle mounted)\n", " rs = 0.095 # meters\n", " rw = 0.35 # meters\n", " nt = t.shape[0]\n", "\n", " # state vector: t, p,vel,acc,theta\n", " xe = np.zeros((nt,5))\n", " xe[:,0]=t\n", " # start\n", " Q = q**2*np.eye(3)\n", " R = r**2*np.eye(2)\n", " xk = np.zeros((3))\n", " Pk = q**2*np.diag([0, 0, 1])\n", " Ak = np.zeros((3,3))\n", "\n", " for i in range(1,nt):\n", " dt = t[i]-t[i-1]\n", " Hk = H(xk,rs,rw)\n", " A = np.eye(3)+ np.array([[0,dt,0.5*dt**2], [0,0,dt], [0,0,0]])\n", " zk = np.array([a1[i],a2[i]])\n", " # EKF step\n", " xk1,Pk1 = EKFstep(xk,Pk,A,Hk,Q,R,zk,dt,rs,rw)\n", " xe[i,1:4] = xk1\n", " xk = xk1 # state update\n", " Pk = Pk1 # state covariance updated\n", " om = xk1[0]/rw # angular position of the wheel\n", " xe[i,4]=np.arctan2(np.sin(om),np.cos(om)); # angle: (-pi, pi)\n", "\n", " return xe" ] }, { "cell_type": "markdown", "metadata": {}, "source": [ "Make filtering:" ] }, { "cell_type": "code", "execution_count": 7, "metadata": {}, "outputs": [], "source": [ "xe = EKFwheel(t,a1,a2,0.17,5.0)" ] }, { "cell_type": "markdown", "metadata": {}, "source": [ "Finally we plot results of the extended Kalman filtering:" ] }, { "cell_type": "code", "execution_count": 8, "metadata": {}, "outputs": [ { "data": { "image/png": "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", "text/plain": [ "
" ] }, "metadata": { "needs_background": "light" }, "output_type": "display_data" } ], "source": [ "%matplotlib inline\n", "plt.figure(figsize=(10,5))\n", "plt.plot(xe[:,0],xe[:,1], 'b-', label='EKF distance, m')\n", "plt.plot(xe[:,0],xe[:,2], 'g-', label='EKF velocity, m/s')\n", "plt.plot(xe[:,0],xe[:,3], 'r-', label='EKF acceleration, m/s^2')\n", "plt.plot(xe[:,0],xe[:,4], color='orange', label='angular position, rad')\n", "plt.xlim(1,11)\n", "plt.grid(color='grey')\n", "plt.title('Results of the Extended Kalman filter (EKF)', fontweight='bold')\n", "plt.xlabel('time (s)')\n", "plt.legend(loc='upper left', shadow=False, prop={'size':8}) \n", "plt.show()" ] }, { "cell_type": "markdown", "metadata": {}, "source": [ "Let us compare these results with Fig.5 in the paper by [Gersdorf B., Frese U. (2013)](https://pdfs.semanticscholar.org/ab65/2f5c812b580f1c6b154161317b2bb9434655.pdf).\n", "\n", "\n", "\n", "These results are quite similar to each other but it should be noted that they also used angular velocity data ($\\omega$) provided by a giroscopic sensor besides the accelerometer output. We notice also that velocity and acceleration became negative instead of being positive as they should be. We suspect that this is due to the linearization." ] }, { "cell_type": "markdown", "metadata": {}, "source": [ "### Accelerometer data provided by Ákos Vinkó\n", "\n", "Accelerometer sensor data provided by [Ákos Vinkó](https://epito.bme.hu/vinko-akos) (Department of Highway and Railway Engineering) were also used for odometry. These are the tangential and radial acceleration components measured by a 3-axis accelerometer and data logger [GCDC data logger](http://www.gcdataconcepts.com/xlr8r-1.html) [accelerometer data](./dat/asz.dat) mounted on a bycicle wheel.\n", "\n", "First read and plot the data:" ] }, { "cell_type": "code", "execution_count": 9, "metadata": {}, "outputs": [ { "data": { "image/png": "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", "text/plain": [ "
" ] }, "metadata": { "needs_background": "light" }, "output_type": "display_data" } ], "source": [ "data = np.loadtxt(\"./dat/asz.dat\")\n", "t = data[:,0]\n", "a1= data[:,1]\n", "a2= data[:,2]\n", "\n", "# Plot accelerometer data\n", "plt.figure(figsize=(10,5))\n", "plt.plot(t,a1, 'r-', label='acceleration 1, m/s^2', lw=1)\n", "plt.plot(t,a2, 'b-', label='acceleration 2, m/s^2', lw=1)\n", "# selected part of data:\n", "plt.xlim(30,52)\n", "plt.grid(color='grey')\n", "plt.title('accelerometer data from Ákos Vinkó (freewheel)', fontweight='bold')\n", "plt.xlabel('time (s)')\n", "plt.ylabel('acceleration (m/s^2)')\n", "plt.legend(loc='upper right', shadow=False, prop={'size':8}) \n", "plt.show()" ] }, { "cell_type": "markdown", "metadata": {}, "source": [ "These data are much more noisy than those by Gersdorf and Freese. Let us see how these data are processed by the extended Kalman filter.\n", "\n", "We now have a slightly different system model since the initial phase angle of the accelerometer is not zero; moreover, sensor mounting and wheel radius are also different." ] }, { "cell_type": "code", "execution_count": 10, "metadata": {}, "outputs": [], "source": [ "def EKFwheel(t,a1,a2,q=0.01,r=5):\n", " \"\"\"\n", " Extended Kalman filter for dual axis acceleration sensor odometry\n", " t - vector of measurement epochs\n", " a1, a2 - measured centripetal and centrifugal accelerations (m/s**2)\n", " q - process noise variance (m/s**2)\n", " r - measurement noise variance (m/s**2)\n", " 29.09.2019. BME Gy. Tóth\n", " \"\"\"\n", " # sensor displacement from wheel axis and wheel radius\n", " rs = 0.165 # meter\n", " rw = 0.33 # meter\n", " nt = t.shape[0]\n", "\n", " # state vector: t, p,vel,acc,theta\n", " xe = np.zeros((nt,5))\n", " xe[:,0]=t\n", " # start\n", " # sensor in 'up' position at angle pi\n", " dist = np.pi*rw\n", " Qk = q**2\n", " Rk = r**2*np.eye(2)\n", " Vk = np.eye(2)\n", " xk = np.zeros((3))\n", " xk[0] = dist\n", " xe[0,1:4] = xk[:]\n", " xe[0,4] = np.pi\n", " Wk = np.array([0, 0, 1])\n", " Pk = Qk*np.outer(Wk,Wk)\n", " Ak = np.zeros((3,3))\n", "\n", " for i in range(1,nt):\n", " dt = t[i]-t[i-1]\n", " Hk = H(xk,rs,rw)\n", " Ak = np.eye(3)+ np.array([[0,dt,0.5*dt**2], [0,0,dt], [0,0,0]])\n", " zk = np.array([a1[i],a2[i]])\n", " # EKF step\n", " xk1,Pk1 = EKFstep(xk,Pk,Ak,Wk,Hk,Vk,Qk,Rk,zk,dt,rs,rw)\n", " xe[i,1:4] = xk1\n", " xk = xk1 # state update\n", " Pk = Pk1 # update of state covariance\n", " om = xk1[0]/rw # wheel's rotation angle\n", " xe[i,4]=np.arctan2(np.sin(om),np.cos(om)) # angle: (-pi, pi)\n", "\n", " return xe\n", "\n", "def EKFstep(xk,Pk,Ak,Wk,Hk,Vk,Qk,Rk,zk,dt,rs,rw):\n", " \"\"\"one step of the extended Kalman filter\n", " 29.09.2019. BME Gy. Tóth\n", " \"\"\"\n", " # state update\n", " xkm = f(xk,dt)\n", " Pkm = np.dot(np.dot(Ak,Pk),Ak.T) + np.dot(np.dot(Wk,Qk),Wk.T)\n", " # new measurement update\n", " Kk = np.dot(Pkm,np.dot(Hk.T,np.linalg.pinv(np.dot(np.dot(Hk,Pkm),Hk.T) + np.dot(np.dot(Vk,Rk),Vk.T))))\n", " xk1 = xkm + np.dot(Kk,(zk - h(xkm,rs,rw)))\n", " Pk1 = Pkm - np.dot(np.dot(Kk,Hk),Pkm)\n", "\n", " return xk1,Pk1" ] }, { "cell_type": "markdown", "metadata": {}, "source": [ "Good filtering requires smaller system noise and greater measurement noise. Additionally, orientation of the $a_2$ axis must be reversed." ] }, { "cell_type": "code", "execution_count": 11, "metadata": {}, "outputs": [ { "data": { "image/png": "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", "text/plain": [ "
" ] }, "metadata": { "needs_background": "light" }, "output_type": "display_data" } ], "source": [ "xe = EKFwheel(t,a1,-a2,0.01,10.0)\n", "\n", "## plot results\n", "plt.figure(figsize=(15,6))\n", "plt.plot(xe[:,0],xe[:,1], 'b-', label='distance by EKF, m')\n", "plt.plot(xe[:,0],xe[:,2], 'g-', label='velocity by EKF, m/s')\n", "plt.plot(xe[:,0],xe[:,3], 'r-', label='acceleration by EKF, m/s^2')\n", "plt.plot(xe[:,0],xe[:,4], color='orange', label='angle of rotation, rad')\n", "plt.xlim(30,50)\n", "plt.ylim(-5,50)\n", "plt.grid(color='grey')\n", "\n", "\n", "plt.title('EKF results using freewheel data by Vinkó Á.', fontweight='bold')\n", "plt.xlabel('time (s)')\n", "#plt.ylabel('distance (m), acceleration (m/s^2)')\n", "#plt.ylabel('velocity (m/s), angle (rad)')\n", " \n", "plt.legend(loc='upper left', shadow=False)\n", "plt.show()" ] }, { "cell_type": "markdown", "metadata": {}, "source": [ "It is easy to recognize three parts: acceleration, breaking and run-out." ] } ], "metadata": { "kernelspec": { "display_name": "Python 3", "language": "python", "name": "python3" }, "language_info": { "codemirror_mode": { "name": "ipython", "version": 3 }, "file_extension": ".py", "mimetype": "text/x-python", "name": "python", "nbconvert_exporter": "python", "pygments_lexer": "ipython3", "version": "3.9.16" } }, "nbformat": 4, "nbformat_minor": 1 }