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: TKOFF_THR_MIN is applied to SLT transitions #27770

Merged
merged 4 commits into from
Aug 28, 2024

Conversation

Georacer
Copy link
Contributor

@Georacer Georacer commented Aug 6, 2024

This PR applies TKOFF_THR_MIN throttle to forward transitions of SLT-type quadplanes.

Screenshot from 2024-08-12 21-55-42

Changes

  • Apply TKOFF_THR_MIN throttle to transitions of SLT-type quadplanes.
  • Split quadplane.in_transition() into forward and backward cases. SLT and tiltrotor never go into a back-transition. Tailsitter can return in_back_transition()==true.

Tests

In SITL the following has been tested:

  • In SLT, the TKOFF_THR_MIN is applied during the forward transition.
  • In SLT, in_frwd_transition is never true during a back-transition.

Notes

  • By default TKOFF_THR_MIN is 60%. We had put it thus for classic FW takeoffs. Is it a problem that all SLT-quadplanes will now transition at 60% min throttle?

@Georacer Georacer marked this pull request as draft August 6, 2024 22:36
@Georacer
Copy link
Contributor Author

Georacer commented Aug 6, 2024

Case where QAssist will employ TKOFF_THR_MIN:
Screenshot from 2024-08-01 17-26-33

ArduPlane/servos.cpp Outdated Show resolved Hide resolved
ArduPlane/quadplane.h Outdated Show resolved Hide resolved
ArduPlane/quadplane.h Outdated Show resolved Hide resolved
@tridge tridge removed the DevCallEU label Aug 7, 2024
@Georacer Georacer force-pushed the pr/transition_min_trottle branch from cd0403b to 9cf0b18 Compare August 12, 2024 19:56
@Georacer Georacer changed the title WIP: Plane: TKOFF_THR_MIN is applied to SLT transitions Plane: TKOFF_THR_MIN is applied to SLT transitions Aug 12, 2024
@Georacer Georacer marked this pull request as ready for review August 12, 2024 20:56
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.

@Hwurzburg can you explain how the flare code works, what type of aircraft is it used on?

ArduPlane/quadplane.cpp Outdated Show resolved Hide resolved
@@ -219,7 +219,7 @@ float Plane::stabilize_pitch_get_pitch_out()
- throttle stick at zero thrust
- in fixed wing non auto-throttle mode
*/
if (!quadplane_in_transition &&
if (!quadplane_in_frwd_transition &&
Copy link
Contributor

Choose a reason for hiding this comment

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

this is specifically aiming for TVBS landing, so not fwd transition

Copy link
Contributor

Choose a reason for hiding this comment

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

we will need @Hwurzburg to have a look at how this is defined, and for what classes of aircraft

Copy link
Contributor Author

Choose a reason for hiding this comment

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

tilt rotor VTOLs landing conventionally as fixed wing....with switch active in pilot throttle controlled modes it will force tilts up at low throttle to clear props...at highest switch position it also sets pitch to flare pitch .....use it on all my tvbs for emergency fw landing when batts are low

@Hwurzburg the reason we ask is that we want to decide if the quadplane.in_transition() test needs to be replaced with a check for forward transition only.
Based on your description, I understand now that the !quadplane_in_transition check is meant to protect against the case where the pilot is currently commanding a forward transition while on low throttle. In this case we don't want to force the landing pitch.

@tridge, on second inspection, I see that there is an additional check here for !control_mode->is_vtol_mode(). When quadplane.is_back_transition()==true then tautologically is_vtol_mode()==true as well.
So adding a definition of and using is_back_transition() is superfluous.

I think we can simply replace in_transition() with in_frwd_transition() and spare us the definition of in_back_transition().

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 just tested the feature. I loaded Convergence in RealFligth, and set long DO_AUX_FUNCTION 89 1. This is the flare switch.
Took off in QSTAB, then I transitioned to FBWA.
Every time I closed the throttle to zero, the front tilt servos would raise the motors vertically.

Copy link
Collaborator

Choose a reason for hiding this comment

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

great!

@tridge tridge removed the DevCallEU label Aug 14, 2024
@Hwurzburg
Copy link
Collaborator

@Hwurzburg can you explain how the flare code works, what type of aircraft is it used on?

tilt rotor VTOLs landing conventionally as fixed wing....with switch active in pilot throttle controlled modes it will force tilts up at low throttle to clear props...at highest switch position it also sets pitch to flare pitch .....use it on all my tvbs for emergency fw landing when batts are low

It is not currently used anywhere.
@tridge
Copy link
Contributor

tridge commented Aug 21, 2024

@Georacer good catch on the default for TKOFF_THR_MIN, I think change to zero, and where the variable is used, if it is zero then use TRIM_THROTTLE, I think it is reasonable that a takeoff always uses at least trim (cruise) throttle
on some aircraft 60% throttle may lead to overspeed on takeoff

@tridge tridge removed the DevCallEU label Aug 21, 2024
@Georacer
Copy link
Contributor Author

@Georacer good catch on the default for TKOFF_THR_MIN, I think change to zero, and where the variable is used, if it is zero then use TRIM_THROTTLE, I think it is reasonable that a takeoff always uses at least trim (cruise) throttle on some aircraft 60% throttle may lead to overspeed on takeoff

I've set TKOFF_THR_MIN to 0. When it is set to 0, the transition will now use TRIM_THROTTLE.

On the other hand, for a normal plane takeoff (not transition), when TKOFF_THR_MIN==0, TRIM_THROTTLE will be used instead. as we have been discussing in #27758

@tridge tridge merged commit bc1e490 into ArduPilot:master Aug 28, 2024
63 checks passed
@Hwurzburg Hwurzburg added the WikiNeeded needs wiki update label Aug 29, 2024
@Georacer Georacer deleted the pr/transition_min_trottle branch September 16, 2024 11:18
Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment
Labels
DevCallEU WikiNeeded needs wiki update
Projects
None yet
Development

Successfully merging this pull request may close these issues.

4 participants