[Canberrauav] analysis of Sundays crash
Andrew Tridgell tridge at samba.org 
Mon Nov 21 22:07:34 EST 2011 

As many of you know, we crashed the Telemaster on Sunday while doing a
longer distance test at the Sutton field. The plane started losing
altitude after going into AUTO mode, and kept losing altitude until it
hit a tree. Jack is working on repairs, so it may be flying again soon!

We have detailed logs, which I've been analysing and discussing with
some other APM developers. The basic problem was with the way that APM
tries to correct altitude errors when using an airspeed sensor.

If you have a look in Attitude.pde, here:

  http://code.google.com/p/ardupilot-mega/source/browse/ArduPlane/Attitude.pde

and look near line 176 you'll see a function called
calc_nav_pitch(). That function calculates what pitch the plane should
aim for while in AUTO mode. You'll see it uses quite a different
algorithm depending on if an airspeed sensor (pitot tube) is connected.

When you have no airspeed sensor, it sets the nav_pitch based directly
on the altitude_error. So if we have a high altitude_error (which means
we are too low) then it will set a high nav_pitch, thus trying to climb
using the elevator. The degrees of nav_pitch is constrained by a limit
that we had set to 30 degrees.

When you do have an airspeed sensor it uses quite a different
strategy. It sets the nav_pitch based solely on the airspeed_error, not
taking into account how much altitude error you have. The theory behind
this is explained in lots of sites on flight theory, such as this one:

  http://www.av8n.com/how/htm/power.html

The idea is that a plane flies most efficiently if you use throttle to
control altitude, so the main altitude control is in calc_throttle()
starting at line 125 in the same file, and calc_nav_pitch() only plays a
minor role.

We have an airspeed sensor on the Telemaster, and the plane was flying
fast (at about 23 m/s, well above its cruise speed of between 15 and 19
m/s) but far too low (hitting a tree when about 85m below its target
altitude). So what was happening was the calc_throttle() was trying to
correct the altitude error by pushing up the throttle
further. Unfortunately we were already at the configured THR_MAX of 75%,
so it couldn't put in any more throttle. The calc_nav_pitch() algorithm
gave a target pitch of just 3 degrees, which wasn't enough for it to
climb, and so the plane kept slowly dropping.

There are a few solutions to this. One way of looking at it is that we
had the plane trimmed badly. The 3 degrees of nav_pitch should have
caused it to gain altitude (slowly). So maybe we were off by a few
degrees when we did the calibration on the ground.

I think however that it shows a basic problem with the altitude error
strategy with an airspeed sensor enabled. If the throttle is already at
its limits then the strategy of using throttle to control altitude has
reached its limit, and it is time to start using pitch to gain
altitude. If you were flying a plane and noticed that you can't push the
throttle up any more, and you were losing altitude, you would pull back
on the yoke to pitch the nose up. It may not be aerodynamically
efficient, but the alternative is to crash.

So I've proposed a patch (attached below) that smoothly moves between
the airspeed based altitude control and pitch based altitude control
based on how close we are to the throttle limits. When cruising in the
normal throttle range we'll control altitude error via the 'energy'
method, using throttle, but when we get close to the throttle limits we
will start using pitch. I think this will mean the plane will cope with
a much wider range of environments and parameters.

After talking to some of the other diydrones developers I found out that
a number of them have avoided using airspeed sensors because of this
problem, and instead just use GPS speed, so we are not the only ones to
hit this. We can't just use GPS speed for our UAV however, as we need to
be able to cope with high wind. Using GPS speed would mean we would risk
stalling when flying downwind.

I'll discuss this patch and other varients on it more with Doug Weibel
(the lead ArduPlane developer) and see what he suggests. I suspect that
this patch or something like it will go in. 

So why did this hit us yesterday and not in previous flights with the
Telemaster? I think the key is likely to be two factors:

 - I suspect we did the ground calibration the aircraft with a couple of
   degrees of down pitch

 - the strong gusts of wind would have meant the plane flew less
   efficiently (it was rolling a lot), which would have lost lift

Many thanks to everyone who helped on Sunday. We may have crashed, but
it gave us valuable practice, and the subsequent analysis has taught me
a great deal about properly tuning for automatic flight and how some of
the trickier corners of the APM code work. We'll be much better prepared
next time we hit a situation like this.

Cheers, Tridge

[Canberrauav] analysis of Sundays crash
Chris Gough christopher.d.gough at gmail.com 
Tue Nov 22 11:49:31 EST 2011 

Hi Tridge, uavers,

proportionally mixing pitch and energy climbing models based on
throttle setting is cool. "The more throttle we are already using, the
more positive pitch we mix into climb-by-throttle command".

But could this push us over the edges of the flight envelope? Imagine
we are descending but trying to climb (e.g. sinking air) and airspeed
is falling (e.g. tailwind gust). We might need to reduce pitch to keep
flying, whereas if the airspeed was stable then increasing pitch would
be OK. Varying the PID tuning surface with altitude_mix would be a
little hairy :)

>From memory, our crash occurred on the lee side of a hill. Just before
the crash, the plane was flying roughly perpendicular to the wind and
did some wild roll oscillation. Perhaps it traveled obliquely through
a rotor rolling of the back of the hill? This could have thrown it
about, and cause abrupt switching between up and down drafts
("lifting" and "knocking").

Do the barometer and GPS altitude estimates diverge more strongly
between way points 3 and 4 than they did say, between way points 2 and
3 (or just prior the entering the lee of the hill)?

Might sudden lifting/knocking distort the vertial coltrol loop? e.g.
sudden negative derivative term (knock) canceling out proportional
error (don't climb!). Lifting/knocking would essentuially be integral
noise.

Might a sudden change in pressure cause an artifact on the airspeed
sensor? e,g, increasing pressure -> overestimate speed.

Would it be possible/interesting to fuzz-test the control
derivative/altitude during simulation?

Chris Gough


On Mon, Nov 21, 2011 at 10:07 PM, Andrew Tridgell  wrote:
> As many of you know, we crashed the Telemaster on Sunday while doing a
> longer distance test at the Sutton field. The plane started losing
> altitude after going into AUTO mode, and kept losing altitude until it
> hit a tree. Jack is working on repairs, so it may be flying again soon!
>
> We have detailed logs, which I've been analysing and discussing with
> some other APM developers. The basic problem was with the way that APM
> tries to correct altitude errors when using an airspeed sensor.
>
> If you have a look in Attitude.pde, here:
>
>  http://code.google.com/p/ardupilot-mega/source/browse/ArduPlane/Attitude.pde
>
> and look near line 176 you'll see a function called
> calc_nav_pitch(). That function calculates what pitch the plane should
> aim for while in AUTO mode. You'll see it uses quite a different
> algorithm depending on if an airspeed sensor (pitot tube) is connected.
>
> When you have no airspeed sensor, it sets the nav_pitch based directly
> on the altitude_error. So if we have a high altitude_error (which means
> we are too low) then it will set a high nav_pitch, thus trying to climb
> using the elevator. The degrees of nav_pitch is constrained by a limit
> that we had set to 30 degrees.
>
> When you do have an airspeed sensor it uses quite a different
> strategy. It sets the nav_pitch based solely on the airspeed_error, not
> taking into account how much altitude error you have. The theory behind
> this is explained in lots of sites on flight theory, such as this one:
>
>  http://www.av8n.com/how/htm/power.html
>
> The idea is that a plane flies most efficiently if you use throttle to
> control altitude, so the main altitude control is in calc_throttle()
> starting at line 125 in the same file, and calc_nav_pitch() only plays a
> minor role.
>
> We have an airspeed sensor on the Telemaster, and the plane was flying
> fast (at about 23 m/s, well above its cruise speed of between 15 and 19
> m/s) but far too low (hitting a tree when about 85m below its target
> altitude). So what was happening was the calc_throttle() was trying to
> correct the altitude error by pushing up the throttle
> further. Unfortunately we were already at the configured THR_MAX of 75%,
> so it couldn't put in any more throttle. The calc_nav_pitch() algorithm
> gave a target pitch of just 3 degrees, which wasn't enough for it to
> climb, and so the plane kept slowly dropping.
>
> There are a few solutions to this. One way of looking at it is that we
> had the plane trimmed badly. The 3 degrees of nav_pitch should have
> caused it to gain altitude (slowly). So maybe we were off by a few
> degrees when we did the calibration on the ground.
>
> I think however that it shows a basic problem with the altitude error
> strategy with an airspeed sensor enabled. If the throttle is already at
> its limits then the strategy of using throttle to control altitude has
> reached its limit, and it is time to start using pitch to gain
> altitude. If you were flying a plane and noticed that you can't push the
> throttle up any more, and you were losing altitude, you would pull back
> on the yoke to pitch the nose up. It may not be aerodynamically
> efficient, but the alternative is to crash.
>
> So I've proposed a patch (attached below) that smoothly moves between
> the airspeed based altitude control and pitch based altitude control
> based on how close we are to the throttle limits. When cruising in the
> normal throttle range we'll control altitude error via the 'energy'
> method, using throttle, but when we get close to the throttle limits we
> will start using pitch. I think this will mean the plane will cope with
> a much wider range of environments and parameters.
>
> After talking to some of the other diydrones developers I found out that
> a number of them have avoided using airspeed sensors because of this
> problem, and instead just use GPS speed, so we are not the only ones to
> hit this. We can't just use GPS speed for our UAV however, as we need to
> be able to cope with high wind. Using GPS speed would mean we would risk
> stalling when flying downwind.
>
> I'll discuss this patch and other varients on it more with Doug Weibel
> (the lead ArduPlane developer) and see what he suggests. I suspect that
> this patch or something like it will go in.
>
> So why did this hit us yesterday and not in previous flights with the
> Telemaster? I think the key is likely to be two factors:
>
>  - I suspect we did the ground calibration the aircraft with a couple of
>   degrees of down pitch
>
>  - the strong gusts of wind would have meant the plane flew less
>   efficiently (it was rolling a lot), which would have lost lift
>
> Many thanks to everyone who helped on Sunday. We may have crashed, but
> it gave us valuable practice, and the subsequent analysis has taught me
> a great deal about properly tuning for automatic flight and how some of
> the trickier corners of the APM code work. We'll be much better prepared
> next time we hit a situation like this.
>
> Cheers, Tridge
>
>
> _______________________________________________
> Canberrauav mailing list
> Canberrauav at canberrauav.com
> http://www.canberrauav.com/mailman/listinfo/canberrauav
>
>



-- 
.

Copyright 2011 http://canberrauav.org.au/