3
$\begingroup$

Introduction :I am trying to create an EKF for an autonomous vehicle, and i need to model the error of the sensors. (I am a mechanical engineer so my knowledge on electric signals is limited). The noise specifications of the IMU we have are in the following image(The first table is for the accelerometers.):

IMU_specs

Also, the same manual informs me about the architecture of the sensors. It can be seen in the following image:

IMU_overviews

Question How can i convert the data from the datasheets to the noise covariance matrix? I have done my research, and i will present my thinking in the following part of the question. I am seeking a confirmation of my understanding, and if i wrong, i would like to know what i did wrong.

The kalman filter is bases on these equations:

$$ x_{n+1} = Ax_n + Bu_{n+1} + w_n $$ $$ y = Cx_n + v_n $$

where the covariances of $w_n$ (disturbance covariance matrix) is $Q$ and the covariances of $v_n$ (measurement covariance matrix) is $R$.

Assumption 1 : In kalman filters (that i have seen) the disturbances and noise are considered zero mean white noise, so: $$ E\{ w\{i\}^{T}w\{j\} \} = 0 \mbox{ where } i \not = j$$ And thus $ R(\tau) = E\{ w\{i\}^{T}w\{i+\tau\} \} = 0 $ for $\tau \neq 0$, where $E$ is for the expectation. So, from my understanding (if we consider the noise from one sensor uncorrelated with the noise of the other sensors, which is a valid assumption): $$ R = \mbox{diag}(\sigma_{1}^2, \sigma_{2}^2, ... , \sigma_{n}^2 )$$

Assumption 2: The power spectral density of the noise is ($T$ is the sampling time, we consider the 1D case): $$ S_{xx}(f_k) = \frac{ |X(f_k)|^2 }{T} $$ where $X(f_k)$ is the FFT of the original signal $x(kt)$. And then the covariance is actually: $$\sigma^2 = \sum_{-N}^{N} S_{xx}(f_k) $$ Or in the continuous case (ergodic process, that has values in $[0,f_s]$): $$ \begin{align} \sigma^2 &= \int_{0}^{f_s} S_{xx}(f) df \\ \sigma^2 &= \bar{S}_{xx}f_s \end{align}$$

According to this page i could calculate the standard deviation by using the noise density (Velocity Random Walk) with this formula ($ND = 12 \frac{mg}{ \sqrt{Hz} } )$ from the datasheet):

$$ \sigma = ND \sqrt{f_s} $$

So by equating these last two formulas $ND = \sqrt{ \bar{S}_{xx} } = \sqrt{ \frac{1}{f_s}\int_{0}^{f_s} S_{xx}(f) df} $

So the frequency f, depends on my sampling rate, because that would be the frequency limit of my noise power spectrum from an FFT. (Actually, it would be a two sided spectrum with limits $[-f_s/2,f_s/2]$, but when you add the power from both sides, a factor of $2$ appears)

Assumption 3 As you can see from the 2nd picture, the accelerometers calculate some integrals at a rate of 1kH and i think i get the accelerations at that rate (If i cant, i would read values at 0.2kHz, which is still different from the accelerometers sampling rate, and my question still holds). However, the sampling rate is at 4kHz. From the analysis above, i think i should multiply $ND$ with $\sqrt{4kHz}$.

Assumption 4 - Edit From the same page( this page ), it says you can convert $ ^{\circ}/\sqrt{s}$ to $ ^{\circ}\sqrt{Hz} $. So the standard deviation of the gyro is (using the datasheet): $$ \sigma_{gyro} = 0.15 / \sqrt{10kH} $$ (if not 10, we could say 1kHz)

$\endgroup$

1 Answer 1

2
$\begingroup$

Assumption 1 is usually a good assumption: just make the measurement noise covariance matrix diagonal. If all the sensors are the same, then this will just be $\sigma^2 I$ where $I$ is the identity matrix.

Assumption 2 Looks correct, but I've not used that.

Assumption 3 If the EKF is running at 1kHz, I suspect that's the rate you should use.

One thing to note: unless you are very sure your signal model is accurate (matches your physical system well), then it's best not to be too tied to precise (but not necessarily accurate) calculations of what the covariance matrices should be.

The reason is the EKF is an approximation, a linearization of a non-linear system. So, in addition to the "real" noises, you're also going to get second and higher order errors coming from that approximation.

$\endgroup$
1
  • $\begingroup$ As the model is not perfect, i want to rely more on the sensor inputs, and thus calculate as precisely as possible the covariance matrices, and less on the model predicted states.( But i think you "tune" that trough the choice of Q matrix). As for the covariance matrix, how do we generally calculate it to your knowledge, if you haven't used the analysis from my second assumption? $\endgroup$ Commented May 18, 2022 at 15:01

Your Answer

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

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