Closed theArchLadder closed 8 years ago
It's your machine equipped with sonar? Blackbox logs of the event?
Yes, you are right, auto disarm behavior needs improving. Thanks for reporting the issue!
No, no sonar. There are a bunch of RTH in the blackbox log i posted on the fly-away issue: https://www.dropbox.com/s/hcxawi62zerswpy/blackbox_log_2016-05-13_115326_RTH-backwards-fly-away?dl=0
It's all a big mess but at least it's something. i might make a dedicated RTH bblog later. I don't think i have a log of the "disarm in air incident".
What are you interested to look at in the blackbox log?
My English is not so good. I have the same issue with my Quad. With "disarm on landing on" the Quad falls from the sky over Homeposition. When switching "disarm on landing off" then landing is fine. Unfortunately no Log but in Failsafe RTH the Quad everytime disarm in the Air over the Homepoint and here is a Log present. I have a XJ470 Build with Sonar, Drotek M8NXXL.SPRF3,Naze32 acro,KISS 30A and 4S. https://onedrive.live.com/redir?resid=5B3CE3F4E300B014!258&authkey=!AIsB8S_UmwfYqBE&ithint=folder%2c](url) The first Log 1/20 is on the Ground and the second 7/20 from fligth to Home.
@Urass Thanks for reporting! For now, you can change nav_mc_min_fly_thr to a lower setting, have it at least 100 below your hover throttle, perhaps even lower just to be safe. The only thing that will happen if this value is to low is that it takes some time from when the quad has landed until it disarms.
@digitalentity What do you think about my idea about waiting until vertical speed has been >25cm/s before starting the "have we landed"-logic, would it be fairly easy to implement? I also think we should lower the default for nav_mc_min_fly_thr, how low can we go?
I just looked at @Urass blackbox log, looks like that quad has a hover throttle of around 1500, very weird that it disarmed in the air then...?
I've disabled sonar with auto disarm on landing after a similar experience. Sonar reads 7cm at 16.5m baro alt ... disarm during initial landing phase. Surprising little damage.
@stronnag Was real altitude around 16.5m? Sounds scary that the sonar gives a wrong value rather than no value...
https://github.com/iNavFlight/inav/blob/master/src/main/flight/navigation_rewrite_multicopter.c#L487 Only the sonar is used If sonar is available, this does not sound safe. I think it should at least also check minimalThrust...
Log file: http://seyrsnys.myzen.co.uk/inav_disarm_16.5/LOG00180.TXT, index 2.
Site is c. 19m above MSL, GPS Alt 36m, baro alt 16.5m. I was shocked by (a) it falling from the sky and (b) the lack of damage, 1 (of 4) landing gear and 1 (of 4) 12mm carbon tube arms broken. The epoxy doctor had it flying the next day, without SONAR. The machine had previously performed multiple flawless SONAR assisted landings.
And my b0rken quad agrees, SONAR should confirm landing based on kinematics, not define it.
@stronnag Thanks, that log was interesting, i'm suprised of how terrible that sonar graph look! Very noisy! I thought the sonar sensor was much better than this... Looks like the sonar should give a -1 value when it cant read altitude, but this feature does not seem reliable.
My take-away is that the sonar can not be trusted by itself like it is now, the question is how the logic should work... Should auto-disarm even use the sonar?
I'm not sure why the sonar was so bad that day (prior logs are much more sane). We certainly need to be able to cope with such poor sonar, because you don't know it's happening until you get to pick up the pieces.
@Urass sonar reads 4-6cm all the time when out of range, i guess it's picking up some weak echo from the frame...
It seems very hard to determine if quad has landed or is higher than sonar range. We could do something like "use sonar if baro < sonarRange"... But what if the baro drifts more than the sonar range? Sonar does not seem that useful for land-detection imho...
Me and @stronnag discussed this on IRC.
One thought was to reduce/skip the timeout, but the same problem applies here, when the descent starts, vertical and horizontal velocity is ~0cm/s and throttle can be below nav_mc_min_fly_thr. So if the baro is out of range and reads 1-10cm the copter will disarm in the air if we don't have that 2000ms timeout.
One could try to use the sonar as extra safety against false positives, but from the logs posted here it looks like the sonar reading can be noisy, in that case we might never get small enough readings for 2000ms and the copter would never disarm.
I hope to be proven wrong here, but as far as i can tell the sonar is not useful in this case.
Idea: keep current code instead of disarming just disable I and D values. Then after a timeout of another 5000ms disarm motors if all the criteria is still met?
That way if it reads a false landing it only gets a bit unstable in the air, and will regain full PID stability when defend rate go up.
And if its landed it doesn't matter since it won't wind up.
Not a bad idea actually, sounds like a good safety feature to have at least during development of this! I don't think we want to disable D-term, but we would have to disable I-term as you said, and at least pos_p and posr_i, or perhaps just disable poshold all together.
Disable poshol all together, but also restrain regular PIDs so they won't grow if the quad is on ground.
...Or we could just sound the buzzer instead of disarming while we are debugging this, since we have to solve those problem with windup etc anyway.
I was actually talking about using it permanently.
Because: It may be a good preparation to do while making sure it's landed. If it happens in air nothing serious happens. And when it happens when it's already landed it may be a good step while waiting to be sure it's absolutely landed.
The problem is that with the current logic, it can take some time between touchdown and disarm because:
And after those two are okay, there is still a timeout before disarm So during this time there can be so much windup that the copter tips over (that has happened for me multiple times). We could reduce that timeout but it could still take a few seconds from touchdown to disarm, so we have to solve that windup anyway, and if we solve that there is really no need to disarm fast so we can play it safe, and by then your idea would not be as needed anymore.
Not sure if you suggest to do a controlled crashed landing or a gentle descent with your idea? Either way it will be bad if it activates in the air, the wind will start to blow it away, it could move far away before it lands and it will land with sideways velocity, that will be bad...
I'm still not saying it's a bad idea, it does sound like a nice extra safety feature. I'm just saying we should not allow a more risky "have we landed" logic because we have this feature.
Really dont think you understood me right.
As I read there are 2 issues with todays version.
Issue 1. It winds up on ground. (Because long to long timer allowing PIDs to grow over time) Issue 2. It can detect false landing. (Because to short timer before acting.)
My proposed version would fix both.
Stage 1, Dont grow PIDs. Stage 2, Disarm.
Why it solves issue 1: You can use even shorter timer to detect "first stage" of landing that simply dont allow PIDs to grow. If it detects that is actually are descending it will abort and continue its descend.
Why it solves issue 2: You can use longer timer before disarming because PIDs are not allowed to grow and you dont get flip overs etc, so got no hurry to disarm.
But if would know where to look I would look at example Ardupilot and see how they are doing it.
Issue 1: the timeout is only 1000ms, as i said before, throttle<min_fly and velocity<25cm/s takes a few second from touchdown until they are true, so reducing the timeout won't solve the problem.
Issue 2: Well, if you use sonar, yes. I don't have any sonar and after i reduced min_fly setting i have not had a single disarm-in-air accident, so it is reliable in that sense. with lower min_fly default, a "wait until >25cm/s" and perhaps a little bit longer timeout i would think this should be very reliable.
What exactly do you mean by "Dont grow PIDs"? We need those while the copter is in the air! We have no use for your proposed stage if it doesn't work in the air.
AFAIK @digitalentity based this code on Ardupilot.
EDIT: Sorry, looks like timeout is 2 seconds, still short thougt, my point still stand i think.
Possible bug found! On the first iteration the timeout counter reads 2513 milliseconds, this was true on 2 landing attempts. If all conditions are true on the first iteration, and they are if min_fly is set to high, then the timer is never reset and we can have an instant disarm! I suspect this is what happened for me! I doubt my throttle was 100 below hover for more than 2 seconds.
EDIT: I think this bug affects sonar users too, both of you have <10cm readings sometimes on the sonar, and with this bug that will give instant disarm i think...
resetLandingDetector();
sets landingTimer = micros();
and is called from here:
https://github.com/iNavFlight/inav/blob/master/src/main/flight/navigation_rewrite.c#L923
I have the NAV_STATE_RTH_3D_HOVER_PRIOR_TO_LANDING .timeoutMs = 2500,
So i guess this has something to do with the bug, the landingTimer gets resets, but then it takes 5000ms, or in my case 2500ms before it is used for the first time. So the landingTimer will be >timeout on the first iteration of isMulticopterLandingDetected()
Not sure how to fix this...
Please keep this issue open as that pull request only attempts to improve one small thing of this topic.
Changes just made to the landing detection in master branch:
TODO
@theArchLadder yes, there is a bug with landingTimer reset. I'll address it soon.
Awesome! I just came up with an idea for replacing min_fly to get rid of the "user problem" with that. I'll start working on that later and we will see if i come up with anything that works :)
Perhaps @DzikuVx would like to make that accelerator false-positive-detector? I think it's a good idea, but i'm not sure how to implement that!
Could we have one or two blackbox variables for this? Would they take up data all the time or only when the landing phase is active?
Would be great to review a few different copters to fine-tune the code...
What data do you want to log?
Well, idk yet, this is what i am logging now:
navDebug[0] = *hasHadSomeVelocity*1 + minimalThrust*2 + !verticalMovement*4 + !horizontalMovement*8;
navDebug[1] = (currentTime - *landingTimer) / 1000;
And perhaps some more stuff, as i said before i'm working on replacing the need for min_fly.
Do they take up data all the time though? Seems a bit wasteful in that case. But i think it would be a good idea to have these if they only take up data on the blackbox during the landing phase.
I do realize they are a bit redundant, it is possible to figure out from the existing variables and the settings, but this would make it easier to debug and improve landing detection as this is flown on different copters.
I was out flying my quad and some guy walking his dog came up and was very impressed with my quad. I told him "look, it can even fly home and land by itself!"... My quad went home, and then decided to disarm 5 meters up in the air and crash right in front of us... I don't think he was impressed anymore! Lets improve this!
From a previous @digitalentity post on RCGroup:
It also looks like these conditions has to be true for 2000 milliseconds. (i think it was 1000 before?).
I have not had any more disarms in the air after lowering nav_mc_min_fly_thr, but it still seems risky to only rely on that setting! At the moment the descent start, the vertical speed is 0cm/s, and the throttle is reduced a lot to get to 200cm/s, so how about waiting until vertical speed has been >25cm/s? I think this would make things safer because we would not only rely on just one condition at first.
As for behavior on ground: Often there is a lot of windup before the copter disarms, sometimes so much that the copter tips over. My guess is that this windup is both from rate-I-term and posr_* trying to adjust the position Very small difference in motor speed is needed during descent so perhaps we could simply limit motor speed difference so we don't get that windup on the ground. A alternative solution would be to not care about position, only try to keep horizontal velocity at zero, the rate-i-term windup still remains though.
Thoughts?