Jump to content


dschin

Member Since 26 May 2010
Offline Last Active May 07 2012 12:45 AM

Posts I've Made

In Topic: Some advices about current GPS/INS implementation

02 August 2011 - 10:00 PM

View PostKenn Sebesta, on 02 August 2011 - 04:32 AM, said:

For a rebuttal, check out slide 6 of http://signal.hut.fi...lmanfilter.pdf. The system has continuous process noise covariance Q_c, and so should follow this relationship. The discrete process covariance can be approximated by Q_k=Q_c* delT, as is shown in slide 7.

Yes, those equations are correct if we have white noise being put into a continuous time system and we want to approximate the behavior of that system with a discrete time model (i.e. we want P_k ~= P(t), when t=k*T). In this case if we use two different sample times to discretize the system then the covariance, P_k, will have approximately the same time history, modeling the continuous time independent of the sample time. The noise level of the discrete time system is determined by the desire to model the continuous time system.

But that is not what we have in most aided INS systems.  We actually have a continuous time system that is converted to discrete time, and then the noise is added in as a discrete noise sequence, after discretization, as we run the prediction step. I want my Q_k to capture this noise level. The level of the noise is determined by our sensors and our sampling scheme, not by the need to develop a discrete model that approximates a continuous time system.  How we do the averaging/filtering helps determine the noise level, along with the actual sensors.  For, example if all we do is cut the sample frequency in half by taking every other data point (no more filtering or averaging) then the variance of gyros and accels will be the same.  This is the noise level that is truly going into my system in the prediction step.  It is the variance of the discrete sequence  (i.e. Q_k), and it is not changing with sample frequency.  Now, however, if I average those two data points then the variance drops.

In Topic: Some advices about current GPS/INS implementation

25 July 2011 - 10:21 PM

I guess I should jump in here since it is (mostly) my code.  Sorry for not seeing this before now.  Finding time for OpenPilot is challenging sometimes.

View PostKenn Sebesta, on 19 July 2011 - 03:17 PM, said:

View Postodtu_ee, on 19 July 2011 - 02:46 AM, said:

For instance, it is written in insgps13state.c (line 361) that:
 //  Pnew = (I+F*T)*P*(I+F*T)' + T^2*G*Q*G' = T^2[(P/T + F*P)*(I/T + F') + G*Q*G')]
(the successive implementation also uses T^2.). It should be changed to
Pnew = (I+F*T)*P*(I+F*T)' + T*G*Q*G'

Yup, you're right odtu_ee. Peabody, if you've not had the time yet to look into why this is the case, you can convince yourself that the delT^2 implementation is incorrect based off of dimensional analysis when compared with the original continuous-time Kalman Filter. Or just look at the continuous-time covariance prediction and integrate by delT. Both ways lead to a single delT on Q.

Edit: Whoops, I hadn't correctly interpreted Q and G. Classically, Q is the continuous variance, Q_c, whereas here it's presented as the discrete variance, Q_k, which is variant with delT. So if Q as given in the above is implemented as a function of delT, then it is Q_k and the implementation is correct. If, however, Q is set once and for all, then it is in fact Q_c and the implementation is incorrect. Personally, I prefer not to use Q_k as it makes life sloppy if you move to an asynchronous filter.

The T^2 comes from converting the input matrix of the continuous time system to discrete time not from trying to use a psd spec to get a discrete covariance. The Q is a discrete time Q_k, and as Kenn recognizes it is then correct to use the T^2. However, I will argue with Kenn that Q_k does not necessarily change with changing T. If all I do is change the sample rate, without changing any of the front end analog filters on the gyros and accels or change the number of discrete points used in averaging after sampling, then Q_k should not change.  

I know that much of the theory simply states that if we change the sample rate of a noisy signal the discrete time variance changes.  But that is an overly simplified (and often misused) principle.  If I sample white noise with a period T to create a discrete sequence I can find the variance.  Then, I can take every second point from that sequence and find another variance.  Will the new variance be half of the first?  I think it is obvious that the two variances will be the same, since the second data set is just a subsample of the first data set.  However, if instead I cut the sample time in half by averaging every two samples to get a single sample then the variance will be cut in half. Or if when cut the sample time in half I also lower the cuttoff frequency of a front end analog filter (which is like averaging) then I will lower the variance.  The problem is that most the "text books" fail to mention any assumption of increased averaging between samples when lowering the sample rate.

Getting all the discrete conversions when dealing with noise is one of the most complicated things to get right in my experience. So maybe since I have two people with some knowledge of this stuff to check me, I should lay it out better.

Here it is:

I have a dynamic system (the INS), that has a continuous time model and a model converted to discrete time, respectively, as follows:

xdot = F*x + G*u
x(k+1) = A*x(k) + B*u(k)

where from first order approximation

A ~= I+F*T
B ~= G*T

Now consider that u is the gyro and accel measurements, which contain the true accel and angular rate plus noise on each.  So when I "run" the dynamic system I am actually running the discrete time system directly by simulating the continuous system in a computer program. This simulation is the prediction step of the EKF, which I like to call the INS in nav systems. The process noise that is added to this dynamic system comes directly from the noise on my measurements of accel and angular rate.  So I really don't need to consider conversions to discrete time any more if I can directly estimate the discrete covariance, Q_k, of the noise that is feeding into my simulation of the continous time system.

All I need to do is use the discrete time Lyaponov equation to propigate the covariance of x(k), as follows:

P(k+1) = A*P(k)*A' + B*Q_k*B'
      ~= (I+F*T)*P(k)*(I+F*T)' + T^2*G*Q_k*G'

Q_k is estimated directly from the sample variance of the gyros and accel measurements, after filters and averaging, just as they enter the INS.

I am pretty sure we have it implemented correctly, but please do check my logic/math again.


I will have to address some of the other issues in later messages.  They are more subjective :(.