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 level-off and throttle without airspeed sensor #28776

Open
wants to merge 1 commit into
base: master
Choose a base branch
from

Conversation

menschel
Copy link
Contributor

@menschel menschel commented Nov 29, 2024

This PR does intend to fix Issues #28685 and #28775

This patch intends to fix two issues with auto takeoff mission item for
planes without an airspeed sensor.

Level-off fix:

  • Correct the level-off condition by factor 2 because during level-off,
    the pitch and therefore the climb-rate decreses linearly.
    Mathmatically the plane therefore only climbs half of the altitude in the expected time
    and is not guaranteed to converge to target altitude by itself.
  • Add flag for level-off stage and let TECS handle the final climb.

Throttle without airspeed sensor:

  • Remove conditional evaluation of airspeed sensor to enable traditional
    TECS-controlled throttle range also without airspeed sensor.
    This restores the behavior of ArduPlane 4.5.7.

It is to be discussed if the flag THROTTLE_RANGE in parameter TKOFF_OPTIONS is to be reversed to keep
the behavior from Plane 4.5.7 consistent with Plane 4.6 onwards.
It could be something like FORCE_MAX_THROTTLE instead.

Latest measurements with this change cherry-picked onto ArduPilot-4.6:

24-12-01_09-12-18.bin
24-12-01_09-16-52.bin
24-12-01_09-21-56.bin
level_off_fix
throttle_fix

@menschel
Copy link
Contributor Author

menschel commented Dec 1, 2024

I'm satisfied with the takeoff behavior now. There is no visible difference from 4.5.7. The parameter needs to be discussed though. I argue the parameter should be "inverted", so any user migrating from 4.5.7 to 4.6 experiences the known behavior.

This patch intends to fix two issues with auto takeoff mission item for
planes without an airspeed sensor.

Level-off fix:
- Correct the level-off condition by factor 2 because during level-off,
  the pitch and therefore the climb-rate decreses linearly.
  Mathmatically the plane therefore only climbs half of the altitude in the expected time
  and is not guaranteed to converge to target altitude by itself.
- Add flag for level-off stage and let TECS handle the final climb.

Throttle without airspeed sensor:
- Remove conditional evaluation of airspeed sensor to enable traditional
  TECS-controlled throttle range also without airspeed sensor.
  This restores the behavior of ArduPlane 4.5.7.

It is to be discussed if the flag THROTTLE_RANGE in parameter TKOFF_OPTIONS is to be reversed to keep
the behavior from Plane 4.5.7 consistent with Plane 4.6 onwards.
It could be something like FORCE_MAX_THROTTLE instead.
@@ -309,13 +308,17 @@ int16_t Plane::get_takeoff_pitch_min_cd(void)

// are we entering the region where we want to start levelling off before we reach takeoff alt?
if (auto_state.sink_rate < -0.1f) {
float sec_to_target = (remaining_height_to_target_cm * 0.01f) / (-auto_state.sink_rate);
float sec_to_target = (remaining_height_to_target_cm * 0.01f * 2.0f) / MIN(TECS_controller.get_max_climbrate(), -auto_state.sink_rate);
Copy link
Contributor

@Georacer Georacer Dec 1, 2024

Choose a reason for hiding this comment

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

The decrease of pitch is not linear; that much we've seen from the SITL tests.
But in any case, can you provide some justification for this formula?

Copy link
Contributor Author

Choose a reason for hiding this comment

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

I make the case that the scalar creates the linear dependency between remaining height and pitch.
Integrating A*X results in (A/2)*X² and that's where the factor 2 comes from.
Setting both equal results in X=1/2 for the gained altitude.

The MIN() is a sanity check to limit climb-rate to the max value known to TECS.
It is not dependent on angle but on the power to weight ratio.

I don't know what happens in 4.5.7 but there it is not linear.

Copy link
Contributor

@Georacer Georacer left a comment

Choose a reason for hiding this comment

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

Thank you for your effort @menschel !

As you have noticed, we chose to address the level-off bug in a much simpler way, implemented here: #28792

Regarding the throttle behaviour, we intentionally changed it from 4.5 to 4.6 here: #27758
In 4.5, the throttle during takeoff would be managed by TECS in TAKEOFF mode but set fixed to TKOFF_THR_MAX in AUTO mode takeoffs.
We opted to keep the 2nd behaviour.

If you really want the old throttle behaviour for TAKEOFF mode back, we would probably need to make use of another TKOFF_OPTIONS bit. That would need to be done carefully, testing all corner cases.

It's not high on my priority list. If you want to implement that, you're very welcome of course.
If you believe the 4.6 behaviour is dangerous for some reason, naturally we'd want to hear your argument.

@menschel
Copy link
Contributor Author

menschel commented Dec 1, 2024

Ahem, you have mixed Takeoff-mode and Auto-mode takeoff mission item.
I fly Auto-mode missions to have reproducible results between tests.
In 4.5 TECS manages throttle in Auto-mode during takeoff mission item and it works great.

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.

2 participants