1
$\begingroup$

I'm currently attempting to apply a Kalman filter to track the angular position, velocity, and acceleration of a bike wheel, and I'm having a lot of trouble, so I want to check if I'm even applying the right tool for the job. As you will see, this is not a "classical" Kalman implementation, and I want to check if I can still use it.

I have a wheel with n reed switches evenly spaced around the circumference of the wheel. The way that I have the filter set up is that every time one of the reed switches is triggered by a magnet sitting on the bike's fork, a new measurement is fed to the filter that has the position and velocity (z = [x_prev + wheel_circumference/n ; wheel_circumference/(n*dt)] where x_prev is the previous position, wheel_circumference is the circumference of the bike wheel, and dt is the time since the last measurement). (I have tried this system using only position measurements, and I am still having trouble.)

Unlike the classic application of the Kalman filter, the measurements in this system occur periodically in position, not in time, i.e. the sensor(s) sends a measurement to the filter iff the wheel's position reaches a certain position. Compared to a traditional sensor, this implies a heavy correlation between position, velocity, and inter-measurement period. Does this correlation negatively affect the Kalman filter?

$\endgroup$

1 Answer 1

2
$\begingroup$

Yes, sorta kinda. Basically, if you can model your system accurately and the resulting model fits the Kalman filter paradigm, then yes.

However, I think it's a mistake to give the filter position and velocity -- were I doing this, I'd just give it the wheel position and let the Kalman filter determine the velocity -- which it will do well to the extent that your model matches the actual plant.

If it'll work at all, it'll be because you take the typical Kalman system model, $\mathbf{x}_k = \mathbf{F}_k \mathbf{x}_{k-1} + \mathbf{B u}_k + \mathbf{w}_k$, and you (probably, unless you have some prior idea of the acceleration being applied) let $\mathbf{B} = \mathbf{0}$, let $\mathbf{w}_k$ reflect your maximum expected acceleration, and let $k$ be the triggering instance.

The first fly in this ointment is that you have to calculate $\mathbf{F}_k$ and $\mathbf{w}_k$ according to the amount of time elapsed since the last trigger instant. So for $\mathbf{x} = \left [ \begin{matrix} \theta & \omega \end{matrix} \right ]^T$, where $\theta$ is angular position and $\omega$ is angular velocity, you'd get something like $$\mathbf{F}_k = \left [ \begin{matrix} 1 & t \\ 0 & 1 \end{matrix}\right ]$$ and $$\mathbf{w}_k = \left [ \begin{matrix} t^2 & t \\ t & 1 \end{matrix}\right ] \sigma_\alpha^2$$ where $\sigma_\alpha$ is your expected variation in acceleration.

(Note that I'm not giving the derivation of $\mathbf{w}_k$, for which I only sorta-kinda-apologize -- it's tedious for me to translate my hen-scratches to properly formatted math, but it'll be good for you to derive it yourself. Start with the definition of the Kalman-Bucy filter and grind through the math to find $\mathbf{P}(t)$ for a constant $\mathbf{w}(t)$ -- the above expression for the effective sampled-time $\mathbf{w}_k$ should drop out).

Note that the second fly in the ointment is that as the speed of the wheel drops the effect of the acceleration uncertainty ($\sigma_\alpha$, above) will get bigger and bigger compared to the position change from sample to sample. At the point where the likelihood of overrunning the sample gets significant, you can't really use a "pure" Kalman filter anymore -- logically, this is because if you haven't triggered a pulse, then you know darned well that your position and velocity excursion are limited, but there's no way to effectively communicate that to a pure Kalman application.

If you need to track a really slow wheel, then you need to come up with some other, nonlinear, state estimator.

PART II

On reflection, I thought of a possibly-better way. It's still not the best way, because you're jamming a nonlinear system with non-Gaussian uncertainty into a model of a linear system with Gaussian noise -- but it has the advantage both of being conceptually simpler, and of working down to zero speed.

The system model that you use to build a Kalman filter doesn't have to be time-invariant. So model the system as $$\begin{align} \mathbf{x}_k = \mathbf{F} \mathbf{x}_{k-1} + \mathbf{B u}_k + \mathbf{w} \\ \mathbf{y}_k = \mathbf{H} \mathbf{x}_k + \mathbf{v}_k \end{align}$$

Note that $\mathbf{v}_k$ is modeled as time-varying. In truth, the system is nonlinear (you get a pulse at specific values of $\theta$), but we'll just pretend.

Run the Kalman at a constant rate in time, with $\mathbf{F}$, $\mathbf{B}$, and $\mathbf{w}$ $\mathbf{H} = \left [ \begin{matrix} 1 & 0 \end{matrix} \right ]$ all constant.

But for each sample where a pulse is triggered, set $\mathbf{y}$ equal to the known position of the wheel, and $\mathbf{v}_k$ small, to reflect that you darned well know where the wheel is at that moment (size $\mathbf{v}$ to reflect any uncertainties in position due to mounting or irregular triggering or whatever).

For each sample where a pulse is not triggered, set $\mathbf{v}_k$ large, to reflect the fact that you don't know where between the triggers the wheel may be. I'd start with $\mathbf{v}_k = \left( 3 \theta_0 \right)^2$, with $\theta_0$ equal to the spacing between trigger points -- and note that the multiply by three is coming directly out of my ear, so feel free to experiment with it. Set $\mathbf{y}$ equal exactly halfway between the last known position of the wheel and the expected next position of the wheel (I'm assuming you know the wheel direction).

The net effect of this should be that if the wheel is turning fairly quickly the filter will have a darned good idea of the position and velocity, with "coasting" between readings. If the wheel is turning slowly, it should coast OK if it's going at a constant rate, it should update at least fairly well if it speeds up, and if it slows down or stops, the fact that you're telling the Kalman filter that it's between positions "somewhere" should cause the Kalman's velocity estimate to slowly decay to zero (which is your best guess, intuitively), while the position estimate slowly settles on halfway between triggers (which again, is intuitively your best guess).

$\endgroup$

Your Answer

By clicking “Post Your Answer”, you agree to our terms of service and acknowledge that you have read and understand our privacy policy and code of conduct.

Not the answer you're looking for? Browse other questions tagged or ask your own question.