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

In flight emergency rearm #9254

Merged
merged 12 commits into from
Oct 24, 2023
Merged

Conversation

breadoven
Copy link
Collaborator

@breadoven breadoven commented Aug 22, 2023

Similar to #8736 but allows for rapid rearm without any arming checks and for a limited timeout period only, currently set at 5s.

Works on the basis of checking if flight was flagged at takeoff with no landing detected since + an additional sanity check on whether the craft still appears to be in flight. Multirotor flight sanity is checked after disarm based on vertical velocity ... if there is none 1.5s after disarming then it's probably not flying so emergency disarm is cancelled. Angle is activated for 5s after an emergency rearm on a multirotor to try and avoid it flying off unpredictably. Change also prevents Nav Launch from activating after an in flight rearm.

The 5s rearm window could be changed to a setting if need be.

@MrD-RC
Copy link
Collaborator

MrD-RC commented Aug 22, 2023

@breadoven to answer your question about if a quad can even rearm in flight. Sure, no problem.

https://youtu.be/9Rtb4lD2hJc

@breadoven
Copy link
Collaborator Author

@breadoven to answer your question about if a quad can even rearm in flight. Sure, no problem.

https://youtu.be/9Rtb4lD2hJc

OK, in that case just need to think of some sort of sanity check or just skip it for multirotor and always allow rearm. Can't help but think that PID behaviour should reveal some difference between sitting on the ground and hovering above it or even descending at minimum throttle. Problem is it needs to be reliable always otherwise you'll miss it at the point of disarm which is when it gets checked.

@rts18
Copy link

rts18 commented Aug 22, 2023

@breadoven The guys on RCGroups will be happy with this addition.

@breadoven
Copy link
Collaborator Author

I guess the solution for quads is to check what happens after you disarm ... if it plummets it's still flying, if it doesn't plummet after a second or so it probably isn't flying so cancel the rearm timeout window.

@Jetrell
Copy link

Jetrell commented Aug 23, 2023

I'm not sure if you've read my post here - #8736 (comment)
This method works well for both hovering or forward flight... But ANGLE mode can also be coupled with ALTHOLD mode for that couple of seconds after rearming. Not just to regain attitude level stabilization, but to prevent an accelerated free fall on heavy multicopters.
This may seem a little over kill. But disarming in flight is not something we plan to do. And not all multicopters fall flat when they start to free fall.
From questions on Discord. It appears most of the MC INAV builds are based around cruisers and long range, more than freestyle.. Meaning that many of these people may not have the fastest reactions to catch a free falling multicopter, if they accidentally disarm inflight.

How fast the multicopter falls or looses attitude control depends on the ESC settings... If Damped-Light is not used, and brake_on_stop is turned off. The quad will practically auto-rotate for a time... But BLheli32 Damped-Light is ON by default and very beneficial to have active.

@breadoven
Copy link
Collaborator Author

I'm not sure if you've read my post here - #8736 (comment) This method works well for both hovering or forward flight... But ANGLE mode can also be coupled with ALTHOLD mode for that couple of seconds after rearming. Not just to regain attitude level stabilization, but to prevent an accelerated free fall on heavy multicopters. This may seem a little over kill. But disarming in flight is not something we plan to do. And not all multicopters fall flat when they start to free fall. From questions on Discord. It appears most of the MC INAV builds are based around cruisers and long range, more than freestyle.. Meaning that many of these people may not have the fastest reactions to catch a free falling multicopter, if they accidentally disarm inflight.

How fast the multicopter falls or looses attitude control depends on the ESC settings... If Damped-Light is not used, and brake_on_stop is turned off. The quad will practically auto-rotate for a time... But BLheli32 Damped-Light is ON by default and very beneficial to have active.

Makes sense and probably necessary to stop the quad shooting off in some random direction when it does rearm. Will have a look at adding it.

I've also added something to check if the quad drops after disarm which looks like it might work. Just checks vertical velocity at least 1s after disarm. If it's > -1m/s it cancels the emergency rearm. Can be ground tested but flight testing might be a bit tricky.

Of course the best solution to inadvertent disarm is to have a dedicated arming switch on transmitters that is deliberately placed away from the other switches, somewhere where your fingers wouldn't normally wander, but still easy to get to quickly. Somewhere in the middle at the top possibly with some physical protection to stop it getting knocked whilst still being easy to operate with a finger. None of the manufacturers do this as far as I can see. I relocate one of the switches if need be so it's away from the others but still easy to use when you need to ... no more accidental disarms.

@Jetrell
Copy link

Jetrell commented Aug 23, 2023

Its interesting that most accidental disarms occur with fixed wings, more so than multicopters.. I generally think this is because fixed wings often have all the RC switches, knobs and channels dedicated to a function or operation. And when people get in a fluster, there main go to switches are Disarm and RTH.

I very rarely accidentally disarm a quad in flight. But the arm switch needs to be prominent and easy to access if needs be... And if a disarm does happen by long range pilots, at altitude. Its a long fall to the ground.

I've also added something to check if the quad drops after disarm which looks like it might work. Just checks vertical velocity at least 1s after disarm. If it's > -1m/s it cancels the emergency rearm.

Could this be a problem ? It doesn't take long for a disarm free fall to break 4km/h. And it may take the pilot a second or so to work out what he has done, before rearming... Which would leave a larger multicopter in the same predicament, as if there was not emergency rearming.
I feel the best advantage of a multicopter rearm after an accidental disarm, is if it occurs at higher altitudes, e,g 30m+
At these altitudes the chance of recovery is much greater. And the loss if not being able to rearm, will cause major damage to larger multicopters... I had this happen once in the early days of INAV, at > 100m and the quad was totaled.

For accidental disarming and rearming at low altitudes < 10m if the pilot doesn't have the altitude to recover. This is were the G-shock detector of Betaflight and Arducopter work well. To auto disarm on impact, even after a midair rearm.

@breadoven
Copy link
Collaborator Author

I've also added something to check if the quad drops after disarm which looks like it might work. Just checks vertical velocity at least 1s after disarm. If it's > -1m/s it cancels the emergency rearm.

Could this be a problem ? It doesn't take long for a disarm free fall to break 4km/h. And it may take the pilot a second or so to work out what he has done, before rearming... Which would leave a larger multicopter in the same predicament, as if there was not emergency rearming. I feel the best advantage of a multicopter rearm after an accidental disarm, is if it occurs at higher altitudes, e,g 30m+ At these altitudes the chance of recovery is much greater. And the loss if not being able to rearm, will cause major damage to larger multicopters... I had this happen once in the early days of INAV, at > 100m and the quad was totaled.

For accidental disarming and rearming at low altitudes < 10m if the pilot doesn't have the altitude to recover. This is were the G-shock detector of Betaflight and Arducopter work well. To auto disarm on impact, even after a midair rearm.

This check cancels the emergency rearm only if the vertical velocity doesn't exceed -1 m/s after 1 second, i.e. the quad hasn't dropped because something is stopping it ... like the ground. Theoretically after 1 second the freefall velocity would be around 10 m/s. Works OK testing on the ground after a simulated takeoff and landing that wasn't hard enough to trigger the landing bump detection, throttle at mid stick. If you rearm within 1 second it arms, after 1 second it doesn't because there's no vertical velocity. To fully test it to ensure it does emergency rearm after 1 second you'd need vertical velocity more than -1 m/s which is tricky unless you disarm in flight. Maybe SITL can check this.

@froqstar
Copy link

What if you accidentally disarm while ascending rapidly, there the momentum may keep you above -1m/s vertical speed for multiple seconds?

@breadoven
Copy link
Collaborator Author

What if you accidentally disarm while ascending rapidly, there the momentum may keep you above -1m/s vertical speed for multiple seconds?

Yes it needs testing or some calcs to check the timings. Or other checks could be added depends how complicated you want to make it. Checking throttle > hover throttle and +ve vertical speed would be useful.

@Jetrell
Copy link

Jetrell commented Aug 26, 2023

I did some testing with a quad today at low altitude over thick grass and hay.. There are a couple things to look at.

  • ANGLE mode stabilization for inflight rearm, is always activated on power-up.. Then once the FC is armed the first time, while on the ground. It stays in ANGLE mode for 5s before reverting back to the flight mode selected by the switch.
    It possibly needs to disregard it on the first arming, and/or the throttle being in the low position.

  • There is a tiny window when the multicopter moves through zero vertical velocity change.. It didn't rearm once.
    I noticed you added +ve and -ve vertical speed..

Checking throttle > hover throttle

But it didn't appear you added your throttle check suggestion ? It may fix the problem.

@breadoven
Copy link
Collaborator Author

  • ANGLE mode stabilization for inflight rearm, is always activated on power-up.. Then once the FC is armed the first time, while on the ground. It stays in ANGLE mode for 5s before reverting back to the flight mode selected by the switch.
    It possibly needs to disregard it on the first arming, and/or the throttle being in the low position.

Just to clarify: you're saying you connect the battery, then arm for the first time and it ends up in Angle for the 5s after arming ?

  • There is a tiny window when the multicopter moves through zero vertical velocity change.. It didn't rearm once.
    I noticed you added +ve and -ve vertical speed..

Yes it should only cancel the emergency rearm if vertical velocity is between +-1 m/s, i.e. neither dropping or climbing. However, this check only starts 1.5 s after rearming so it will always rearm within the first 1.5s. It's only after 1.5s that it might no rearm if vertical velocity indicates it's not flying. I tested it and it seems to work when static on the ground. I guess the problem here is you can't allow for all possible situations. You could for instance do a full throttle climb, cut the throttle to 0 then disarm. If the quad reaches the top of the climb > 1.5s later at the point you try and rearm with the vertical velocity at 0 then emergency rearming will fail. But this is a pretty unique situation that's unlikely to happen in reality. What was the quad doing when it failed to rearm in your test ... was it climbing when disarmed or just hovering ?

There are no throttle checks as of yet.

@Jetrell
Copy link

Jetrell commented Aug 26, 2023

It was disarmed in slow forward flight with a slow climb.. I'd considered that even a lighter weight 7" in slow forward flight, with that much prop area, could potentially hold altitude for over 1.5s.
In reality, its likely to take most people at least a second or so before they even work out whats gone wrong... Its easy when testing, because its not an accidental situation.

You could for instance do a full throttle climb, cut the throttle to 0 then disarm. If the quad reaches the top of the climb > 1.5s later at the point you try and rearm with the vertical velocity at 0 then emergency rearming will fail.

I agree, freestyle maneuvers are always going to be impossible for a flight detector to predict... But I think a throttle check would increase reliability, for the way most users fly... Anyone cruising or doing long range flying is unlikely to lower the throttle back to idle until they land.

@breadoven
Copy link
Collaborator Author

It was disarmed in slow forward flight with a slow climb.. I'd considered that even a lighter weight 7" in slow forward flight, with that much prop area, could potentially hold altitude for over 1.5s. In reality, its likely to take most people at least a second or so before they even work out whats gone wrong... Its easy when testing, because its not an accidental situation.

Ah, yes I was wondering about that ... sounds like it's acting like an autogyro which could maintain lift due to the forward speed and air wash over the props. Looks like a speed check is required to account for this although without a pitot this might also get it wrong at times.

Alternatively you could just scrap this check if the rearm time window is limited to 5s. I was thinking you could change the 5s to a setting up to perhaps 30s in which case inadvertent rearm on the ground would be a problem. As you say, it does take a few seconds to twig you've hit the disarm switch ... so perhaps 5s is marginal.

@Jetrell
Copy link

Jetrell commented Aug 27, 2023

Just to clarify: you're saying you connect the battery, then arm for the first time and it ends up in Angle for the 5s after arming ?

Sorry, I over looked answering this question..
If the flight mode switch is in the AIR mode position. It ignores that, and powers up in ANGLE mode.
Only after the craft is armed, does it finally switch out of ANGLE, and back to AIR mode after the 5s have expired.

@breadoven
Copy link
Collaborator Author

breadoven commented Aug 27, 2023

Just to clarify: you're saying you connect the battery, then arm for the first time and it ends up in Angle for the 5s after arming ?

Sorry, I over looked answering this question.. If the flight mode switch is in the AIR mode position. It ignores that, and powers up in ANGLE mode. Only after the craft is armed, does it finally switch out of ANGLE, and back to AIR mode after the 5s have expired.

I've redone the logic for this so it should work better and possibly fix the above issue (wasn't sure why it was happening with the old logic). It should work the same way but it now checks for horizontal speed and also gyro rates. I'm thinking gyro rates should be completely different for a quad on the ground, pretty well 0, and a quad that disarmed in flight, probably quite high given it no longer has the motors keeping it stable. It still uses the 5s re-arming window but given the way it now works this could possibly be scrapped completely if the in flight check is reliable enough. (still need to commit the change)

@Jetrell
Copy link

Jetrell commented Aug 28, 2023

I tested it again under controlled conditions.. This method appears to be a nice balance.
No issue now with it being in ANGLE mode on power-up. And it appears to rearm and level stabilize after rearming, so far.

I haven't tried disarming it at altitude or at a higher speed.. It just feels too risky ATM.
What I'm thinking about doing, is a print made of TPU. That is a spherical cage, that a 3" quad is mounted into.. This should provide protection from a hard impact with ground if it doesn't rearm... But it won't be finished for a while yet.

@Jetrell
Copy link

Jetrell commented Sep 6, 2023

@breadoven I ran some test with both Fixed wing and Multicopter.

Quad inflight rearming.

  • An ascending or descending disarm. Allows for an instant rearm, with ANGLE mode quickly regaining level stability after the quad starts to fall off axis... In tests, rearmed was between 1 to 2 seconds after disarming.
  • When in forward flight in ACRO mode, and then disarming. This will obviously cause the quad to quickly loose attitude stability.. But rearm worked well, catching the fall and level stabilizing it also.
  • After landing and disarming. IF an in flight rearm has occurred. The quad requires a few seconds for the landing detector to register its NOT flying, before the throttle could be accidentally left above zero, and rearmed on the ground, without it taking off.
    But if an inflight rearming NEVER occurs.. Then safety checks on the ground are always instantaneous. And it will not arm and launch if the throttle is accidentally left above zero.
    You seem to have a good balance between ground safety, and the certainty that the flight detector will always rearm..

Fixed wing inflight rearming.

  • The inflight rearming worked... Without Permanently enabled launch mode starting again after the rearm. (very nice)
  • But when disarming did occur, the FC would revert back to MANUAL mode. rather than ACRO mode.. Manual mode could cause problems in windy conditions ?
  • In the moments after landing. The landing detector prevented rearming IF the throttle is accidentally left high. Providing good safety.. With the override flight safety timer doubling up on this.

I tested disarming in Acro, Angle, Cruise, CH, RTH and WP.. With all working as expected.

Besides ACRO on a fixed wing when its disarmed.. I have two other recommendations that would help.

  • It would be good if the Arming stats information, only appeared for 1s, after and inflight rearm.. Five seconds as with ground arming, blocks out the OSD information for too long IMO.
  • It would also be beneficial for users who use Programming logic functions like STICKY etc.. If an inflight disarm and rearm did NOT reset all the FLAG conditions.. It can cause havoc with more complex logic.

All in all, Great work !

@breadoven
Copy link
Collaborator Author

@Jetrell

After landing and disarming. IF an in flight rearm has occurred. The quad requires a few seconds for the landing detector to register its NOT flying, before the throttle could be accidentally left above zero, and rearmed on the ground, without it taking off.

Do you mean it took a few seconds to detect a landing, or just that it was possible to emergency rearm for a few seconds after landing, something that wasn't possible if no in flight rearm had occurred ?

But when disarming did occur, the FC would revert back to MANUAL mode. rather than ACRO mode.

Was this on the ground, in flight or both ? Not sure how this could happen unless Manual mode was activated in some way. Nothing in this change should affect how Manual mode works. Guess I can check it again myself on HITL.

And I agree about the arming screen. I'll see how easy it is to reduce the display duration. Not sure about the Programming logic functions, sounds a bit more complicated to prevent problems there. At the end of the day if you mistakenly disarm in flight being able to recover the model should be the main consideration.

Thanks for testing again. Did you use the crash cage on the quad ?

@Jetrell
Copy link

Jetrell commented Sep 6, 2023

Do you mean it took a few seconds to detect a landing, or just that it was possible to emergency rearm for a few seconds after landing, something that wasn't possible if no in flight rearm had occurred ?

It detected the disarm instantly in flight, which is good... It was the second part you asked above.. Which I thought was fine..

Was this on the ground, in flight or both ? Not sure how this could happen unless Manual mode was activated in some way. Nothing in this change should affect how Manual mode works. Guess I can check it again myself on HITL.

It was inflight.. I didn't actually ground test the airplane first.. This plane doesn't have a logger.. And unfortunately the Arming screen covers the mode selection on the OSD too,. So I can't look at that..
But this plane wasn't precisely tuned in Manual mode.. So it would dive to the right a little in Manual mode.. Which was exactly what it did when the aircraft was disarmed in flight.. I test it dozens of times with the same result. So it was easy to come to this conclusion.

Thanks for testing again. Did you use the crash cage on the quad ?

No problem.. The TPU cage was a little heavy for the poor old quad.. But fortunately your a clever guy, and got the flight detector coding correct.. So it wasn't needed.

@breadoven
Copy link
Collaborator Author

breadoven commented Sep 6, 2023

I made a change to prevent emergency rearm working if a landing has been detected, something that definitely shouldn't be possible.

The OSD arming screen issue is caused by Safehomes which increases the display time from 1.5s to 4.5s. It's not easy to change this so given accidental disarm isn't something that will happen very often I don't think it's worth fixing.

@MrD-RC
Copy link
Collaborator

MrD-RC commented Sep 7, 2023

I made a change to prevent emergency disarm working if a landing has been detected, something that definitely shouldn't be possible.

The OSD arming screen issue is caused by Safehomes which increases the display time from 1.5s to 4.5s. It's not easy to change this so given accidental disarm isn't something that will happen very often I don't think it's worth fixing.

I’m currently looking at arming screens for a different PR. In that PR, I’m allowing for the arm screen time to be set in CLI. So having a short override for an inflight rearm would be useful.

There could be a REARMED_IN_FLIGHT flag set upon inflight rearm and cleared at disarm. It would be simple to check that and handle the arming screen appropriately. This way, the arming screen could be:

  • shown for a short time
  • an alternative armed screen
  • not shown at all, and an !ARMED! system message used

This flag could also be used to decide if the programming framework is reset or not. I think the more things that continue as if the flight hadn’t been interrupted, the better.

@Jetrell
Copy link

Jetrell commented Sep 10, 2023

Not sure how this could happen unless Manual mode was activated in some way. Nothing in this change should affect how Manual mode works. Guess I can check it again myself on HITL.

I had a look over this again. And used the analogue DVR.
I noticed at the moment of disarming, before the STATS cover the selected mode the craft was in.. The actual mode stayed as it had been selected by the mode switch. Even though the plane instantly started to loose attitude control on the pitch axis (because of the poor servo trim on this airplane)... So it must have reverted to Manual in the code somewhere.. Or something like the stabilization PID controller has been disabled at disarm.

Capture1

@MrD-RC
Copy link
Collaborator

MrD-RC commented Sep 10, 2023

Also, what would happen to the home location if an in-flight re-arm happens? I believe it shouldn't be changed to the in-flight re-arm position, instead, it should remain at the original first arming (before takeoff) coordinates.

Rearming in flight will not have any effect on the home point. It hasn’t since about version 2.0; when home position reset was defaulted to first arm. You would need to disconnect the battery. Then the home position will be set on the next arm.

@breadoven
Copy link
Collaborator Author

You can set the Home position to update every arm if you select that option so this would be an issue. Not sure why you'd want to change Home every arm though and I'd have thought most people stick to the default of 1st Arm only.

The only reason Manual mode might become active without the mode being selected is if the sensors are calibrating. There's no reason for the sensors to recalibrate on arming so I can't see how Manual could have become active during an in flight rearm.

Having a REARMED_IN_FLIGHT flag would be the easiest way of handling things although Arming flags seem to be down to 2 bits and one of them seems to be reserved. The only other option would be a general state flag which is probably OK. Although this wouldn't help in all cases because some things get reset on disarm.

@rmaia3d
Copy link
Contributor

rmaia3d commented Sep 11, 2023

You can set the Home position to update every arm if you select that option so this would be an issue. Not sure why you'd want to change Home every arm though and I'd have thought most people stick to the default of 1st Arm only.

The only reason Manual mode might become active without the mode being selected is if the sensors are calibrating. There's no reason for the sensors to recalibrate on arming so I can't see how Manual could have become active during an in flight rearm.

Having a REARMED_IN_FLIGHT flag would be the easiest way of handling things although Arming flags seem to be down to 2 bits and one of them seems to be reserved. The only other option would be a general state flag which is probably OK. Although this wouldn't help in all cases because some things get reset on disarm.

Exactly! On fixed wing it indeed doesn't make much sense to change the home position on every arm, but on multi-copters it does.

For example, you are in a flying field with some people, cars, obstacles nearby your first arm position. You can arm, briefly fly some distance to a clearer part of the field, land, disarm and arm again so that "new" home position is the actual return point in case of an RTH. By doing this you reduce the risk of the craft hitting something or someone during the automated landing sequence.

@MrD-RC
Copy link
Collaborator

MrD-RC commented Sep 11, 2023

Exactly! On fixed wing it indeed doesn't make much sense to change the home position on every arm, but on multi-copters it does.

For example, you are in a flying field with some people, cars, obstacles nearby your first arm position. You can arm, briefly fly some distance to a clearer part of the field, land, disarm and arm again so that "new" home position is the actual return point in case of an RTH. By doing this you reduce the risk of the craft hitting something or someone during the automated landing sequence.

This is what the home reset mode is for. No need to risk an in flight disarm resetting the home point. You can fly to where you want the home point. Trigger the home reset mode. You don’t even need to land, let alone disarm. Then carry on with your flight. Best of both worlds.

@rmaia3d
Copy link
Contributor

rmaia3d commented Sep 16, 2023

Exactly! On fixed wing it indeed doesn't make much sense to change the home position on every arm, but on multi-copters it does.
For example, you are in a flying field with some people, cars, obstacles nearby your first arm position. You can arm, briefly fly some distance to a clearer part of the field, land, disarm and arm again so that "new" home position is the actual return point in case of an RTH. By doing this you reduce the risk of the craft hitting something or someone during the automated landing sequence.

This is what the home reset mode is for. No need to risk an in flight disarm resetting the home point. You can fly to where you want the home point. Trigger the home reset mode. You don’t even need to land, let alone disarm. Then carry on with your flight. Best of both worlds.

Oh!! I wasn't aware of this feature!! It indeed sounds great!!! For sure, best of both worlds. Awesome!

@breadoven
Copy link
Collaborator Author

breadoven commented Sep 27, 2023

Added a flag to indicate emergency in flight rearming which is used to prevent the home position and reference altitude resetting, logic conditions resetting and also reduces the arming screen display time to 1/3 of the normal time, i.e. 0.5s just to give brief indication craft has rearmed. The flag resets 1s after arming once it's done its job.

Preventing the home position and altitude reference from resetting isn't easy because they're normally constantly reset when disarmed (depending on the reset setting used). To avoid this causing a problem during an emergency rearm the logic has been changed so home position and reference altitude are constantly reset only before the first arm but for subsequent rearms they are reset immediately after arming. This happens within a fraction of a second after arming so shouldn't affect things in any obvious way other than altitudes noticeably recalibrating for a second or so. Seems to test OK in HITL.

Edit:
I have noticed a problem with this which is that the emergency rearm only works if it's not possible to rearm normally in flight. So if the criteria to rearm normally are met you can rearm in flight and not use the emergency rearming which means Home and Altitude reference etc resets are not bypassed. Needs more work to get around this issue.

Also noticed Programming/Logic stuff is reset not only on Arm but also on Disarm so the fix here doesn't work since it only works on Arming. Fixing the Disarm reset is more problematic.

@Jetrell
Copy link

Jetrell commented Sep 27, 2023

I have noticed a problem with this which is that the emergency rearm only works if it's not possible to rearm normally in flight. So if the criteria to rearm normally are met you can rearm in flight and not use the emergency rearming which means Home and Altitude reference etc resets are not bypassed. Needs more work to get around this issue.

Also noticed Programming/Logic stuff is reset not only on Arm but also on Disarm so the fix here doesn't work since it only works on Arming. Fixing the Disarm reset is more problematic.

No problem.. Thanks for the heads-up.. I won't test it again until this is sorted.

@breadoven
Copy link
Collaborator Author

The issues mentioned above have been fixed now except for the logic conditions. Can't really see how to fix that unless you don't reset them on disarm. Is this necessary or just a belt and braces reset @DzikuVx ?

I tested the Home position and Altitude reference resets on HITL and it now appears to work as required. Might have also fixed a bug if you had reset Home Each Arm but reset Altitude only on First Arm ... which messes up the OSD MSL altitude display. Changing the reference altitude to gpsOrigin seems to fix this and makes more sense than the Home reference altitude used previously.

@rts18
Copy link

rts18 commented Sep 30, 2023

Can't really see how to fix that unless you don't reset them on disarm.

I see no reason to reset them. Surely a reboot by disconnecting and reconnecting the battery is good enough. When would you ever want to reset your logic states when powered??

In flight disarming also causes a problem with both analogue and digital VTX's reverting to low power mode.
If you happened to be flying at any distance. You will loose video feed. And the HD video MSP OSD. Making it difficult to assess what has gone wrong.

I'm aware that one uses vtx_low_power_disarm and maybe easier to accomplish. While the other uses an MSP flag.
This idea #8727 was suggested. And possibly by modifying it, to prevent the MSP disarming flag from being sent to any device, with-in the rearm timing window, or if flight is detected. Could be a means to prevent HD video systems from dropping to standby power?

@breadoven breadoven added this to the 7.0 milestone Oct 22, 2023
@breadoven
Copy link
Collaborator Author

I think this can be merged now. The outstanding issues regarding Logic conditions resetting and HD VTX low power on disarm can be fixed separately.

@breadoven breadoven merged commit f30c719 into iNavFlight:master Oct 24, 2023
14 checks passed
@DzikuVx DzikuVx added Release Notes Add this when a PR needs to be mentioned in the release notes and removed Testing Required labels Oct 27, 2023
@DzikuVx DzikuVx mentioned this pull request Oct 27, 2023
@rts18 rts18 mentioned this pull request Oct 31, 2023
@breadoven breadoven deleted the abo_emerg_flight_rearm branch November 21, 2023 22:52
@konstkarapan
Copy link

This feature just saved my quad today. Big thanks @breadoven 🫡

@Macianno
Copy link

Macianno commented Oct 21, 2024

I generated some test data for this issue today ;) I turned on landing_bump_detection lastly and it worked nice on bumped ladings, but today it happen when I was still in the air just after back-flip. When I looked in log file there was all conditions met to do this, but when it falling down, i tried to rearm but it was not possible. I wondering if "emergency rearm flag" was cleared if landing_bump_detection triggered disarm? Could this be a reason that I could not rearm in the air? There is LOG file attached and link for DVR (disarm happen around 1:00min of video):

https://drive.google.com/file/d/1T9uLWiTPyu61En0Iby_PLuAP0nXPPb5N/view?usp=sharing

LOG00046.TXT

Hopefully almost nothing happened with my quad... Just right door was broken and little scratches on props when quad hit on the sugar beet after falling from 38m ;)

@breadoven
Copy link
Collaborator Author

@Macianno There is a change for 8.0 that should stop this problem with the G bump detection and would have stopped it in this case, see https://github.com/iNavFlight/inav/pull/10138/files. Only allows G Bump detection to work below 1m/s horizontal velocity which is way below the 12 m/s your quad was doing when it disarmed.

In flight rearm is currently limited to disarming by switch only. This is the only way in flight disarm should happen if everything else is working as expected.

@Macianno
Copy link

Macianno commented Oct 22, 2024

@breadoven Thank you for this explanation. Can you explain to me how land_detect_sensitivity works? If I change it to 4 (lower sensitivity) will affects velocity threshold or how it works? I looked to file with code, that you give me a link and it looks like only velocity and gyro is taken for this settings but I am not sure if I am right... Z-axis G-force threshold is constant? I am still learning inav code structure to have better imagination how it works. Thank you in advance :)

@breadoven
Copy link
Collaborator Author

breadoven commented Oct 22, 2024

nav_land_detect_sensitivity just factors the velocity and gyro thresholds for normal landing detection. It doesn't have any affect on the G-bump detection. The parameters for the G-bump detection are shown in the code, basically Z axis exceeding 2g then falling back below 1g within 0.1s, just hard coded and can't be adjusted because that's what seems to work (most of the time at least).

Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment
Labels
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.

9 participants