ardupilot icon indicating copy to clipboard operation
ardupilot copied to clipboard

TECS: Fix airspeed control during takeoff

Open Georacer opened this issue 1 year ago • 15 comments

This PR addresses #27147.

The major change in TECS behaviour is that it will no longer force full throttle and a speed weight of 2 during the whole of a TAKEOFF waypoint. Instead, it will limit this behaviour for the part while the airspeed is below the setpoint.

The changes make it so the aircraft does not overspeed during the climb.

It depends on #27125 for easier testing of the changes, by invoking ./Tools/autotest/autotest.py build.Plane test.Plane.CatapultTakeoff or equivalent.

The commits of this PR are purposely split for now, to facilitate comparison and testing of each change. You can find a detailed explanation of the reasoning behind the changes in the attached .pdf. PR_explanation.pdf

Georacer avatar May 27 '24 16:05 Georacer

in our testing we put in an additional check that throttle doesn't go below cruise in takeoff, should we add that in? Do you mean for the whole climb, or just the first segment? For the first segment I don't think it's necessary, the throttle is very high anyways.

For the rest of the climb, it will be equivalent to setting a lower TECS throttle limit. In general, I'd rather not add more ifs than we strictly need. But it might become necessary if I can't fix the soaring case.

Georacer avatar May 28 '24 08:05 Georacer

@tridge in the end I bit the bullet and forced a lower throttle limit of TRIM_THROTTLE for the whole climb, to fix the failing soaring takeoff.

The alternative would be to bring back the artificial altitude demand or change the minimum pitch angle logic.

The updated test results can be found here: PR_explanation.pdf

Of course, I can upload the SITL .bin logs if required.

Georacer avatar May 28 '24 14:05 Georacer

Has this been tested with normal hand launched 1m foamies using defaults (which most users would use) both with and without an airspeed sensor?

Hwurzburg avatar May 29 '24 11:05 Hwurzburg

Has this been tested with normal hand launched 1m foamies using defaults (which most users would use) both with and without an airspeed sensor?

Not specifically. Do you have specific testing steps in mind?

What if I use RealFlight to hand-launch this model, after resetting the TECS parameters?

Georacer avatar May 29 '24 12:05 Georacer

Can't hurt,but I can test on a real plane this week when weather permits

Hwurzburg avatar May 29 '24 13:05 Hwurzburg

Can't hurt,but I can test on a real plane this week when weather permits

Unfortunately I have no real-world flight testing capabilities around here. I'd be much obliged if you did.

Georacer avatar May 29 '24 13:05 Georacer

Has this been tested with normal hand launched 1m foamies using defaults (which most users would use) both with and without an airspeed sensor?

@Hwurzburg I tried with hand-launching the Aeroscout with RealFlight and a 2x2 test matrix:

  • Mode: AUTO, TAKEOFF
  • ARSPD_USE: 0, 1

I used the parameter files found here: https://github.com/ArduPilot/SITL_Models/tree/master/RealFlight/Tridge/Planes/Aeroscout except I deleted all TECS* related lines, so that the defaults will remain.

I also used this short mission in the tests: rf_mission.txt

Here are the logs: logs.zip It flirts with underspeed a bit, as it's not tuned at all, but it didn't fall out of the sky.

Georacer avatar May 29 '24 17:05 Georacer

Okay, I'll change when I'm back from vacation. Do our build options guarantee initialization to the default value, which I guess is false for boolean and zero for numerical?

On Fri, 31 May 2024, 07:02 Andrew Tridgell, @.***> wrote:

@.**** commented on this pull request.

In libraries/AP_TECS/AP_TECS.h https://github.com/ArduPilot/ardupilot/pull/27174#discussion_r1621670510 :

@@ -419,6 +419,9 @@ class AP_TECS { // need to reset on next loop bool _need_reset;

  • // Checks if we reset at the beginning of takeoff.
  • bool _reset_after_takeoff{false};

@Georacer https://github.com/Georacer it also should not be initialised to false - the init just wastes flash space

— Reply to this email directly, view it on GitHub https://github.com/ArduPilot/ardupilot/pull/27174#discussion_r1621670510, or unsubscribe https://github.com/notifications/unsubscribe-auth/AAYBBLHK5W5E6OS5OK65PMTZE7Y35AVCNFSM6AAAAABILPUY2SVHI2DSMVQWIX3LMV43YUDVNRWFEZLROVSXG5CSMV3GSZLXHMZDAOBZHA2TONJWGI . You are receiving this because you were mentioned.Message ID: @.***>

Georacer avatar May 31 '24 12:05 Georacer

Do our build options guarantee initialization to the default value

yes

tridge avatar Jun 01 '24 00:06 tridge

Aeroscout AutoTakeoffs Master (Airspeed Sensor active) Master This PR with Airspeed Sensor withASPD This PR without Airspeed being used withoutARSPD

A bit surprised that no full throttle is kept until LVL_ALT is achived....I had recently fixed MODE TAKEOFF not to switch to TECS until alt reached (full throttle climb) where it had beeb switching to TECS once level alt reached....but this seems to switch even before that is reached... I think full throttle needs to be active until LVL_ALT is reached to get into navigation ASAP....and we will have to fix MODE TAKEOFF again if this merged to revert its behviour also...

Hwurzburg avatar Jun 01 '24 21:06 Hwurzburg

A bit surprised that no full throttle is kept until LVL_ALT is achived....I had recently fixed MODE TAKEOFF not to switch to TECS until alt reached (full throttle climb) where it had beeb switching to TECS once level alt reached....but this seems to switch even before that is reached...

@Hwurzburg, the TAKEOFF flight mode is not within the scope of this PR, only AUTO is. If I negatively affected TAKEOFF, we can examine that separately.

I think full throttle needs to be active until LVL_ALT is reached to get into navigation ASAP....and we will have to fix MODE TAKEOFF again if this merged to revert its behviour also...

The point of this PR is primarily to prevent the aircraft from overspeeding, by intentionally giving TECS back its throttle control during the climb. As I showed above this is beneficial. Do have any objections with it?

Georacer avatar Jun 20 '24 12:06 Georacer

The point of this PR is primarily to prevent the aircraft from overspeeding, by intentionally giving TECS back its throttle control during the climb.

we may need a TECS API called by mode_takeoff.cpp that forces for the next loop full throttle to be used, this would apply below TKOFF_LVL_ALT

tridge avatar Jun 26 '24 07:06 tridge

I must say that I am opposed to

  1. not having the option of using TKOFF_THR_MAX for the entire climb with an airspeed sensor and I think this should be the default. Lest someone have a crash due to poor setup on their first auto takeoff, or want max climb all the time but not want it during navigation
  2. not having TKOFF_THR_MAX always until at least TKOFF_LVL_ALT is reached

Hwurzburg avatar Jun 26 '24 11:06 Hwurzburg

I must say that I am opposed to

1. not having the option of using TKOFF_THR_MAX for the entire climb with an airspeed sensor and I think this should be the default. Lest someone have a crash due to poor setup on their first auto takeoff, or want max climb all the time but not want it during navigation

2. not having TKOFF_THR_MAX **always** until at least TKOFF_LVL_ALT is reached

Hey @Hwurzburg !

So for today, my intention was to make it so in TAKEOFF mode,

  1. the throttle would be kept at the maximum allowable while below TKOFF_LVL_ALT and then
  2. past that, TECS would be allowed to fly as normal. However, as the min pitch is locked at TKOFF_LVL_PITCH for the whole climb, this interferes with TECS' controls and results in underspeed. I believe that is the old (read: current) behaviour as well. This is a graph produced (more or less) with the new test TakeoffMinThrottle on the existing master. image

It's quite complex to fix this in TAKEOFF mode, as that mode interferes with the FlightStage quite a bit, making it hard for TECS to understand what's going on. If you want, we can discuss this live.

In any case, I have now adjusted this PR it so the throttle will be kept at max until TKOFF_LVL_ALT, which is the old behaviour. Up until TKOFF_ALT, TECS will regulate throttle as it sees fit. This holds for both TAKEOFF and AUTO modes.

A graph of how TAKEOFF mode works with this PR: image

And a graph of how AUTO mode works with this PR, with TKOFF_LVL_ALT=30: image

Are you satisfied with these changes?

Georacer avatar Jun 26 '24 17:06 Georacer

The point of this PR is primarily to prevent the aircraft from overspeeding, by intentionally giving TECS back its throttle control during the climb.

we may need a TECS API called by mode_takeoff.cpp that forces for the next loop full throttle to be used, this would apply below TKOFF_LVL_ALT

@tridge I've avoided doing that for now, with the latest changes. I've chosen another way to let TECS know of TKOFF_LVL_ALT, see ArduPlane.cpp. If that's too bold, let me know.

Georacer avatar Jun 26 '24 17:06 Georacer

I've made the following changes after today's Dev Call:

  1. I've removed the takeoff-first-stage height check from within TECS. TAKEOFF mode will control it by itself...
  2. via the new TECS::set_min_throttle() method.

As a recap, here are the specs I'm trying to hit:

1 In AUTO takeoff 1.1 before reaching min airspeed, use max throttle. 1.2 after reaching min airspeed, do airspeed control as normal. 2 In TAKEOFF mode 2.1 before reaching min airspeed, use max throttle (fallback to 1.1) 2.2 before reaching TKOFF_LVL_ALT, use max throttle.

Here are the comparison between master and this branch, using the two new autotests I've created.

Before, AUTO takeoff waypoint. Note how the throttle is at max for the whole climb and the vehicle overspeeds. image

After, AUTO takeoff waypoint. TECS now keeps max throttle until minimum airspeed is reached, and then controls throttle as normal. image

Before, TAKEOFF mode, with

  • TKOFF_LVL_ALT=30
  • TKOFF_THR_MAX=90 TECS switches to FlightStage:Normal as soon as TKOFF_LVL_ALT is hit. image

After, TAKEOFF mode. The functional behaviour is unchanged. image

Georacer avatar Jul 03 '24 14:07 Georacer

how about the same plots without an airspeed sensor?

Hwurzburg avatar Jul 03 '24 14:07 Hwurzburg

how about the same plots without an airspeed sensor?

Right, thanks for the reminder.

AUTO, with the following same additional parameters as the with airspeed test, but also with ARSPD_USE=0 "ARSPD_USE": 0.0, "TKOFF_LVL_ALT": 30.0, "TKOFF_THR_MINACC": 3.0, "TECS_PITCH_MAX": 35.0, "PTCH_LIM_MAX_DEG": 35.0

Before: image

After: image

TAKEOFF, same as the previous with airspeed-setup, but again, adding ARSPD_USE=0. Before: image

After: image

I'll spin-up Windows to do a TAKEOFF hand-launch on RealFlight, for good measure.

Georacer avatar Jul 03 '24 16:07 Georacer

I've updated the original PR text, since there has been a significant rework in the last two weeks. Please read that first.

To address the review comments that were pending: 1. Are TAKEOFF and AUTO modes' behaviour identical? It wasn't 100% before, should be identical now. The only caveat is that mode AUTO doesn't have direct access to TKOFF_LVL_ALT and hence can't do full throttle below it.

2. Taking into account takeoffs that happen mid-mission, from a deep valley. No change in the AUTO or TAKEOFF altitude logic has been made, so it shouldn't make things worse. Any TECS changes only affect throttle logic, not altitude thresholds and targets.

3. How about reverse-throttle setups? No new throttle limits have been added, most notably in servos.cpp except for FlightStage::TAKEOFF, where reverse throttle isn't used.

4. What about when ARSPD_USE=0? It is deemed that in lack of airspeed measurement, we can't rely on synthetic airspeed during takeoff. So max throttle will be used throughout the climb.

5. Do we need to increase TKOFF_LVL_ALT? No, since the default behaviour for most users who have TKOFF_MODE=0 will be max throttle for the whole climb. Individual users can tailor to their own needs.

New behaviour:

  1. The new parameters TKOFF_MODE and TKOFF_THR_MIN are introduced.

  2. In the current master with a TAKEOFF mode, the throttle was allowed to drop when climbing past LVL_ALT. Now this is only allowed when ARSPD_USE=1 and TKOFF_MODE=1.

  3. In the current master with an AUTO takeoff and ARSPD_USE=0, the throttle was allowed to recede past TKOFF_THR_MAX_T. Now it is always at max.

  4. In the current master TKOFF_THR_MAX_T applies only when ARSPD_USE=0. Now it applies always. This is to simplify the TKOFF* parameters.

  5. Increased TKOFF_LVL_ALT from 5m to 10m. At the request of Henry.

Georacer avatar Jul 23 '24 12:07 Georacer

sorry wont be able test fly...did a quick sim with no airspeed sensor and defaults...master drops throttle after tkoff_lvl_alt is reached (5m)...but this keeps it maxed until over 2x that alt....why?

Hwurzburg avatar Jul 23 '24 13:07 Hwurzburg

sorry wont be able test fly...did a quick sim with no airspeed sensor and defaults...master drops throttle after tkoff_lvl_alt is reached (5m)...but this keeps it maxed until over 2x that alt....why?

This is intentional (as written above), in order to guarantee that the plane can climb without stalling up until TKOFF_LVL_ALT while fixed at TKOFF_LVL_PITCH or higher. Master doesn't do a good job maintaining actual airspeed in this case.

If one installs an airspeed sensor and is confident about their tuning, they can set TKOFF_MODE=1 and it will fly with normal TECS past TKOFF_LVL_ALT.

Georacer avatar Jul 23 '24 13:07 Georacer

when does thr drop without aspd sensore if not after TKOFF_LVL_ALT?

edit: just read your comment....will recheck my sim..yep its okay my only concern is that AUTO max perf climb for some period cannot be obtained...there should be some way to access the TKOF_LVL_ALT param from mode AUTO

Hwurzburg avatar Jul 23 '24 14:07 Hwurzburg

when does thr drop without aspd sensore if not after TKOFF_LVL_ALT?

edit: just read your comment....will recheck my sim..yep its okay my only concern is that AUTO max perf climb for some period cannot be obtained...there should be some way to access the TKOF_LVL_ALT param from mode AUTO

I'm not sure I understand your concern. Is it that while doing an AUTO takeoff the thruster shouldn't be wide open for the whole climb? If ARSPD_MODE=0, then one can set a lower altitude in the takeoff waypoint. If ARSPD_MODE=1, then TKOFF_MODE=1 can be set, where there will be normal throttle control after TKOFF_THR_MAX_T.

Georacer avatar Jul 23 '24 15:07 Georacer