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

Nav launch manual throttle option #8134

Merged
merged 11 commits into from Jul 16, 2022

Conversation

breadoven
Copy link
Collaborator

Adds an option to use Nav Launch with fully manually controlled throttle. For those that prefer to launch with the motor already running before launch this seems a better option than having to shake the model to start the motor or using high idle throttle settings which cause problems if the launch isn't detected. On arming the throttle just needs to be raised to the required power and the plane thrown with INAV controlling only the climb out attitude. The throttle can be controlled by the stick during the launch.

The launch initiates at the "launch in progress" phase since all the previous phases, motor idle control and launch detection are redundant. The launch ends as usual except the throttle holds the stick setting. Launch can be aborted in the usual way by moving the sticks. Also launch timeout starts from the moment the throttle is raised. If the throttle is lowered again the launch timers are reset so the launch only ever starts from the moment the throttle is raised.

Still needs flight testing but bench testing works as expected.

@Jetrell
Copy link

Jetrell commented Jun 18, 2022

@breadoven Something you may not be aware of... Is the way normal launch and auto launch deal with I-term accumulation, and I-term error windup.
During normal launch conditions, this effect is mitigated with the default setting of fw_iterm_throw_limit = 165 and airmode_type = STICK_CENTER_ONCE.
So it doesn't allow I-term error to accumulate, and deflect the surfaces more than 165uS, if the throttle is raised for too long before the plane is thrown, and the pitch/roll/yaw sticks are moved.

Auto launch presently prevents the I-term from growing, until after the model is thrown, and launch throttle is activated, through detection.
Will it activate I-term with this approach, in the Stabilized/Climb phase, before the sticks are moved?
While I-term error should not accumulate before the throw if STICK_CENTER_ONCE is used, because moving the stick would disable the launch mode.

Angle based self leveling modes are affected mostly by this. While Acro is not, unless it has I-term set considerably higher, for greater attitude stabilization.

@breadoven
Copy link
Collaborator Author

breadoven commented Jun 19, 2022

@breadoven Something you may not be aware of... Is the way normal launch and auto launch deal with I-term accumulation, and I-term error windup. During normal launch conditions, this effect is mitigated with the default setting of fw_iterm_throw_limit = 165 and airmode_type = STICK_CENTER_ONCE. So it doesn't allow I-term error to accumulate, and deflect the surfaces more than 165uS, if the throttle is raised for too long before the plane is thrown, and the pitch/roll/yaw sticks are moved.

Auto launch presently prevents the I-term from growing, until after the model is thrown, and launch throttle is activated, through detection. Will it activate I-term with this approach, in the Stabilized/Climb phase, before the sticks are moved? While I-term error should not accumulate before the throw if STICK_CENTER_ONCE is used, because moving the stick would disable the launch mode.

Angle based self leveling modes are affected mostly by this. While Acro is not, unless it has I-term set considerably higher, for greater attitude stabilization.

The launch code resets error accumulators until motor spin up after detection so this isn't active if you start the launch after this as this option does. However, this is no different to shaking to initiate the motor before throwing (not something you're supposed to do I guess but many seem to use this method). So I don't see this option as being any different to the shake and throw method, it just cuts out the shaking bit to get the motor running instead allowing you to do it in more controlled way using the throttle directly. In either case you need to be aware of the wind up issue and throw immediately the motor is running to avoid problems. You can't wait too long anyway once the throttle is raised using this option or the shake and throw method because the launch end timer will have started potentially cutting the launch short if you wait too long to throw. Did make me wonder if using the recent code to detect if a fixed wing is flying could help here, reset error accumulators until flight is detected (usually very quick unless you launch into a howling gale but in that case you probably wouldn't want to use Nav launch anyway).

I'll consider adding something to reset the error accumulators if this option is used and the throttle is low. Shouldn't be needed though should it since anti wind-up is active with throttle low anyway ?

I have noticed that even if you use detection to start the launch after you've thrown that the plane will often take some time to correct any roll introduced by the throw. Stabilisation seems a but sluggish until it gets going.

@Jetrell
Copy link

Jetrell commented Jun 20, 2022

I think I missed a case.... Concerning Stick_center_once operation... It acts as a latch, and keeps i-term activated in flight, even when the throttle is lowered... This has benefits for gliding.
But as you know, Angle based modes will reset the i-term accumulation if the throttle is pulled low.

But when Airmode is permanently enabled. It effects all the Angle based modes. By not resetting i-term or error if the throttle is lowered.

Question -
With Air mode permanently enable Stick_center_once should prevent I-term windup before launch, because the pitch or roll or yaw sticks need to be moved, as well as the throttle increased to enable i-term accumulation.
Under this condition.. Will the i-term be enabled at launch with this PR? Because only one state of the two is meet.

But if it doesn't have Air mode permanently enabled, then it will certainly activate the i-term as soon as the throttle is raised.
Does that make sense? You know the logic better than I do. :-)

@breadoven
Copy link
Collaborator Author

I'll just test it and see if anything bad happens especially if you don't throw immediately after raising the throttle. As I said before this is just replicating the shake and throw method but using the throttle stick to directly control the motor. With the throttle stick low it should behave the same as prior to detection, error accumulators and tpa are reset (PR needs updating to include this) as is the launch end timer. Raising the throttle essentially acts like the detection phase, it stops resetting the error accumulators and starts the launch end timer. I guess the main problem with this is it isn't fool proof, you do need to launch as soon as you raise the throttle so maybe this needs emphasising in the "documentation". You have the same problem if you use the shake and throw method, you can't sit there with the motor running because apart from anything else the launch end timer will time out and the launch finish before you've thrown and also there's the wind up issue. But why wouldn't you launch immediately ?

Did occur to me that the launch with throttle low change I've been using for a long time now would have ANTI_WINDUP enabled during the launch since the throttle stick is low throughout. Maybe that explains the sluggish stabilisation during the climb, not that it ever caused any problems, just drifted a bit more than it should have perhaps. This was always with STICK_CENTER setting for airmode_type.

@breadoven
Copy link
Collaborator Author

Flight tested with a change that resets error accumulators and TPAFilter up until flight is detected. Launching worked as expected, climb out behaved no differently to a normal launch using launch detection. Start of flight is detected in around 200-300 ms from release even launching into a bit of a headwind so this is similar to using launch detection which starts the motor in a similar time frame depending on settings used. Flight detection has also been added to start the end of launch timer rather than just relying on the throttle stick position. So using flight detection avoids any issues with ITerm wind up and the launch ending earlier than expected. It does however require a GPS lock to work. This option will still work without a GPS but you can't hang around with the throttle raised waiting to launch, you need to launch as soon as the motor is running. The setting description has been updated to reflect this.

Still needs a bit more testing but otherwise seems to work OK and a better option than the shake to start method IMO.

@Jetrell
Copy link

Jetrell commented Jun 24, 2022

I know this is a wild edge case.. but I thought it might be worth mentioning.
I was doing some ground testing before a flight.. Just to be sure... And I know its hard to fool the launch detection.

But in the case that launch was not detected (GPS plug detached from the force of the throw).. It would appear that the launch cannot be overridden/aborted by the roll stick alone, unless the throttle stick is lowered.. Which may leave the pilot without control if urgently required. Or even a temporary fly away, because the launch timer would not have been activated either?

@breadoven
Copy link
Collaborator Author

I know this is a wild edge case.. but I thought it might be worth mentioning. I was doing some ground testing before a flight.. Just to be sure... And I know its hard to fool the launch detection.

But in the case that launch was not detected (GPS plug detached from the force of the throw).. It would appear that the launch cannot be overridden/aborted by the roll stick alone, unless the throttle stick is lowered.. Which may leave the pilot without control if urgently required. Or even a temporary fly away, because the launch timer would not have been activated either?

If nav_fw_launch_min_time is set to the default of 0 then it is possible to fix this by allowing stick cancellation to work when the time from launch detection is >= nav_fw_launch_min_time rather than the current > nav_fw_launch_min_time. Wasn't sure why it was only > so left it but I can't see any reason why it can't be zero as well (>=), probably just an oversight. I'll change it since it also allows another bit of code to be removed. If nav_fw_launch_min_time is set > 0 then there's nothing you can do in these circumstances but at least with this option you can kill the throttle.

Have you tested this change @Jetrell ?

@Jetrell
Copy link

Jetrell commented Jun 25, 2022

@breadoven I ran about 10 launches with the latest commit... Having nav_fw_launch_min_time = 0

  • Full control over the throttle throughout the launch phase, works fine... If anything, its better and more energy conservative than the standard mode. Because you can lower the throttle once a good climb speed is reached.

  • It will disable the launch as soon as the elevator or aileron stick is applied throughout the launch phase. I noticed this specifically on one launch, when the wind direction changed and knocked the little 250G as it left my hand. My reaction was to catch it with aileron... even though the DVR showed the level stabilization was already beginning to.

  • I-term doesn't windup after the throttle is raised, before the throw (permanent air mode was disabled).. So the GPS speed trigger must be doing its job... This plane doesn't have a data logger. But it looks just as locked-in, as it does with normal auto launch.

  • Timer and Altitude settings both work to finish auto launch, as before.

There is one thing I'd like to bring up, concerning both auto launch methods... Its the limited stick abort deadband that both the elevator and aileron sticks have from center.
It so easy to disable the launch mode, even when raising the throttle. (stick mode 1) I did this 3 times in 10 today, due to nav_fw_launch_min_time = 0.. and I was very careful in raising it.
And the beeper also shuts off as the throttle is raised.. So unless I was watching the screen, I would have no idea that I knocked the aileron, and aborted launch mode.
My view of stick disable is like this... I don't want to accidentally disable it (which I often do).. And if I'm going to abort.. I'll feed a good amount of stick input in anyway, for control.
Whats your view on increasing the abort deadband 10 to 20uS?

@MrD-RC
Copy link
Collaborator

MrD-RC commented Jun 25, 2022

I think increasing the deadband is a good idea. Why not 50uS? That's still only 5% movement. So 2.5% in each direction. Still tiny.

@breadoven
Copy link
Collaborator Author

I actually already made a change some time back that makes the stick movement dead band customizable specifically for the launch reason. I've knocked the stick on throwing a few times causing the launch to abort ... annoying. I currently have it set at 250us just for launch. It remains the same at 10us otherwise. I'll do a PR if this sounds better than just increasing it in all cases.

@DzikuVx DzikuVx added this to the 6.0 milestone Jul 13, 2022
@DzikuVx
Copy link
Member

DzikuVx commented Jul 13, 2022

@breadoven could you please resolve conflicts?

@breadoven
Copy link
Collaborator Author

All fixed.

@breadoven breadoven added the Release Notes Add this when a PR needs to be mentioned in the release notes label Jul 16, 2022
@breadoven breadoven merged commit cf0a4dd into iNavFlight:master Jul 16, 2022
@breadoven breadoven deleted the abo_manual_throttle_launch branch July 23, 2022 10:02
Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment
Labels
Ready to merge Release Notes Add this when a PR needs to be mentioned in the release notes
Projects
None yet
Development

Successfully merging this pull request may close these issues.

None yet

4 participants