Team,

Presently I am doing work on multicopter modeling and control. One topic of interest to me is how can the tilt dynamic model of a multicopter be accurately determined from flight data, without disabling the controls or injecting any sort of intrusive signals. It turns out it can be done from normal flight data using a few basic concepts from signal processing. The method is described here. The above plot is the measured pitch dynamic impulse response of my draganflier. The x axis is time. The y axis is the pitch rate impulse response to an impulse command sent to the ESC. There are two curves in the plot. h(t) is the response, computed from flight data. H(t) is an exponentially decaying sinusoid fitted to the measurement. In this case, the Laplace transform of the impulse response is 5/(s*s+4*s+29), which is of exactly the form you would expect to arise from an analysis of fixed pitch control. Basically, in the case of my draganflier, there is about a 0.25 second delay between the time a new tilt rate is commanded to the motors and when quad begins tilting. I have measured a similar delay for the ArduCopter. The cause of this delay is mainly the inertia of the propellers, which delays the response of propeller thrust to change in motor torque, and the inertia of the quad, which delays the tilt rate response of the quad to propeller thrust.

As a check on the accuracy of the method, it is possible to convolve H(t) with control inputs to predict tilt rate. The following is a comparison of measured and predicted pitch rate during a flight of my draganflier.

Don't get too excited about the way the model seems to predict the high frequency features. If you are curious about that, read my report.

From the form of the tilt dynamic model it is possible to determine the form of an optimal feedback controller. It is not a PID controller. But that will be the subject of another report.

Best regards,

Bill

Views: 3608

Tags: dynamics, multicopter

Comment by bgeig on March 4, 2012 at 9:42pm

Bill,

Interesting results. Do you think the inertial response of the airflow as the prop RPM is changed affects the delay? On larger rotorcraft, the time required for rotor inflow to respond to a change in rotor speed or blade angle can be approximated as a first order lag with a time constant ~0.1 sec.

Comment by SaadTiwana on March 5, 2012 at 12:06am

Interesting work. Keep it up!! :) Reading your report now.


Developer
Comment by Andrew Tridgell on March 5, 2012 at 12:15am

Great stuff Bill! I'm really looking forward to what you suggest for the feedback controller.

I also found your comments on the noise interesting. I've been spending a lot of time recently looking at how well DCM as implemented in ArduPlane/ArduCopter deals with noise, which has resulted in some significant changes that we are looking at pushing out soon. I've been modelling it with our SITL simulation of planes and copters running at 1kHz, adding either white noise or noise based on motor speed. I've come to the conclusion that a lot of the control issues we've been seeing in APM are due to buildup of errors in the omegaI matrix in DCM as a result of noise in the accel and gyro data.

Have you looked at how noise propogates in DCM? The sort of noise we want to cope with is fairly large - around 0.5g of noise in accels and around 0.5 radians/s noise on the gyros.

Cheers, Tridge


T3
Comment by William Premerlani on March 5, 2012 at 4:05am

@Brian

Yes, I think that the airflow itself is part of the dynamics. Definitely

@Andrew,

I have looked at "noise" propagation in DCM, and realized that one approach to dealing with the effects of translational and rotational vibration is to treat it as signal, not as noise. As a result, in MatrixPilot we have gone to 8000 samples per second, and we use an "integrate and dump" filter to decimate the sampling rate down to our frame rate. The integration at a high sampling rate prevents the vibration signals from building up errors. For example, MatrixPilotQuad is able to hold yaw to within a couple of degrees for the duration of a 10 minute flight of my draganflier, without needing a magnetometer, all the while my draganflier is vibrating like a paint shaker. In other words, I can hover in place for 10 minutes without touching the yaw control at all, and with only minor inputs to roll and pitch.

In other words, sampling and integrating at 8000 samples/second achieves zero error build up in attitude estimation.

Best regards,

Bill Premerlani


T3
Comment by William Premerlani on March 5, 2012 at 4:20am

Andrew,

A couple more comments about rotational vibration. What I decided to do is to treat rotational vibration as a real signal. So, as a long as I sample and integrate it at a high enough frequency, the result reflects the actual orientation.

The reason I decided to try sampling and integrating at a high rate was the realization that much of the "drift" of the gyros was not really drift, but an accumulation of error from the white noise included in the gyros. A higher sampling rate attenuates the effects of white noise. It also turned out to be a solution to the problem of vibration effects.

Best regards,

Bill

Comment by Wouter van Verre on March 5, 2012 at 5:14am

Hi Bill,

Very interesting work, as always. I think the whole quad community is going to benefit from your research.

Regarding the high sample rates in the MatrixPilot firmware. If I remember correctly sample/hold amplifiers were the limiting factor in the UDB3 boards. Does this mean that using a different A/D converter with even higher sampling rates might return even better results?

Also, I have been wondering about your views on using digital sensors. In particular I wonder how the digital low pass filters they implement would influence the DCM calculations...?

Kind regards,

Wouter

Comment by Kári Davíðsson on March 5, 2012 at 7:27am

Aliasing is hard (almost impossible) to deal with (except by raising the sampling rate).

Do you have any details on the decimation filters you are using?

I guess you are measuring the closed loop response, i.e. with the PID controller active?

Comment by Alex Pabouctisids on March 5, 2012 at 10:48am

Nice work. Did you consider using the system identification tool from matlab (if you have it)?

If you have some raw input - output data i could give it a go myself and see what kind of transfer function i can compute. It doesn't need to be an impulse response, just the recording of general flight should suffice as it usually contains a large enough spectrum, especially at the frequencies you're most interested in.


Developer
Comment by Andrew Tridgell on March 5, 2012 at 3:24pm

Hi Bill,

Thanks for the comments! Getting yaw hold with no compass to within two degrees over 600 seconds is incredible. That implies an extremely low gyro drift rate. For the code I'm working on how I've assumed a maximum drift rate of 0.02 degrees/s/s.

Have you plotted your omegaI components over time to get an estimate of what drift rates you really see?

Here is a plot of omegaI over a 6 minute flight with a small quadcopter and APM:

as you can see, DCM records an apparent drift rate of around 0.005 degrees/s/s, which would make yaw hold without a compass quite impossible.

On APM we're currently sampling the gyros and accels at 1kHz, and doing a simple average to feed DCM. We run the DCM matrix update on ArduPlane at 50Hz and on ArduCopter at around 200Hz.


T3
Comment by William Premerlani on March 5, 2012 at 3:25pm

Team,

Thank you all so much for your thoughtful questions. In no particular order, here are my answers.

Regarding sampling rate, I did some testing with the UDB3 at rates significantly higher than 8,000 samples per cycle. I did not see any improvement in performance, so I settled at 8,000 samples per second. The design of the analog filters on the gyro outputs has an error in the UDB3 (its backwards), so there is no capacitor providing a voltage source for the sample and hold amplifiers. We have fixed on the UDB4, so maybe the UDB4 would be able to go higher. That said, I found the performance of the combination of 8,000 samples per second and "integrate and dump" to be flawless in the face of vibration. As I mentioned in my response to Andrew, MatrixPilotQuad running on a UDB3 or UDB4 has a residual in flight gyro drift rate of less than 0.5 degrees per minute.

Regarding digital gyros, I am skeptical about the way that they do filtering. Theoretical analysis of the way gyros and accelerometers are used in IMUs shows that "integrate and dump" is the right way to go for decimation filtering, and the use of a low pass filter will produce inferior results. I have not tried the digital gyros yet, but when I do I will probably want to use them to send along unfiltered samples, and then do my own filtering. Which leads into my next answer.

The decimation filter that I am using is "integrate and dump". What that means is that between executions of attitude and position computations, the outputs of the accelerometers and gyros are digitally integrated. Samples are taken at 8000 samples per second. Attitude and position are computed 40 times per second. So there are 200 samples that are integrated between computations. Each time the 40 Hz computations are executed, the digital integrators transfer their values to the computations, and then are reset. (Hence the term, "dump", in "integrate and dump".) The reason that this works so well is that the critical downstream computations are integrals. By doing the integration at 8000 samples per second, we are achieving almost the same benefits as if we were doing all of the computations at 8000 Hz. So, "integrate and dump" is a method of achieving a virtual computation rate of 8000 Hz.

Regarding the controller being active during my measurements, yes it was active. I tried turning it off, but then my quad was impossible to fly. However, the controller that I am using is not a PID. (More on that in the future.)

Regarding "impulse response", just to be clear, impulse response is a control theory term meaning the response of a system to an input that is an impulse. Once you have figured out what the impulse response of a system is, you can use it for a lot of things, including determining the Laplace transform of the system, and designing a suitable controller for the system. During my tests I never administered an impulse, but for a linear system, the total input can be thought of as a series of impulses.

Regarding the raw data, here is a link to the spreadsheet that I used to do the computations. If anyone wants to try other methods to compute the pitch impulse response of my draganflier from it have fun. Also, some of you might be interested to see how to use a spreadsheet to do the computations. Here is what is contained on the 4 sheets of the spreadsheet:

Sheet 1 : vector - matrix computations to determine impulse response

Sheet 2 : plot of h(t)

Sheet 3 : raw data

Sheet 4 : curve fitting of h(t)

Your mission, should you accept it, is to compute h(t) from pitch input and pitch output.

Pitch input is labeled pfb, for "pitch feedback". I am using a fly-by-wire system, so pfb is the only input to the differential p

Comment

You need to be a member of DIY Drones to add comments!

Join DIY Drones

© 2014   Created by Chris Anderson.   Powered by

Badges  |  Report an Issue  |  Terms of Service