Skip to content

Fixed wing Auto Speed Mode#11595

Open
breadoven wants to merge 7 commits into
iNavFlight:maintenance-10.xfrom
breadoven:abo_auto_speed_mode
Open

Fixed wing Auto Speed Mode#11595
breadoven wants to merge 7 commits into
iNavFlight:maintenance-10.xfrom
breadoven:abo_auto_speed_mode

Conversation

@breadoven
Copy link
Copy Markdown
Collaborator

@breadoven breadoven commented May 27, 2026

Adds Auto Speed mode for fixed wing similar to #10928.

Operation is pretty simple. It is enabled as an aux mode so can be activated in the usual way. Minimum and maximum allowed speeds are set using 2 settings with a range of 5 to 50 m/s, defaults of 11m/s and 22m/s respectively. The desired speed is set between these limits using a control such as the throttle stick (default) which acts as a speed controller. The control used can be selected with a setting that defines the channel used by the control. Speeds are either Pitot or 3D GPS based (so a valid velocity estimated is required) defaulting to Pitot if installed.

An OSD element has been added which displays the current set speed, this is only visible when Auto speed mode is active. The OSD element also indicates which speed source is being used, Ground or Airspeed, and whether or not Auto speed is active, displaying "OFF" if the mode is selected but not active.

Throttle is automatically controlled using PID control with P, I and D inputs with filtering to damp out rapid throttle changes. In Nav modes the normal fixed wing pitch2throttle control is bypassed when using a Pitot. Minimum ground speed throttle override is still active for Pitot and ground speed based control.

There is no maximum throttle limit set at the moment. Minimum throttle is dynamically limited in ground speed mode based on cruise throttle + pitch2throttle settings, but Pitot speed mode is always limited to Idle only. Motor stop is disabled when using Auto speed regardless of other Nav settings. In light of this, for safety reasons, Auto speed mode is included in the Nav arming blocker so must be disabled before arming and it also won't activate until the plane is detected in flight.

The mode can be activated in all cases except during during Failsafe and Emergency Landing and certain phases of Nav modes where it's not sensible to use it. So it can be used in Manual and Acro as well as navigation modes.

Currently there is no way to rapidly shut off the mode other than via the aux activation. This may need to be looked further if it's considered a problem together with other changes to improve functionality such as dealing with strong head winds etc.

HITL tested only at the moment where it works well with the default PID tune. Throttle control is smooth and responsive. Behaviour in strong wind works as expected with minimum throttle protection preventing stall when flying down wind using ground speed as the reference.

Configurator support iNavFlight/inav-configurator#2641.

@qodo-code-review
Copy link
Copy Markdown
Contributor

Qodo reviews are paused for this user.

Troubleshooting steps vary by plan Learn more →

On a Teams plan?
Reviews resume once this user has a paid seat and their Git account is linked in Qodo.
Link Git account →

Using GitHub Enterprise Server, GitLab Self-Managed, or Bitbucket Data Center?
These require an Enterprise plan - Contact us
Contact us →

@github-actions
Copy link
Copy Markdown

github-actions Bot commented May 27, 2026

Test firmware build ready — commit 3ad4da1

Download firmware for PR #11595

237 targets built. Find your board's .hex file by name on that page (e.g. MATEKF405SE.hex). Files are individually downloadable — no GitHub login required.

Development build for testing only. Use Full Chip Erase when flashing.

@Jetrell
Copy link
Copy Markdown

Jetrell commented Jun 1, 2026

@breadoven Firstly I want to start by saying how much we all appreciate your work here on INAV. ❤️
And what follows is not ingratitude. But rather, just putting the facts out there.

When I setup the fixedwing auto speed mode with the IPF. I also tried a simplified version as you have here. But found it was just too lacking in many area's of safety of operation, and efficiency.
I noticed you mentioned many of these other issues. But I thought a rundown of why I added these extras, might help.

Example:

  • The Min and Max throttle value the throttle controller can use. Plays a big part in how efficient the system can work. So their addition is practically a must.
    Plus if you do add those setpoints. It isn't a good idea to share them with nav_fw_min_thr and nav_fw_max_thr. Because altering them will significantly effect the way Pitch2Thr works when not using auto speed mode.

  • I also tried using the throttle stick to set the speed target.
    It only worked very average. Because whether you fly with stick mode 1 or 2. Most of us move the throttle stick little by little as we make an aileron or rudder input. Causing the target speed to shift, and constantly require resetting.
    Even with a throttle deadband. It still occurred when flying in Acro.
    And using the throttle stick to set the speed target also rules out a safety shut off of auto speed mode. As you would have noticed. I used a delta (mildly faster) movement of the throttle stick, to exit auto speed mode if an emergency happens. Which it did once. And by pulling the throttle lower or even higher, it switches back to manual throttle control.
    I know the addition of a pot for speed target control, requires the use of an extra channel, But it does make it worth while. However I also tried just having the target setpoint being hard set as well, to a cruise speed that suits the pilots requirements. That too work well if channels are lacking.

  • I also found that 3Dspeed required the "tailwind" safety airspeed throttle-up addition, to stay ahead of a low airspeed stall, if the plane was commanded to climb manually or by nav control when in RTH or a mission.
    Which would also require a setting, but I found it was absolutely worthwhile from a safety stall perspective.

  • And Airspeed target was something that I noticed many people asked about. And i did find it advantageous for flight efficiency. The main time 3Dspeed was better, is if you wanted to make good headway into a strong headwind. And make it to your destination faster.

  • I also found having the auto speed Throttle element on the OSD helped to determine how well the system was working. It provided a good visual reference when tuning and when commanding a steep dive or climb, so you could see how efficiently throttle was being feed-in, to hold the target speed.

I no this was long winded. And I'm not trying to make more work for you. But I thought it might be helpful for you to know what I also tried. So the feature can be made safer and more user friendly.
Plus if this feature is implemented to a higher standard, it leaves the door open for so many better fixedwing improvements.
e.g.
Fixed airspeed when running autotune. Which provides a more accurate FF and Rate tune.
I also tried using in with AutoLaunch. It also improved climb out efficiency, without risking a stall.
And it also help slow the plane, without risking a stall, when I tried it with fixedwing auto landing mode.

@breadoven
Copy link
Copy Markdown
Collaborator Author

breadoven commented Jun 1, 2026

@Jetrell I probably should have said this is a work in progress. The initial build was just for basic testing in light wind but obviously is limited otherwise.

I've made some changes in the latest commits:

Added pitot
Pitot will be used by default if available. There is no means of actively selecting between pitot and ground speed ... at the moment. One issue with the virtual pitot I noticed is that its usage isn't dependent on isEstimatedWindSpeedValid so that's been added. However, the check for isEstimatedWindSpeedValid doesn't look too useful with it typically taking 15 mins to timeout and become invalid if you're not manoeuvring. This seems to have come from the research paper used for the theory but doesn't seem realistic for real world use. I think a shorter time period should be used here, probably < 5 mins.

Added stall protection when using ground speed
This is based on existing cruise throttle and pitch2throttle and sets the minimum allowed throttle.

Added low ground speed protection
This uses the existing logic which works albeit crudely but I guess it's really just a last resort thing. One issue here is the Nav Pos and Alt controllers shut off if ground speed drops below 3m/s. This doesn't make sense if you have a pitot so the logic needs reconsidering where airspeed is available.

Added a NAV_CTL_SPEED flag
Allows activation in all Nav phases where it makes sense including during most Auto landing phases.

Things that need further work:

  1. Adding Max/Min throttle settings - this is trivial to do so not an issue. Although is this not more related to Max throttle than Min ? As mentioned above min speed using ground speed is dynamically set by cruise throttle and pitch2throttle settings. And with pitot I don't see the issue with allowing idle throttle, e.g. in dives.
  2. Using speed demand methods other than throttle - probably a personal preference thing but I can see the issue with the other control axis upsetting the set throttle position.

I also found having the auto speed Throttle element on the OSD helped to determine how well the system was working. It provided a good visual reference when tuning and when commanding a steep dive or climb, so you could see how efficiently throttle was being feed-in, to hold the target speed.

I'm not sure what you mean here. The normal OSD throttle display shows the Auto Speed throttle setting the same as any other auto throttle mode. The only OSD element that's been added for this PR displays the selected speed, (300U) or (ASPD) if Autospeed mode is ON but not active. This could be changed to show if airspeed or ground speed is being used I guess, e.g. G: 300U vs A: 300U.

@Jetrell
Copy link
Copy Markdown

Jetrell commented Jun 1, 2026

isEstimatedWindSpeedValid doesn't look too useful with it typically taking 15 mins to timeout and become invalid if you're not manoeuvring.
I think a shorter time period should be used here, probably < 5 mins.

I totally agree. The wind can swing in as little as a couple of hundred meters. So 15mins seems extreme. I figured it was just set this high, so virtual wind/airspeed wouldn't become invalid and cause issues with something that was relying on it.

Although is this not more related to Max throttle than Min ?

Max throttle is more beneficial for power efficiency. But limiting Min throttle to a value higher than zero. Has two benefits that I found.

  1. The first could stop a possible ESC desync, in the case of the plane pulling a loop in Acro mode. It will shut the throttle down in the diving half of the loop. And then the p term will apply Max throttle in the climbing half of the loop. I've seen it throttle-up very hard and fast.
  2. The other is that a propeller (disc) that is spinning at lower speeds creates more drag, than a propeller that has stopped spinning. This is useful to help the auto speed mode hold the target speed in a dive.

The normal OSD throttle display shows the Auto Speed throttle setting the same as any other auto throttle mode. The only OSD element that's been added for this PR displays the selected speed

Sorry, I could have worded that better.
What I meant was not Nav Auto throttle.. It's OSD element will be displaying what auto speed mode is outputting when the plane is in a navigation mode.
But when the plane is in Auto speed mode and flying in Acro, Angle , AngleHold, Horizon or Manual. That OSD element will only display the manual throttle value. Not the output of the Auto Speed mode controller.
That was why I mentioned having it as its own throttle element is very useful.

@breadoven
Copy link
Copy Markdown
Collaborator Author

  1. The first could stop a possible ESC desync, in the case of the plane pulling a loop in Acro mode. It will shut the throttle down in the diving half of the loop. And then the p term will apply Max throttle in the climbing half of the loop. I've seen it throttle-up very hard and fast.

There is filtering on the throttle output that damps the rate of change so maybe it's not an issue in this case.

  1. The other is that a propeller (disc) that is spinning at lower speeds creates more drag, than a propeller that has stopped spinning. This is useful to help the auto speed mode hold the target speed in a dive.

This PR honours motor stop where applicable, Acro, Manual etc, but it could be changed to prevent that and have Idle as the minimum allowed always. I left motor stop behaviour as is to avoid surprises, e.g. in Manual, although that could be fixed by only allowing activation when in flight.

The normal OSD throttle display shows the Auto Speed throttle setting the same as any other auto throttle mode. The only OSD element that's been added for this PR displays the selected speed

Sorry, I could have worded that better. What I meant was not Nav Auto throttle.. It's OSD element will be displaying what auto speed mode is outputting when the plane is in a navigation mode. But when the plane is in Auto speed mode and flying in Acro, Angle , AngleHold, Horizon or Manual. That OSD element will only display the manual throttle value. Not the output of the Auto Speed mode controller. That was why I mentioned having it as its own throttle element is very useful.

This shows the Auto throttle OSD display whenever Auto Speed is active, so it also works for non Nav modes.

@Jetrell
Copy link
Copy Markdown

Jetrell commented Jun 5, 2026

The maintenance-9.x branch was damage a week back, and was retired. It would seem like this may have been built upon it. The tuning tab won't load.
I think @sensei-hacker has now repaired and replaced it for 9.1.

And when I was going to set it up on a plane. I could only find Auto Speed in the modes. But I couldn't find an activation setting or channel selection to choose between 3DSpeed, and Airspeed, while in flight.
I guess that would require two modes. One for each speed type. So the different slider positions could be placed on the same RC channel,

@breadoven
Copy link
Copy Markdown
Collaborator Author

breadoven commented Jun 5, 2026

The maintenance-9.x branch was damage a week back, and was retired. It would seem like this may have been built upon it. The tuning tab won't load. I think @sensei-hacker has now repaired and replaced it for 9.1.

It was built on the maintenance 10.x branch so I don't know if that also has a problem related to 9.x. @sensei-hacker ?

Edit: I just checked and I also can't get the Tuning tab to work in Configurator with the changes for this PR or the 9.0.2 version so there must be something in the firmware that's broken.

And when I was going to set it up on a plane. I could only find Auto Speed in the modes. But I couldn't find an activation setting or channel selection to choose between 3DSpeed, and Airspeed, while in flight. I guess that would require two modes. One for each speed type. So the different slider positions could be placed on the same RC channel,

At the moment there is only the Auto Speed mode. As it is this PR will use airspeed if a pitot is active, otherwise it uses ground speed. There is no means of swapping between airspeed and ground speed and I don't think it makes sense to do this by using up a mode. Would be better to use programming probably which should be easy enough to add if not already possible, I haven't checked.

@sensei-hacker
Copy link
Copy Markdown
Member

It was built on the maintenance 10.x branch so I don't know if that also has a problem related to 9.x.

maintenance-10.x is not affected by the same issue.

The problem was that maintenance-10.x commits got leaked into maintenance-9.x.(which I then reverted, meaning there are commits add and removing the changes).

@breadoven
Copy link
Copy Markdown
Collaborator Author

It's probably an MSP issue related to the new PID this PR adds. Need to check it further.

@Jetrell
Copy link
Copy Markdown

Jetrell commented Jun 5, 2026

Would be better to use programming probably which should be easy enough to add if not already possible, I haven't checked.

Using the IPF would be okay.
Otherwise it means the user would have to disable their pitot, removing the other benefits it adds, just so they could use 3Dspeed auto speed. Which isn't ideal.

@sensei-hacker
Copy link
Copy Markdown
Member

sensei-hacker commented Jun 6, 2026

This PR honours motor stop where applicable, Acro, Manual etc, but it could be changed to prevent that

IMHO people who want motor stop off can (and probably do) turn it off. Those who want it on can turn it on. I don't see any reason for this mode to override the pilot's specific instructions.

@sensei-hacker
Copy link
Copy Markdown
Member

sensei-hacker commented Jun 6, 2026

It's interesting to me that some RC folks still say this "a propeller that is spinning at lower speeds creates more drag, than a propeller that has stopped spinning". NACA, the predecessor of NASA, tested this properly in the 1930s -1940s and got solid data. (The 1930s and 1940s saw a great need for advancing research on airplane performance, for -- reasons).

See:
NACA Report No. 641 Hartman, Edwin P., and Biermann, David. (1938). "The Aerodynamic Characteristics of Full-Scale Propellers Having 2, 3, and 4 Blades." National Advisory Committee for Aeronautics (NACA).

NACA ARR No. L5A13a / Walter A. Bartlett Jr. (1945): "Wind-Tunnel Tests of a Dual-Rotating Propeller Having One Component Locked or Windmilling".

Quoting the NACA technical memorandum "Improving the Performance of Multi-engined Airplanes by Means of Idling Propellers:
"the 'free-wheel' Propeller significantly minimizes the braking effect of a stopped engine."

The reasoning for thinking otherwise may be either using the reference frame of a person standing on the ground rather than the airplane's frame of reference, or forgetting that fighting the torque takes energy? Forgetting that you're using up energy fighting the spin (that energy coming from aileron drag fighting the torque). I've seen that in "testing" where they have the apparatus anchored to a table and forget to measure the torque applied to the table. From that testing, we can conclude that stopping the motor is better -- but only if the plane is anchored to a table while flying.

Looking at it from the relevant frame of reference, that of the aircraft, perhaps we can see that a prop that is freewheeling is free-wheeling WITH the airflow? It's moving right along with the air, minus motor friction. Therefore isn't a prop "stopped" from the frame of reference of someone on the ground one that is moving AGAINST the airflow. Probably nobody thinks that having the prop go BACKWARDS against the airflow would make it more efficient, but from the point of view of the airflow, a braked prop is moving backwards relative to the flow - it's not moving with the airflow. That seems to be what the professional researchers have found?

Or perhaps one could look at this way:

Is applying a little bit of backwards force to make the propeller not go with the airflow but instead match the person on the ground exactly the same thing as applying a lot of backwards force to make it spin backwards relative to the guy on the ground? Does the research over the last 90 years by NACA, NASA, DLR and others indicate it's doing precisely the same thing, just in different amounts?

@Jetrell
Copy link
Copy Markdown

Jetrell commented Jun 6, 2026

"the 'free-wheel' Propeller significantly minimizes the braking effect of a stopped engine."

It all depends on the ESC setting state.
If the ESC is running Passive Freewheeling (asynchronous). Then it will rotate like a windmill. With little drag.

But if Active Freewheeling (synchronous rectification) is applied. The motor acts as a regenerative drag brake.. Not stopping the motor, but impeding the airflow through the propeller disc .

@breadoven
Copy link
Copy Markdown
Collaborator Author

breadoven commented Jun 6, 2026

The main reason for keeping the motor at idle is simply because a mode like this may demand max throttle regardless of throttle position (or some other control being used for speed demand for that matter). If you allow motor stop the motor will go from stop to max instantaneously as soon as the throttle is raised slightly which isn't desirable and I don't think normally happens in any other mode.

I never liked the motor behaviour before nav_overrides_motor_stop was added when the motor went from stop to cruise throttle in Nav modes, banging on and off with the throttle stick around the low point. It's not healthy especially with things like folding props.

Having said that you could add something to limit throttle acceleration if the motor is stopped so not an issue to fix if need be and I guess it also depends on whether or not the ESC has soft start.

And the Tuning tab in Configurator should be working correctly now with the PID settings for this added.

@Jetrell
Copy link
Copy Markdown

Jetrell commented Jun 6, 2026

And the Tuning tab in Configurator should be working correctly now with the PID settings for this added.

Did it work for you ? I tested the last commit with the Configurator build for this PR, and also with the RC1 release. And the Tuning tab still would not open for me.

motor went from stop to cruise throttle in Nav modes, banging on and off with the throttle stick around the low point. It's not healthy especially with things like folding props.

Yeah true. And some ESC software's (Oxbot) have trouble with this instantaneous smash of the throttle.

@breadoven
Copy link
Copy Markdown
Collaborator Author

And the Tuning tab in Configurator should be working correctly now with the PID settings for this added.

Did it work for you ? I tested the last commit with the Configurator build for this PR, and also with the RC1 release. And the Tuning tab still would not open for me.

I think you'll need to use the version from actions for the last commit:

https://github.com/iNavFlight/inav-configurator/actions/runs/27044501551

@sensei-hacker
Copy link
Copy Markdown
Member

Just to double-check:

Did you guys just say the Tuning tab is broken on Windows for 9.1-rc1? Or it just doesn't work with this PR?

@dcan999
Copy link
Copy Markdown

dcan999 commented Jun 6, 2026

I was getting ready to submit a PR for a fixed-wing speed control feature, then found this and realized similar work is already in progress.

Would it be useful if I shared my implementation so you can review the approach and pull any ideas/features that seem helpful? Mine currently includes throttle-stick speed-set adjustment for pilots with limited channels, optional AUX/pot speed-set adjustment with configurable speeds at 1000us and 2000us, air/ground speed source selection, minimum airspeed protection, max throttle/authority limiting, and exposed tuning for FF, throttle change rate, and I-decay/bleed.

Happy to compare notes rather than duplicate work.

@breadoven
Copy link
Copy Markdown
Collaborator Author

Just to double-check:

Did you guys just say the Tuning tab is broken on Windows for 9.1-rc1? Or it just doesn't work with this PR?

It doesn't work with this PR, which is expected because of the new PID controller. Works fine with the accompanying Configurator PR though.

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.

4 participants