paparazzi-devel
[Top][All Lists]
Advanced

[Date Prev][Date Next][Thread Prev][Thread Next][Date Index][Thread Index]

Re: [Paparazzi-devel] IMU's


From: Christophe De Wagter
Subject: Re: [Paparazzi-devel] IMU's
Date: Thu, 1 Sep 2011 17:06:20 +0200

Dear Heinrich,

In your last email you ask why many projects try to boost the frequency of the measuring and control loop so much. Here are a few observations: higher sampling and even control rates help because:

1) they help to reduce control loop latencies (phase margin) [especially when running several parallel loops that are not synced]
2) they help to improve measurement resolutions (emi / vibrations / can be averaged out by oversampling)
3) they greatly help because at higher measurement rates you need less analog filtering. (when you off coarse comply with shannon theorem: sampling freq >= 2x max signal)
         - analog filtering gives extra delays AND does not preserve integration: the less analog filtering the better:
         - integral of a signal is not equal to the integral of a RC low-pass filtered signal  (this is why e.g. ITG3200 uses 1000Hz even when you ask 10Hz output and it has high order filtering with better integral preservation)

4) control performance (closed loop bode plot) of your total system is simply higher at higher control loop rates. [perturbations are rejected faster and commands followed faster]
5) when integrating gyro's smaller time steps reduce digital integration errors in case of fast dynamics. (also related to low-pass filtering)

In the case of power consuming or fragile actuators it is sometimes better to use lower loop rates... in almost any other case faster is better, which is why so many projects increase there rates. 

Please note: this does not mean that lower control rates are not possible so I can imagine your quad flies "perfectly" at lower rates. But you did not mention its weight for instance. A 300gram 30cm quadrotor will not fly well at 50Hz in turbulence while a 1kg 1m wide quad can fly well indoor with 20Hz feedback. If you want to make a quadrotor that plays the piano, so it can change its position at 1 Hz (which is even slow), then you need 4Hz velocity performance, 16Hz attitude performance and 64Hz rate performance or in other words: the attitude should be easily capable to follow a 16Hz sinus command in closed loop with perturbations or 64Hz rate command. Therefore you need a control loop of at least and preferably much more than 256Hz in an ideal situation. 

Does that help in answering you questions about high rates?

-Christophe 



On Wed, Aug 10, 2011 at 12:20 PM, Prof. Dr.-Ing. Heinrich Warmers <address@hidden> wrote:
Hi Chirstophe,
i agree with yours comments.

We used  the true airspeed sensor, an have be flown up to  a wind of 15m/s.
The delta flow up to 28m/s. Is this a low speed?
We use the DCM rate of 25 Hz the same as the feedback loops.
On HD videos taken  from a camera on the aircraft we were surprised  that the fly was verry smooth.
We saw no ozillations. We saw ozillations, when we used a low roll angle 40° border.
After setting this value to 80°
the behavior was ok and the aircaft flow tunrs wiht a 20 m radius.
 
Fore the Implementation of the DCM code  there are 2  main points.
1. Correction to hold the orthogonality  of the DCM matrix in every calculation step
2. Correction of the attitude also when flying circles
The run time of each step is less than 1.5 ms for floating point calculation.
Most of the time is spend in calculation of the  transcendental  angle functions.
This can be speed up by using tables as Paparazzi does for fix point calculations.
Since the filter has a  complementary filter structure, you can all ways find situations in witch the filter fails.
But this is also true  for full kalman filters.
My idea to have a correct attitude information is to use different ranges of the accelerator sensors.
We have situations in which the 10 bit  resulution  of the adxl355 or adxl354 is bad.
10 bit of a +-3g sensor give a pure angle  error of  +-0.3°.
This seems to be to  high even for quadrocopters.
When  we fly wiht poylon electric aricraft we have acellerations in the range of 10g.
The problem can be solved by usenig 2 sensors (One full range 2g, and one full range 16g).


Another point to high speed calculation for quadrocopters.
Most quadrocopters use the gyro signal direct (without building a difference ) to get stability, called back stepping.
For this a high rate ( 50 Hz) is necessary.
The main point for high frequencies is to deal with  Shannon theorem even the bandwidth is to high.
The motors generate vibrations in the range of 200..2000 Hz. These frequencies are mixed in the gyro signal.
I measured  this signals has a amplitude up to  0.3 of the maximum rate signal.
Another point is the calculation of the non linearity. Same algorithms need very small delta angle to get the the fix point  of the solution.
My own quadocopter fly with a feedback frequency of 20 Hz.
and a gyro signal rate of 100Hz.. Another club members use 50 Hz on a AVR (quads- and three copters 20cm diameter), both without problems.
So i do not  understand why  many projects (ASTEC, Paparazzi, UAVP, Openpilot etc.)  deal with very high rates.

Regards

Heinrich

Christophe De Wagter schrieb:
About the discussions of AHRS filters: 

DCM or quaternions or euler angles are all fully equivalent notations for attitude and can be converted from any notation to any other. The advantage of euler is its intuitive (for small angles) interpretation, its disadvantage is the non-linearity at 90 deg pitch, the advantage of quaternions is the reduced memory size (e.g. when used in a full kalman filter it is better to add 4 states than 6/9 states). The DCM attitude notation is needed in all attitude cases at least as an intermediate step to convert vectors and is used in all cases (euler->DCM = [cos.cos sin.cos ....] and quaternion->DCM= [q0*q1/2, q1*q3/2, ..].

Now indeed without ground-speed information extremely large errors will occur. This can be provided with (slow and delayed) GPS or approximated with an airspeed sensor. This secretly assumes that the plane is pointing in the direction of motion and therefore is only valid for fixedwing. All fixedwing attitude algorithms use this: that is DIY'DCM based <subsystem name="ahrs" type="dcm_float"/> as well as <subsystem name="ahrs" type="ic"/> as well as textbook extended kalman filters. The difference only lies in filter gains and computational power: e.g. the IC (integer complementary) filter does the same as DCM but with 30 times less computational effort for the autopilot (but still needs some fixedwing integration update).

However: all the above mentioned filters do not have a 3D velocity and change in velocity feedback making them not useful for helicopters and give trouble when applying very long longitudinal accelerations (large airspeeds). The 3D speed feedback is possible and quite easy to implement but makes the filter much less stable, which is why this is not applied as a default. 

So Hector Garcia certainly has a point about the performance but as dr Warmers says in practice it will work nicely on slow fixedwing aircraft with not too much wind (much defined as in: constantly clearly blown away from its normal trajectory with visible yaw and pitch oscillations).

Sincerely

-Christophe 



On Wed, Aug 10, 2011 at 8:29 AM, Christophe De Wagter <address@hidden> wrote:
Work is on its way to include Magnetometer in order to get the auto-takeoff right (as it does not work so well yet since the filter needs a bit of time to get the heading right).

Please note that http://www.sparkfun.com/products/10252 is not compatible at this moment as the driver needs to be changed a bit for the talk-through-i2c. It was already made and will hopefully be added to the master soon.

-Christophe 



On Wed, Aug 10, 2011 at 5:34 AM, David Conger <address@hidden> wrote:
FWIW: This one: http://www.sparkfun.com/products/10121 also works since fixed-wing doesn't use MAG.
-David
On Aug 9, 2011, at 3:00 AM, address@hidden wrote:

> Hi Guys,
>
> i m also flying a tiny with IMU (TWOG+Aspirin)  didn t had any problems with the DCM code so far
> it really performs quite good, at least in slow planes like the twinstar.
> if someone want s to use the aspirin wit a tiny/twog there have to be soldered three little wires on the back of the standart carrier board to change it to i2c - not a problem
> i have also seen the sensor stick from sparcfun http://www.sparkfun.com/products/10724
> with the dcm code and it worked right out of the box, just check that the sensor orientation is configured correctly
> have a nice week everyone
>
> Tobi
> ___________________________________________________________
> Schon gehört? WEB.DE hat einen genialen Phishing-Filter in die
> Toolbar eingebaut! http://produkte.web.de/go/toolbar
>
> _______________________________________________
> Paparazzi-devel mailing list
> address@hidden
> https://lists.nongnu.org/mailman/listinfo/paparazzi-devel


_______________________________________________
Paparazzi-devel mailing list
address@hidden
https://lists.nongnu.org/mailman/listinfo/paparazzi-devel



_______________________________________________ Paparazzi-devel mailing list address@hidden https://lists.nongnu.org/mailman/listinfo/paparazzi-devel

_______________________________________________
Paparazzi-devel mailing list
address@hidden
https://lists.nongnu.org/mailman/listinfo/paparazzi-devel



reply via email to

[Prev in Thread] Current Thread [Next in Thread]