This forum uses cookies
This forum makes use of cookies to store your login information if you are registered, and your last visit if you are not. Cookies are small text documents stored on your computer; the cookies set by this forum can only be used on this website and pose no security risk. Cookies on this forum also track the specific topics you have read and when you last read them. Please confirm whether you accept or reject these cookies being set.

A cookie will be stored in your browser regardless of choice to prevent you being asked this question again. You will be able to change your cookie settings at any time using the link in the footer.

Thread Rating:
  • 0 Vote(s) - 0 Average
  • 1
  • 2
  • 3
  • 4
  • 5
Use of IMU in pypilot
#8
(2024-09-17, 12:58 AM)mgrouch Wrote: accelerometer bias is easy to estimate in Kalman method for a boat. 
To be clear, it uses the same formula (least squares) to estimate accel and compass bias as the kalman filter, except I have memory of points all over the sphere so the result is correct. You cannot find a reliable solution to a non-linear fit like this using an extended kalman filter.. I have tried.

Think about this: If the boat rolls and pitches around a bit in theory it is possible to fit a curve to the points, but in practice, if you think about fitting a circle or sphere to points that are almost all only on one part of it, slight noise can give much larger or smaller circles with different bias. You need a point on the opposite side of the circle which is like having the boat flipped over.

It is possible to use the gyros and/or compass sensors to help find the accelerometer bias and maybe this is what you mean, but the gyros have more errors, such as scale and non-linearity. This is a problem. The most stable and reliable method to find accelerometer bias I have found is to take "still points" by averaging the sensors in different orientations. It does work, and avoids compounding errors from other sensors by using only the accelerometers to compensate themselves. It is possible to get more accuracy by using nonlinear fits, but not really important for the autopilot. The accelerometer bias is most stable of all the sensors as well.

Quote:On a boat average acceleration is g. Most of AHRS Kalman papers are for drones and not for a boat
so they can’t take that into account. It’s a very strong condition. Might bring much better results for 
a boat oriented Kalman filter. 

Kalman filter doesn’t really require much memory. It’s few state vectors and transition matrices. 
They are sparse and often multiplied by blocks. 

It would converge where the model tells it to converge.
I have played with kalman filters maybe more than you realize. What you are suggesting works in theory but in practice can diverge. There are ways to prevent this, but basically the reason is the kalman filter has no "memory" besides the covarience matrix and state. This means that it really has no idea what the sensors would read if the boat rotated 180 until it actually does. This means it cannot compensate bias is a reliable way.

What you are right about is the kalman filter could more quickly converge to gyro bias, by estimating them as additional states in the filter. As I mentioned I had always intended to do this, but never got to it, and the dynamics on a boat seem to make it work ok by a simple lowpass, it just takes a few minutes, especially initially as the bias is unknown. The bias drifts over time, but as long as this drift is slower than the lowpass filter it does work, and on a boat the rate of turn is never really fast. I am assuming high speed spinning and maneuvers like a drone could cause the gyro bias to change faster, but I am not sure. What do you think?

I really think the problems you have that no one else reports is because you are using different sensors from everyone else. Maybe your sensors use magneto resistors, or maybe the gyros just are not as stable. Maybe the driver for your sensors has a bug in it. RTIMULib2 had multiple bugs for reading the 9255, and I fixed them. You can compare my fork to others, and without these changes the sensors would do crazy things.

I then wrote the driver for the icm20948 and really tested it carefully. I did not do this work for all of the drivers so the sensors you are using might always cause problems unless you fix rtimulib2, and this would not surprise me.
Reply


Messages In This Thread
Use of IMU in pypilot - by mgrouch - 2024-09-13, 09:52 PM
RE: Use of IMU in pypilot - by seandepagnier - 2024-09-16, 03:20 AM
RE: Use of IMU in pypilot - by mgrouch - 2024-09-16, 03:50 PM
RE: Use of IMU in pypilot - by seandepagnier - 2024-09-16, 04:21 PM
RE: Use of IMU in pypilot - by mgrouch - 2024-09-17, 12:58 AM
RE: Use of IMU in pypilot - by seandepagnier - 2024-09-17, 03:06 PM
RE: Use of IMU in pypilot - by mgrouch - 2024-09-17, 03:22 PM
RE: Use of IMU in pypilot - by mgrouch - 2024-09-16, 04:45 PM
RE: Use of IMU in pypilot - by seandepagnier - 2024-09-19, 10:41 PM

Forum Jump:


Users browsing this thread: 1 Guest(s)