Merge pull request #60 from kcamd/master

Fixes typos and small mistakes in chap. 8,9,10
This commit is contained in:
Roger Labbe 2015-09-20 12:40:54 -07:00
commit 3bd0eda268
3 changed files with 10 additions and 10 deletions

View File

@ -431,8 +431,8 @@
"\n",
"$$\n",
"\\begin{aligned}\n",
"x &= 1x + \\Delta t \\dot{x} + y + 0 \\dot{y} \\\\\n",
"v_x &= 0x + 1\\dot{x} + 1y + 0 \\dot{y} \\\\\n",
"x &= 1x + \\Delta t \\dot{x} + 0y + 0 \\dot{y} \\\\\n",
"v_x &= 0x + 1\\dot{x} + 0y + 0 \\dot{y} \\\\\n",
"y &= 0x + 0\\dot{x} + 1y + \\Delta t \\dot{y} \\\\\n",
"v_y &= 0x + 0\\dot{x} + 0y + 1 \\dot{y}\n",
"\\end{aligned}\n",
@ -901,9 +901,9 @@
"cell_type": "markdown",
"metadata": {},
"source": [
"The covariance contains the data for $x$ and $\\dot{x}$ in the upper left because of how it is organized. Recall that entries $\\mathbf{P}_{i,j}$ and $\\mathbf{P}_{j,i}$ contain $\\sigma_1\\sigma_2$.\n",
"The covariance contains the data for $x$ and $\\dot{x}$ in the upper left because of how it is organized. Recall that entries $\\mathbf{P}_{i,j}$ and $\\mathbf{P}_{j,i}$ contain $\\sigma_i\\sigma_j$.\n",
"\n",
"Finally, let's look at the lower left side of $\\mathbf{P}$, which is all 0s. Why 0s? Consider $\\mathbf{P}_{3,0}$. That stores the term $p\\sigma_3\\sigma_0$, which is the covariance between $\\dot{y}$ and $x$. These are independent, so the term will be 0. The rest of the terms are for similarly independent variables."
"Finally, let's look at the lower left side of $\\mathbf{P}$, which is all 0s. Why 0s? Consider $\\mathbf{P}_{3,0}$. That stores the term $\\sigma_3\\sigma_0$, which is the covariance between $\\dot{y}$ and $x$. These are independent, so the term will be 0. The rest of the terms are for similarly independent variables."
]
},
{
@ -1171,7 +1171,7 @@
"So now we have to design our state transition. The Newtonian equations for a time step are:\n",
"\n",
"$$\\begin{aligned} x_t &= x_{t-1} + v_{t-1}\\Delta t + 0.5a_{t-1} \\Delta t^2 \\\\\n",
" v_t &= v_{t-1} \\Delta t + a_{t-1} \\\\\n",
" v_t &= v_{t-1} + a_{t-1}\\Delta t \\\\\n",
" a_t &= a_{t-1}\\end{aligned}$$\n",
" \n",
"Recall that we need to convert this into the linear equation\n",
@ -2186,7 +2186,7 @@
"cell_type": "markdown",
"metadata": {},
"source": [
"Why does it return to zero at the end? Think about that before reading the answer. The filter begins to adapt to the new measurements my moving the state close to the measurements. The residuals become small, and so the state and residuals agree. "
"Why does it return to zero at the end? Think about that before reading the answer. The filter begins to adapt to the new measurements by moving the state close to the measurements. The residuals become small, and so the state and residuals agree. "
]
},
{
@ -2217,7 +2217,7 @@
"\n",
"$$\\bar{\\mathbf{x}} = \\mathbf{Fx} + \\mathbf{Bu}$$\n",
"\n",
"Our state is a vector, so we need to represent the control input as a vector. Here $\\mathbf{u}$ is the control input, and $mathbf{B}$ is a matrix that transforms the control input into a change in $\\mathbf{x}$. Let's consider a simple example. Suppose the state is $x = \\begin{bmatrix} x & \\dot{x}\\end{bmatrix}$ for a robot we are controlling and the control input is commanded velocity. This gives us a control input of \n",
"Our state is a vector, so we need to represent the control input as a vector. Here $\\mathbf{u}$ is the control input, and $\\mathbf{B}$ is a matrix that transforms the control input into a change in $\\mathbf{x}$. Let's consider a simple example. Suppose the state is $x = \\begin{bmatrix} x & \\dot{x}\\end{bmatrix}$ for a robot we are controlling and the control input is commanded velocity. This gives us a control input of \n",
"\n",
"$$\\mathbf{u} = \\begin{bmatrix}\\dot{x}_\\mathtt{cmd}\\end{bmatrix}$$\n",
"\n",

View File

@ -298,7 +298,7 @@
"\n",
"It is almost true to state that the only equation we (anyone) know how to solve is $\\mathbf{Ax}=\\mathbf{b}$. We only really know how to do linear algebra. I can give you a linear equation and you can solve it. If I told you your job depended on knowing how to solve the equation $ax+3b=c$ you would trivially solve it for any values of $a$, $b$, and $c$. There is no linear equation that you cannot either solve or prove has no solution ($x+1=x$).\n",
"\n",
"Anyone with formal education in math or physics has spent years learning various analytic ways to solve integrals, differential equations and so on. Yet even trivial physical systems produce equations that cannot be solved analytically. I can take an equation that you are able to integrate, insert a $\\log$ term, and render it insolvable. It is stuff like this that leads to jokes about physicists stating stating the problem \"assume a spherical cow on a frictionless surface in a vacuum...\"\n",
"Anyone with formal education in math or physics has spent years learning various analytic ways to solve integrals, differential equations and so on. Yet even trivial physical systems produce equations that cannot be solved analytically. I can take an equation that you are able to integrate, insert a $\\log$ term, and render it insolvable. It is stuff like this that leads to jokes about physicists stating the problem \"assume a spherical cow on a frictionless surface in a vacuum...\"\n",
"\n",
"How do we do things like model airflow over an aircraft in a computer, or predict weather, or track missiles with a Kalman filter? We retreat to what we know: $\\mathbf{Ax}=\\mathbf{b}$. We find some way to linearize the problem, turning it into a set of linear equations, and then use linear algebra software packages to compute an approximate solution. Linearizing a nonlinear problem gives us inexact answers, and in a recursive algorithm like a Kalman filter or weather tracking system these small errors can sometimes reinforce each other at each step, quickly causing the algorithm to spit out nonsense. \n",
"\n",

View File

@ -329,7 +329,7 @@
"\n",
"It has perhaps occurred to you that this sampling process constitutes a solution to our problem. Suppose for every update we generated 500,000 points, passed them through the function, and then computed the mean and variance of the result. This is called a **Monte Carlo** approach, and it used by some Kalman filter designs, such as the **Ensemble filter** and **particle filter**. Sampling requires no specialized knowledge, and does not require a closed form solution. No matter how nonlinear or poorly behaved the function is, as long as we sample with enough sigma points we will build an accurate output distribution.\n",
"\n",
"\"Enough points\" is the rub. The graph above was created with 500,000 sigma points, and the output is still not smooth. What's worse, this is only for 1 dimension. In general, the number of points required increases by the power of the number of dimensions. If you only needed 500 points for 1 dimension, you'd need 500 squared, or 250,000 points for two dimensions, 500 cubed, or 125,000,000 points for three dimensions, and so on. So while this approach does work, it is very computationally expensive. Ensemble filters an particle filters use very clever techniques to significantly reduce this dimensionality, but the computational burdens are still very large. The Unscented Kalman filter uses sigma points but drastically reduces the amount of computation by using a deterministic method to choose the points."
"\"Enough points\" is the rub. The graph above was created with 500,000 sigma points, and the output is still not smooth. What's worse, this is only for 1 dimension. In general, the number of points required increases by the power of the number of dimensions. If you only needed 500 points for 1 dimension, you'd need 500 squared, or 250,000 points for two dimensions, 500 cubed, or 125,000,000 points for three dimensions, and so on. So while this approach does work, it is very computationally expensive. Ensemble filters and particle filters use very clever techniques to significantly reduce this dimensionality, but the computational burdens are still very large. The Unscented Kalman filter uses sigma points but drastically reduces the amount of computation by using a deterministic method to choose the points."
]
},
{
@ -911,7 +911,7 @@
"\n",
"### Weight Computation\n",
"\n",
"This forumation uses one set of weights for the means, and another set for the covariance. The weights for the mean of $\\mathcal{X}_0$ is computed as\n",
"This formulation uses one set of weights for the means, and another set for the covariance. The weights for the mean of $\\mathcal{X}_0$ is computed as\n",
"\n",
"$$W^m_0 = \\frac{\\lambda}{n+\\lambda}$$\n",
"\n",