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

Plane: Fix inability to climb the last few meters of takeoff #28707

Closed

Conversation

Georacer
Copy link
Contributor

Summary

This PR addresses #28685.

Details

This affects takeoffs without an airspeed sensor.

Cause

Some airframes will not climb at 0 pitch, regardless of throttle setting.
Thus, the current takeoff level-off strategy of asymptotically forcing pitch to 0, results in the aircraft to never climb the final few meters.

Reproduction

The behaviour was reproduced in SITL, by setting:

  • PTCH_TRIM_DEG: -10.0
  • TKOFF_THR_MAX: 75.0

Solution

After the expected time to complete the takeoff has elapsed, drive the desired pitch gradually back to takeoff pitch, over the next 5 seconds.

Testing

Before:
image

After:
image

Alternatives

The proposed solution of widening the TECS pitch limits and letting TECS take over and regulate the last few meters of the climb was not feasible:
During an airspeedless takeoff, TECS uses throttle to correct for altitude errors.
It would use pitch (if it was allowed) to correct for airspeed errors).
Thus letting TECS command the pitch angle would not help.

When an airspeed sensor is not used, during a takeoff, the pitch angle
is asymptotically driven to 0 as the takeoff altitude is approached.
Some airplanes will then stop climbing and fail to reach altitude.

If that happens, then minimum pitch is driven back up to taekoff pitch
gradually within 5 seconds.
@menschel
Copy link
Contributor

menschel commented Nov 22, 2024

Weather is currently not favorable for a test flight but I'll try to test in case it gets better.

Edit: Please also address the forced 100% throttle.

@menschel
Copy link
Contributor

menschel commented Nov 23, 2024

Two short flights.
24-11-23_08-37-52.bin
24-11-23_08-42-26.bin
Fun fact, the overshoot now happens based on the workaround.
EDIT: Scratch that, apparently turning into the wind and therefore trading speed for altitude also adds to the overshoot.

IMO the whole thing is connected to a false climb-rate estimation. I have logs from a landing test session with 4.5.7 and I see level-off happening at 3m below target altitude, not 8m.
It may be a good idea to stop limiting the pitch at level-off and see what TECS is doing out of it. If I'm not mistaken, the waypoint is 1km away and TECS should linearly climb.

EDIT:
The 4.5.7 test session. 00000027.BIN
I've also noticed an increasing rate of log corruption with 4.6.0beta. APM Planner complains, MissionPlanner ignores it.

@menschel menschel mentioned this pull request Nov 23, 2024
23 tasks
@@ -304,6 +304,14 @@ int16_t Plane::get_takeoff_pitch_min_cd(void)
// if height-below-target has been initialized then use it to create and apply a scaler to the pitch_min
if (auto_state.height_below_takeoff_to_level_off_cm != 0) {
float scalar = remaining_height_to_target_cm / (float)auto_state.height_below_takeoff_to_level_off_cm;

const int32_t takeoff_end_delay_ms = AP_HAL::millis() - takeoff_state.level_off_start_time_ms - g.takeoff_pitch_limit_reduction_sec*1000;
Copy link
Contributor

Choose a reason for hiding this comment

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

Suggested change
const int32_t takeoff_end_delay_ms = AP_HAL::millis() - takeoff_state.level_off_start_time_ms - g.takeoff_pitch_limit_reduction_sec*1000;
const uint32_t takeoff_end_delay_ms = AP_HAL::millis() - takeoff_state.level_off_start_time_ms - g.takeoff_pitch_limit_reduction_sec*1000;

Copy link
Contributor

Choose a reason for hiding this comment

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

.... or at least something needs to change here; we rely on integer wrap semantics. Possibly break this into two separate statements.

@tridge
Copy link
Contributor

tridge commented Nov 25, 2024

@Georacer I'm surprised you didn't implement the expanding pitch window using TECS like we discussed, did it not work out?

@Georacer
Copy link
Contributor Author

@Georacer I'm surprised you didn't implement the expanding pitch window using TECS like we discussed, did it not work out?

As I wrote in the description, the proposed solution of widening the TECS pitch limits and letting TECS take over and regulate the last few meters of the climb was not feasible:
During an airspeedless takeoff, TECS uses throttle to correct for altitude errors.
It would use pitch (if it was allowed) to correct for airspeed errors; this is not reliable in an airspeedless case, which we are in.
Thus letting TECS command the pitch angle would not help.

I did try it and it didn't give effective results.
If you're really curious I can repeat the experiment.


self.delay_sim_time(5)

self.reboot_sitl(force=True)
Copy link
Contributor

Choose a reason for hiding this comment

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

Suggested change
self.reboot_sitl(force=True)
self.disarm_vehicle(force=True)

.... we're going to restart SITL anyway, this is a little faster than rebooting.

@@ -304,6 +304,14 @@ int16_t Plane::get_takeoff_pitch_min_cd(void)
// if height-below-target has been initialized then use it to create and apply a scaler to the pitch_min
if (auto_state.height_below_takeoff_to_level_off_cm != 0) {
float scalar = remaining_height_to_target_cm / (float)auto_state.height_below_takeoff_to_level_off_cm;

const int32_t takeoff_end_delay_ms = AP_HAL::millis() - takeoff_state.level_off_start_time_ms - g.takeoff_pitch_limit_reduction_sec*1000;
if (takeoff_end_delay_ms > 0) {
Copy link
Contributor

Choose a reason for hiding this comment

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

This might be a linear_interpolate?

@tridge
Copy link
Contributor

tridge commented Nov 27, 2024

discussed on EU dev call, decided just to declare the takeoff complete if we are in the taper off region and we timeout

@menschel
Copy link
Contributor

menschel commented Nov 27, 2024

Can we also do something about the now forced 100% throttle?

I argue that it's a wrong design decision not to fall back to TECS controlled throttle, means the airspeed sensor presence should not be evaluated here.
https://github.com/ArduPilot/ardupilot/blob/master/ArduPlane/takeoff.cpp#L282

It also adds to the issue here because it influences the climb-rate estimation.

@Georacer
Copy link
Contributor Author

Can we also do something about the now forced 100% throttle?

I argue that it's a wrong design decision not to fall back to TECS controlled throttle, means the airspeed sensor presence should not be evaluated here. https://github.com/ArduPilot/ardupilot/blob/master/ArduPlane/takeoff.cpp#L282

It also adds to the issue here because it influences the climb-rate estimation.

For this PR we definitely won't change the throttle strategy.

Having a constant THR_MAX was a request from other developers, so you'd have to make your case on why this is a good idea.
Preferably by opening a new ticket.

@menschel
Copy link
Contributor

menschel commented Nov 30, 2024

I believe I have the issue #28685 solved in #28776

If I may do so, I'll include your commit d698139 .

@Georacer
Copy link
Contributor Author

Georacer commented Dec 1, 2024

Superseded by #28792

@Georacer Georacer closed this Dec 1, 2024
@Georacer Georacer deleted the pr/takeoff_level_off_bugfix branch December 1, 2024 19:02
Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment
Labels
None yet
Projects
None yet
Development

Successfully merging this pull request may close these issues.

4 participants