Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

TECS: Fix airspeed control during takeoff #27174

Merged
merged 6 commits into from
Jul 29, 2024

Conversation

Georacer
Copy link
Contributor

@Georacer Georacer commented May 27, 2024

This PR addresses #27147 and #27211.

It fixes a lot of bugs currently lodged in TECS during a takeoff, both in TAKEOFF and AUTO modes. The major one was that TECS was operating in reset mode during all of FlightStage::TAKEOFF.

It refactors the throttle limits system for Plane so that: servo.cpp is the primary place where throttle limits (upper and lower) are imposed. mode_takeoff.cpp will also impose throttle limits according to its functionality description. AP_TECS.cpp will take those limits into account, also for the no-airspeed case, which was missed previously.
This has the benefit that TECS doesn't need to incorporate the logic for the various throttle limits decisions.

Logging of the throttle limits that TECS uses is added, in place of duplicate pitch limit logging.

Finally, it introduces TKOFF_MODE and TKOFF_THR_MIN. By default TKOFF_MODE makes it so that all takeoff climbs are done in max throttle (THR_MAX or TKOFF_THR_MAX).
When TKOFF_MODE=1 the throttle range past TKOFF_LVL_ALT can very between min and max.
ardupilot-Takeoff_Mode_0
ardupilot-Takeoff_Mode_1

TKOFF_THR_MIN is also taken into account in quadplane transitions.

A lot of tests have been added to expose the new functionality.


Old PR text:

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

Copy link
Contributor

@tridge tridge left a comment

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

in our testing we put in an additional check that throttle doesn't go below cruise in takeoff, should we add that in?

libraries/AP_TECS/AP_TECS.cpp Outdated Show resolved Hide resolved
Tools/autotest/arduplane.py Outdated Show resolved Hide resolved
@Georacer
Copy link
Contributor Author

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 Georacer force-pushed the catapult_takeoff_fix branch from 83e51c3 to 04b6983 Compare May 28, 2024 14:13
@Georacer
Copy link
Contributor Author

@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.

@tridge tridge requested a review from priseborough May 28, 2024 21:25
@tridge tridge force-pushed the catapult_takeoff_fix branch from 04b6983 to 1a782b7 Compare May 29, 2024 07:09
@tridge tridge force-pushed the catapult_takeoff_fix branch from 1a782b7 to dfb8ede Compare May 29, 2024 07:22
@Hwurzburg
Copy link
Collaborator

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

@Georacer
Copy link
Contributor Author

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?

@Hwurzburg
Copy link
Collaborator

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

@Georacer
Copy link
Contributor Author

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
Copy link
Contributor Author

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
Copy link
Contributor Author

Georacer commented May 31, 2024 via email

@tridge
Copy link
Contributor

tridge commented Jun 1, 2024

Do our build options guarantee initialization to the default value

yes

@Hwurzburg
Copy link
Collaborator

Hwurzburg commented Jun 1, 2024

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...

@Georacer
Copy link
Contributor Author

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?

@tridge
Copy link
Contributor

tridge commented Jun 26, 2024

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

@Hwurzburg
Copy link
Collaborator

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

@Georacer
Copy link
Contributor Author

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 Georacer force-pushed the catapult_takeoff_fix branch from fa7f6d5 to bc635b3 Compare June 26, 2024 17:50
@Georacer
Copy link
Contributor Author

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 Georacer force-pushed the catapult_takeoff_fix branch from f5b27d6 to 1462fbe Compare July 23, 2024 08:00
@Georacer
Copy link
Contributor Author

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 Georacer added WikiNeeded needs wiki update DevCallEU labels Jul 23, 2024
Autotests for takeoffs have been added for Plane, covering AUTO and
TAKEOFF mode takeoffs.

An auxiliary `set_servo` method has been added to `vehicle_test_suite.py`.
@Georacer Georacer force-pushed the catapult_takeoff_fix branch from 1462fbe to 57f7b29 Compare July 23, 2024 12:51
@Hwurzburg
Copy link
Collaborator

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?

@Georacer
Copy link
Contributor Author

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.

@Hwurzburg
Copy link
Collaborator

Hwurzburg commented Jul 23, 2024

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

@Georacer
Copy link
Contributor Author

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.

const uint32_t dt = now - _takeoff_start_ms;
if (dt*0.001 < aparm.takeoff_throttle_max_t) {
_THRminf = _THRmaxf;
} else {
Copy link
Collaborator

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

what is this????

Copy link
Contributor Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

This particular if-statement is the implementation of TKOFF_THR_MAX_T: It ensures throttle is at max for the first TKOFF_THR_MAX_T seconds.

I didn't create it; I moved it from _update_throttle_without_airspeed further above to make it common with both with- and without-airspeed measurement cases. Thus simplifying the default takeoff logic.

Georacer added 2 commits July 23, 2024 18:19
These concern the TAKEOFF flight stage and address ArduPilot#27147.

* Logging metadata fixes
* Disabled continuous TECS reset during takeoff
* Fixed bug in reached_speed_takeoff calculation
* Limited SPDWEIGHT=2 to only first part of takeoff climb
* _post_TO_hgt_offset set to constant
* Takeoff I-gain now defaults to 0 and is used
* Use at least TRIM_THROTTLE during the climb
* Updated description of TECS_TKOFF_IGAIN with new behaviour
* Forced max throttle while below TKOFF_LVL_ALT
* Added throttle constraints in no-airspeed mode

Additionally, set_min_throttle() has been created, that allows one to
set the minimum TECS throttle for the next update_pitch_throttle() loop.
Additionally, the throttle limits system has been reworked. TECS will
receive external throttle limits from Plane and will always take them
into account and respect them.
This is a rework so that servos.cpp is responsible for setting the
throttle limits under more circumstances and always notifies TECS when
it does so.

Additionally, the TAKEOFF mode has been improved with a new parameters
TKOFF_MODE and TKOFF_THR_MIN that extend the throttle behaviour.
@Georacer Georacer force-pushed the catapult_takeoff_fix branch from 57f7b29 to c1d113f Compare July 23, 2024 16:19
Copy link
Contributor

@tridge tridge left a comment

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

with the change to use TKOFF_OPTIONS I'm happy for this to go in
many thanks to @Hwurzburg for the careful testing!!

ASCALAR(takeoff_throttle_min, "TKOFF_THR_MIN", 60),

// @Param: TKOFF_MODE
// @DisplayName: Takeoff mode
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

add TKOFF_OPTIONS, with first bit being this option

@Georacer Georacer force-pushed the catapult_takeoff_fix branch from 6e3cb18 to 04ec2b9 Compare July 25, 2024 20:37
@priseborough priseborough self-requested a review July 27, 2024 08:43
@tridge tridge merged commit b5c91a1 into ArduPilot:master Jul 29, 2024
93 checks passed
@Georacer Georacer deleted the catapult_takeoff_fix branch September 26, 2024 19:09
Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment
Labels
WikiNeeded needs wiki update
Projects
None yet
Development

Successfully merging this pull request may close these issues.

7 participants