Skip to content

Fix FW transition throttle glitch for tilting rotor quadplanes #29696

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

Merged
merged 4 commits into from
May 23, 2025

Conversation

priseborough
Copy link
Contributor

@priseborough priseborough commented Apr 4, 2025

This is a fix for the instant forward motor(s) throttle drop that can occur when a quadplane with tilting rotors completes the transition from VTOL to FW flight. This issue was reported here #28957

This fix:

Extends the functionality of the set_throttle_min function such that the rate that the lower limit releases can be controlled by a TECS_THR_ERATE parameter and the throttle out previous value used by the TECS throttle rate limiter can also be optionally reset. If TECS_THR_ERATE is <=0 the legacy behaviour will be observed, ie the minimum throttle will be held for one TECS frame after the function is called.

Adds a function to the motors library that enables the raw normalised throttle demand to be obtained for a specified motor index.

Adds a function to the SRV_Channels library that enables the slew rate limiter state to be set for a specified channel function.

Adds a function to the tiltrotor class that provides the mean throttle of all tilting motors.

When the transition into FW flight is ready to complete it checks for a throttle demand from tilting rotors or if not available the forward motor throttle demand. The TECS minimum throttle and SRV_Channels forward throttle are both set to this value.

Testing on a multirotor VTOL with forrward tilting motors shows that the TECS throttle lower limit is set and releases at the specified 0.2 rate.

Screenshot 2025-04-04 at 9 58 10 PM Screenshot 2025-04-04 at 9 57 40 PM Screenshot 2025-04-04 at 9 57 00 PM

Here's a before and after for a SITL test using the -v Plane -f quadplane-tilthvec option

Before - the throttles of the tilting motors step to 0 before increasing
Screenshot 2025-04-07 at 8 06 41 AM

After - the throttles of the tilting motors ramp down smoothly
Screenshot 2025-04-07 at 8 04 35 AM

@priseborough
Copy link
Contributor Author

@tridge - I need help with setting up compiler directives to manage flash space

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.

thanks for this @priseborough !

@tridge
Copy link
Contributor

tridge commented Apr 7, 2025

@priseborough also please note this PR which allows the existing throttle slew limit to apply to tilted motors:
#28960
we may want both mechanisms. The advantage of the other PR is it works for non-TECS modes

@priseborough
Copy link
Contributor Author

@priseborough also please note this PR which allows the existing throttle slew limit to apply to tilted motors: #28960 we may want both mechanisms. The advantage of the other PR is it works for non-TECS modes

I think we need both. That PR deals with issues before transition completes, this one with what was happening immediately after for tiltrotor setups. Note that the reset of servo throttle channel slew limiters should also help for non TECS modes after transition completes.

Copy link
Member

@IamPete1 IamPete1 left a comment

Choose a reason for hiding this comment

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

This looks good. #29011 Would handle the smoothing of the throttle outputs. But you would still need to workout the average throttle for the TECS re-set.

// 31 previously used by TECS_LAND_PTRIM
// 31 previously used by AP_Int8 TECS_LAND_PTRIM which was removed in November 2022

// @Param: THR_ERATE
Copy link
Member

Choose a reason for hiding this comment

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

Do we need a new param? Can't we use the existing plane throttle slew limit?

Copy link
Contributor Author

Choose a reason for hiding this comment

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

It needs to be slower based on flight testing where the tilting rotors were energising the front wing in a tandem wing configuration.

Copy link
Member

Choose a reason for hiding this comment

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

OK, should we default to 0 meaning use the existing slew limit? Or at least we should use the larger of this and the existing slew limit. Someone may have set a very slow slew limit already.

@priseborough priseborough force-pushed the pr-plane-tilt-throttle-fix branch from c991bd9 to 8d227d9 Compare April 11, 2025 10:48
@priseborough
Copy link
Contributor Author

priseborough commented Apr 11, 2025

In the process of cleaning it up and updating in response to review comments a single frame glitch in the servo demands has been introduced. I'll remove the needs rework flag when the cause of this has been resolved.

@priseborough
Copy link
Contributor Author

The reason for the glitch in servo demand after incorporating review comments was af73ffb

The current throttle state also has to be reset to avoid a glitch if the TECS throttle demand is fetched before the next TECS update cycle.

I've added a patch that adds the set of current throttle state.

@priseborough
Copy link
Contributor Author

priseborough commented Apr 13, 2025

@IamPete1 and @tridge using the conversion form thrust to throttle applied to thrust demand is not exactly the same as retrieving the raw throttle demand.

If I revert commits 3ad8f32 and 8d227d9 I get the following ESC demands for vectoring quad SITL test

Screenshot 2025-04-13 at 2 25 54 PM

Using the thrust to throttle scaling I get a small dip at the time of the reset, indicating that motors->thr_lin.thrust_to_actuator does not produce the same result as motors->get_raw_motor_throttle.

Screenshot 2025-04-13 at 2 23 22 PM

I worked out why this was happening. The motors library throttle to thrust and vice-versa transformations operate with throttle in the range from spin min to spin max. Plane does not do this so the throttle returned by thr_lin.thrust_to_actuator needed to be mapped to the range from spin min to spin max. Doing this removed the throttle glitch.

Screenshot 2025-04-17 at 2 00 41 PM

@priseborough
Copy link
Contributor Author

@tridge and@IamPete1 I've tagged it for the next dev call.

@priseborough
Copy link
Contributor Author

It has been flight tested on a ARACE tiltrotor at commit 1204cba

Here are a couple of the forward transitions from the flight:

Transition in AUTO - no sudden dips in forward throttle on completion
Screenshot 2025-04-24 at 5 31 00 PM
Screenshot 2025-04-24 at 5 31 06 PM

Transition from QLOITER to CRUISE - no sudden dips in forward throttle on completion
Screenshot 2025-04-24 at 5 32 08 PM
Screenshot 2025-04-24 at 5 32 21 PM

// 31 previously used by TECS_LAND_PTRIM
// 31 previously used by AP_Int8 TECS_LAND_PTRIM which was removed in November 2022

// @Param: THR_ERATE
Copy link
Member

Choose a reason for hiding this comment

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

OK, should we default to 0 meaning use the existing slew limit? Or at least we should use the larger of this and the existing slew limit. Someone may have set a very slow slew limit already.

@priseborough
Copy link
Contributor Author

priseborough commented Apr 29, 2025

@IamPete1 wrt your comments on the default value for TECS_THR_ERATE here #29696 (comment), the AP_TECS::set_throttle_min function is only called with the reset output and slew limiter option for the tiltrotor cases so no other airframes are affected and it might be safer to decay TECS throttle lower limit for tilt rotors rather than wait for a user to stall a flow energised wing during transition and then realise they should have set TECS_THR_ERATE to a positive value.

@priseborough
Copy link
Contributor Author

I've rebased and fixed the conflicts by removing an unnecessary reverted logging commit in TECS.

@priseborough priseborough force-pushed the pr-plane-tilt-throttle-fix branch from f4f1c78 to 0d96899 Compare April 30, 2025 07:14
@priseborough priseborough force-pushed the pr-plane-tilt-throttle-fix branch from 8b5e8f2 to 0d96899 Compare May 15, 2025 09:51
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.

looks good, thanks!
just a small update to the new TECS parameter. Let me know if you'd like me to make and test that change

@Hwurzburg Hwurzburg added the WikiNeeded needs wiki update label May 19, 2025
Copy link
Member

@IamPete1 IamPete1 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 throttle scale corrected it seems to work as expected. This is Qloiter to FBWB.

image

Throttle min is set to the current throttle then it decays back at the default 20% per second. High throttle in this case so it takes nearly the full 5 seconds to get down to 0. In this case the output throttle was soon constrained on that limit,

Decay the lower limit to -1 with the rate controlled by a user adjustable parameter.
Allow the set_throttle_min function to reset the the output slew rate limiter.
@tridge tridge force-pushed the pr-plane-tilt-throttle-fix branch from eb0bcf2 to 05d12e7 Compare May 21, 2025 05:39
@tridge
Copy link
Contributor

tridge commented May 21, 2025

@IamPete1 @priseborough I've pushed the fixes and squashed

@tridge
Copy link
Contributor

tridge commented May 21, 2025

looks good in RealFlight testing

…nishes

When tilt quadplane FW transition finishes, get the throttle of the motors
used for forwrd flight and reset the TECS minimum throttle ramp and
the servo channel slew limiter to prevent a sudden drop in motor
throttle that upset the vehicle.
@tridge tridge force-pushed the pr-plane-tilt-throttle-fix branch from 05d12e7 to 6ba98a7 Compare May 23, 2025 08:38
@tridge tridge requested review from Georacer and IamPete1 May 23, 2025 08:46
Copy link
Member

@IamPete1 IamPete1 left a comment

Choose a reason for hiding this comment

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

LGTM

@tridge tridge merged commit 18076df into ArduPilot:master May 23, 2025
102 checks passed
Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment
Projects
None yet
Development

Successfully merging this pull request may close these issues.

6 participants