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

Switched RTH Preset Altitude Override #6179

Merged
merged 20 commits into from
Apr 14, 2021

Conversation

breadoven
Copy link
Collaborator

RTH altitude mode can't be changed in flight which can result in the craft climbing unnecessarily when switched RTH is used to simply bring it home as directly as possible with the pilot able to monitor safe altitude manually. This can be an issue with Max or Fixed settings causing large climbs for instance when a level route back would have been better.

This PR provides a function that allows the pilot to override the preset RTH altitude during switched RTH by using the AltHold mode switch to effectively reset the RTH altitude to Current during the climb phase, i.e. RTH altitude is set at the altitude achieved when the AltHold switch is selected ON.

The AltHold mode switch must be set OFF after RTH is initiated before the override function will work to avoid inadvertent override if AltHold switch was already ON. The function is inhibited for failsafe RTH and controlled by a setting, default set to OFF.

The RTH altitude setting returns to the preset value when RTH is switched OFF with the exception of the Max setting which resets to the current altitude.

Been tested on a fixed wing and works as expected.

Related to #6128.

@digitalentity digitalentity self-assigned this Nov 15, 2020
@digitalentity digitalentity added this to the 2.6 milestone Nov 15, 2020
@digitalentity
Copy link
Member

digitalentity commented Nov 15, 2020

This fell through the cracks, sorry. I'll review tomorrow

src/main/navigation/navigation.c Outdated Show resolved Hide resolved
@b14ckyy
Copy link
Collaborator

b14ckyy commented Nov 16, 2020

I don't agree with the ALTHOLD as a altitude reset trigger. This won't work with Single-Channel Mode setups like on a rotary switch or with the Mode buttons on Jumper/Radiomaster radios. To use this we would need to add a separate switch just for RTH altitude override.

I recommend to use either pitch or roll input with time delay to reset the RTH altitude to the current altitude. This way the pilot could override not only the altitude but also the climb_first option but continuing climb.

RTH engaged > plane climbs
Pitch stick pushed forward over max threshold for more than 1s > climb is aborted and current altitude will be used for rth
and
Roll stick pushed to one side for more than 1s > plane goes into rth turn to fly back but continues climb to override climb first

@MrD-RC
Copy link
Collaborator

MrD-RC commented Nov 16, 2020

I don't agree with the ALTHOLD as a altitude reset trigger. This won't work with Single-Channel Mode setups like on a rotary switch or with the Mode buttons on Jumper/Radiomaster radios. To use this we would need to add a separate switch just for RTH altitude override.

I recommend to use either pitch or roll input with time delay to reset the RTH altitude to the current altitude. This way the pilot could override not only the altitude but also the vlimb_first option but continuing climb.

RTH engaged > plane climbs
Pitch stick pushed forward over max threshold for more than 1s > climb is aborted and current altitude will be used for rth
and
Roll stick pushed to one side for more than 1s > plane goes into rth turn to fly back but continues climb to override climb first

Love this idea. It allows the override of two aspects of the launch. However, I would probably see a longer threshold time, maybe 5 seconds. Also, it would be cool if stick up cancels the climb, but stick down will re-enable it.

@digitalentity
Copy link
Member

I will move this to 2.7 milestone so we can finalize the logic and won't rush the implementation. I like the idea with stick-controlled behavior better as it doesn't repurpose the flight mode creating potential issues and confusion.

@digitalentity digitalentity modified the milestones: 2.6, 2.7 Nov 16, 2020
@b14ckyy
Copy link
Collaborator

b14ckyy commented Nov 16, 2020

I will move this to 2.7 milestone so we can finalize the logic and won't rush the implementation. I like the idea with stick-controlled behavior better as it doesn't repurpose the flight mode creating potential issues and confusion.

good idea. I know you wanna finish 2.6 asap but no need to rush at this point. :)

@breadoven but the idea is great. This would make the use of max-alt RTH much easier when flying in mountains or doing cloud surfing and some low altitude flying afterwards. climbing to 2000m with a nearly empty battery can be a bad thing.

@breadoven
Copy link
Collaborator Author

OK I see what you're saying. I did this as a quick and easy fix for unwanted RTH climbs and using Althold mode seemed a reasonable easy to implement method given it effectively holds the RTH altitude. I assumed most transmitters could be configured to have RTH and Althold switched separately if you wanted to use this function. (even on my basic Flysky i6!). However, I quite like the pitch stick idea, more intuitive perhaps, so I'll have a look at this method. Needs to use a short time delay to make it worth using though which shouldn't be a problem given there's no reason to use full pitch or roll stick in RTH mode so hard to override by mistake.

Override trigger changed from AlfHold mode to pitch stick input.
@breadoven
Copy link
Collaborator Author

OK so updated this to work off the pitch stick. Set to trigger the override if pitch is held above 1900 for more than 1 second. Tested on the ground with a bodge to get function to run and works as it should but flight test is rained off for now.

As to using roll to override Climb First, needs a bit more work. However, it could be combined in a separate PR together with a mod I've been using for a while which allows a Loiter (spiral) climb when Climb First is used rather than the linear climb that's used now. It employs the same method that's used for changing altitude to the RTH Home altitude (Loiter with a m/s rate limit rather than pitch limit). Is there some reason why a spiral climb isn't used for the initial RTH climb other than instability/stall issues perhaps if it's too tight and steep? If this spiral climb isn't of interest then the roll stick override for Climb First can just be added to this PR (guess the PR name would need changing).

@MrD-RC
Copy link
Collaborator

MrD-RC commented Nov 18, 2020

One good reason not to turn while climbing is the environment. If your flying gaps low down and failsafe, the last thing you want to do is turn. In this scenario, there is less likely to be an obstacle straight in front of you, than to the sides. This is for me, one of the reasons for climb first.

I would have the spiral climb as a separate option. Maybe change climb first from an on/off affair, to climb method. This could have, for example, TURN_FIRST, SPIRAL_CLIMB, and CLIMB_FIRST as options.

RTH Climb First override added using roll stick.
RTH altitude override - pitch down stick
RTH Climb First override - roll right stick
Stick hold for > 2 seconds.
Fix ABS build error
@breadoven
Copy link
Collaborator Author

Updated to include RTH Climb First override.
Stick hold time increased to > 2s.
Pitch down to override RTH altitude preset.
Roll right to override Climb First.

Tested in flight and works as expected.

@breadoven
Copy link
Collaborator Author

Seems to be an issue with the Settings.md update. Keep getting workflow messages to update it using the python script but when you do it updates other PR entries that are in the latest settings.yaml taken from the iNavflight master but which aren't in the current settings.md document on iNavflight master because it hasn't been updated with the current settings.yaml. Makes it appear as if the other changes in settings.md are related to your PR when in fact they aren't. Easier to not use the python script and just update manually to ensure other unrelated entries don't end up part of your PR, or will this come out in the wash when the iNavflight master settings.md is updated at some point ?

@CertainBot
Copy link

This is a very nice feature indeed. A suggestion is to have an OSD message showing which (stick command) RTH mode is active for a quick check/confirmation. What is great is that the pitch roll stick commands can give 4 types of RTH or even 5 if retrieving the original mode is done by reengaging RTH.

@avsaase
Copy link
Member

avsaase commented Dec 20, 2020

@breadoven Great feature! Couple ideas for further improvements:

  • both holding roll left and right changes from climb first to turn first and the stick direction determines the direction of the turn. IMO turning and climbing can then be done at the same time.
  • I think 1 second of stick position >1900 or <1100 is enough to avoid triggering this feature accidentally. 2 seconds is a long time.
  • holding the elevator stick down (pitch up) could reenable the original rth altitude

I also like the idea of a SPIRAL_CLIMB setting.

@breadoven
Copy link
Collaborator Author

I did think of OSD messages but decided you just end up with message overload. This is an optional settings so I think if you decide to use it you should be able to remember the stick movements to override which are intuitive to an extent anyway.

The problem with things like this is how complicated do you want make them ? I think if you start adding more and more options it starts getting too confusing to use easily. If you want to reset to the original RTH altitude it's probably easier to just toggle the RTH mode which resets the overrides.

The stick time delay is always going to be a preference. 1s is only going to mean a few meters extra climb or distance travelled so doesn't make much of a practical difference. Easily changed if need be.

I'll do a PR for the spiral climb. I did ask why it wasn't an option already but got limited feedback. I think it's not suitable for some planes that have a tendency to tip stall perhaps. I did notice it didn't work well with a flying wing that suffered from horizon drift, struggled to turn and climb consistently as you'd expect. However, things improved significantly after changing an IMU setting.

@avsaase
Copy link
Member

avsaase commented Apr 3, 2021

I'd like to test this, but I'm not 100% sure how the roll override combines with the spiral climb option. There's also a merge conflict between the two PR's.

@breadoven
Copy link
Collaborator Author

Roll override just changes RTH climb first to turn first. Spiral climb only works with climb first, just an alternative to the linear climb it performs currently. So if you have climb first and spiral climb set it will spiral climb on RTH during the initial climb. If you override this initial climb using the roll stick the spiral climb will stop and the wing will turn to home and return directly climbing on the way using the current turn first linear climb.

I'll have to check the merge conflict.

@breadoven
Copy link
Collaborator Author

breadoven commented Apr 4, 2021

@avsaase Actually the merge conflict will just be down to a change on the same line in both PRs, should be the following:

if (((navGetCurrentActualPositionAndVelocity()->pos.z - posControl.rthState.rthInitialAltitude) > -rthAltitudeMargin) || (!navConfig()->general.flags.rth_climb_first)) {

You'd need to resolve it yourself by including the additions from both PRs.

Need to ensure your cruise speed is set correctly and the climb rate is no higher than perhaps 2m/s for the spiral climb option otherwise there's a risk of stall obviously. Also depends on the loiter radius used.

@avsaase
Copy link
Member

avsaase commented Apr 4, 2021

Should I remove || rthAltControlStickOverrideCheck(ROLL) introduced by this PR from that line then?

@breadoven
Copy link
Collaborator Author

With both PRs (override and spiral climb) merged the line should read as:

if (((navGetCurrentActualPositionAndVelocity()->pos.z - posControl.rthState.rthInitialAltitude) > -rthAltitudeMargin) || (navConfig()->general.flags.rth_climb_first == OFF) || rthAltControlStickOverrideCheck(ROLL)) {

navConfig()->general.flags.rth_climb_first == OFF and rthAltControlStickOverrideCheck(ROLL) are both disabling climb first, the first by setting if OFF, the second by overriding it using the Roll stick during the RTH initial climb.

@avsaase
Copy link
Member

avsaase commented Apr 4, 2021

Okay that's the way I did it. Thanks. I hope to test it next week but the weather forecast isn't looking great.

@avsaase
Copy link
Member

avsaase commented Apr 12, 2021

I just tried this out today and I think it's great. It's nice to set an RTH altitude that's safe in any environment you fly in, but not do an unnecessary long climb when you have don't need to. I tried this in combination with the spiral climb option, which also works well.

@avsaase avsaase requested a review from digitalentity April 12, 2021 20:12
@avsaase avsaase added Ready to merge Release Notes Add this when a PR needs to be mentioned in the release notes labels Apr 12, 2021
@avsaase
Copy link
Member

avsaase commented Apr 12, 2021

@breadoven This can be merged once you resolve the conflict.

@breadoven
Copy link
Collaborator Author

OK, conflict fixed.

@avsaase
Copy link
Member

avsaase commented Apr 13, 2021

Have you tried this on a multirotor? I only recently found out you have some manual control during rth and I am wondering how that interacts with this PR. I can probably try it myself this evening, but maybe you know?

@breadoven
Copy link
Collaborator Author

I haven't tried it on a multirotor. Not had many flights since I got one. Also not had it climb more than 20m in RTH and it climbs so fast the override barely had time to be any use. I assume if you pitch whilst it climbs it moves towards home (how does this work with turn first ?) and roll would see it move sideways ? Not sure why you'd want this during a RTH (dodging obstacles maybe ?) since it's largely constrained in its path home anyway. Needs a quick test to see if anything odd happens I guess. Should be able to do it today.

@breadoven
Copy link
Collaborator Author

OK I managed to test this on a 5" multirotor. It works as expected overriding the settings however I'm thinking the Roll override should be limited to fixed wing only.

The reaction of a multirotor to Roll and Pitch inputs during RTH climb is much more aggressive than a FW. This isn't a problem for the Pitch override because it simply causes the drone to accelerate toward home which is what you want it to do (assuming it's already turned toward home which it does immediately RTH is selected, takes less than a couple of seconds on the 5"). However, the Roll override causes it to slew sideways a relatively large distance, fully under control but moving in the wrong direction, which isn't what you want. Also overriding Climb First doesn't seem so useful for a multirotor anyway since it always climbs vertically in this case, it can't fly off in the "wrong" direction. away from home, like a FW can which is probably the main reason for using the Climb First override.

So keep the Altitude Pitch override for a multirotor but inhibit the Climb First Roll override is my suggestion.

@b14ckyy
Copy link
Collaborator

b14ckyy commented Apr 13, 2021

During RTH it is possible with INAV to make course correction in altitude and also direction to avoid obstacles if needed. This works on fixed wings and also copters. This feature should stay untouched IMHO. but as roll override does only abort climb first and pitch override does abort the climb, roll should be only blocked on copters during the ascent phase. Not during the RTH phase. If this is possible.

@avsaase
Copy link
Member

avsaase commented Apr 13, 2021

I also did a quick test with a quad today and the altitude override worked well but I think 2 seconds is too long. I wanted to use this when I was very close to home and it actually overshot the home position before the altitude override was triggered. Since you need to hold the stick above above maxcheck, which most people would normally almost never do, I feel it is safe to reduce the hold time to 1-1.5 seconds. I didn't try the climb first override, but I agree it doesn't make much sense to have this override on quads.

@b14ckyy I think what @breadoven means is to disable the override this PR introduces, not the manual control that already exists.

@breadoven
Copy link
Collaborator Author

I was thinking of reducing the delay to 1 second myself. So I'll update the PR with a reduced delay of 1 second and inhibit the Roll override for a multirotor.

Reduced stick hold delay time to 1s and limited climb first override to fixed wing only
@avsaase
Copy link
Member

avsaase commented Apr 14, 2021

Just tried this again and the 1 second delay is much better. Thanks!

@DzikuVx DzikuVx merged commit 1ba891d into iNavFlight:master Apr 14, 2021
@breadoven breadoven deleted the RTH-Altitude-Override branch April 15, 2021 13:43
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.

7 participants