ardupilot
ardupilot copied to clipboard
Copter: Land Detector: Include angle checks
This PR fixes #26864 where the aircraft can detect a landing when at full throttle in stabilize and upside down. Now the aircraft will correct detect a crash.
Sorry I didn't explain what is happening here and why this fix works.
The land detector checks that the throttle mix value has dropped to near throttle_mix_at_min as part of the landing checks. To set the throttle mix value to throttle_mix_at_min we have two key checks:
- Angle requested < 15 degrees
- Angle error < 30 degrees
It then sets throttle_mix to throttle_mix_at_min.
The land detector checks to see if throttle_mix is close to throttle_mix_at_min before proceeding but this is not the same as checking that it has been set to throttle_mix_at_min. This check passes all the time with the default settings as throttle_mix_at_min = throttle_mix_at_man.
We are then left in a state where we are able to detect a landing without passing the two checks above.
Why does this fix the problem above? The problem above goes through a number of steps:
- throttle goes high in stabilize
- stabilise correctly detects a take off
- aircraft is inverted and left stationary
- the angle boost takes the throttle to zero
- the land detector checks throttle_mix and finds that it is equal to throttle_mix_at_min and throttle_mix_at_man so it passes
- a landing is detected with a high throttle request
- the takeoff flow of control error is triggered because the aircraft should not have detected a landing
Crash detection:
The crash detection now works correctly because we are not detecting the landing. As Pete says below this is a race and we simply need to not detect a landing to allow the crash detection to work correctly. In this case the aircraft will repeatedly detect a landing and a takeoff meaning the aircraft would never disarm.
Tricky little bugger.
Those checks seem sensible for checking for a successful landing. However, I think that this indirectly fixes the issue. The problem to me seems to be that we cannot reliably infer if we are taking off from flightmode->is_taking_off() in stabilise because that mode doesn't have the user_takeoff flag. I think a more direct fix to the issue would be to bring the has_user_takeoff() check, up to line 56 of land_detector.cpp: https://github.com/ArduPilot/ardupilot/blob/3c8b3be7a730255927d64265bcaf0d98ebb3c0b1/ArduCopter/land_detector.cpp#L56
So it would look something like this:
if (has_user_takeoff(false) && !flightmode->is_taking_off() && motors->get_throttle_out() > get_non_takeoff_throttle() && motors->get_spool_state() == AP_Motors::SpoolState::THROTTLE_UNLIMITED) {
This would mean that we can then only use this check for the modes that support the user_takeoff() function.
@Gone4Dirt,
Thanks for the feedback. This is Leonard's work but this Internal Error and the set-land-complete() after it is quite important because it is essentially an independent check that the flight modes have fulfilled their responsibility to clear the land-complete flag. If we add the "has_user_takeoff" condition then I worry we are basically giving a get-out-of-jail-free pass to those modes that don't "have user takeoff" (which includes Stabilize and Acro)
For reference, each mode has this "has_user_takeoff()" method available and will apparently return true if it will accept a MAVLink command to takeoff to a specified altitude. So even in Loiter and AltHold modes a GCS can send a takeoff command to ask the vehicle to climb to X meters and it will do it without the pilot touching the sticks. You can try it yourself in SITL by doing this:
- start SITL copter
- loiter
- rc 3 1500
- arm throttle force
- takeoff 10
By the way, this PR is failing the Heli autorotation autotest which I'm sure we're going to need to look into. A random guess is that during auto rotation its not landing flat and so the new landing-detector conditions are not being met.
FAILED STEP: test.Helicopter at Tue Apr 23 06:40:59 2024 Failure Summary: test.Helicopter: AutoRotation (Check engine-out behaviour) (Failed to DISARM within 120.000000s) (see /tmp/buildlogs/HeliCopter-AutoRotation.txt) (duration 10.23026156425476 s) FAILED 1 tests: ['test.Helicopter']
The new checks added here are the same as those in update_throttle_mix
here:
https://github.com/ArduPilot/ardupilot/blob/c9f7a3c03d7ef58e328c7ebbe6b4be0d8b030394/ArduCopter/land_detector.cpp#L230-L235
So if they are set then throttle mix will also be set to max, so the existing update_land_detector
check for throttle_mix_at_min
will fail. I don't think there will be any change in behavior in none manual throttle modes? The only change would be in a manual throttle mode with throttle at zero? That would be this case in update_throttle_mix
:
https://github.com/ArduPilot/ardupilot/blob/c9f7a3c03d7ef58e328c7ebbe6b4be0d8b030394/ArduCopter/land_detector.cpp#L222
This PR fixes #26864 where the aircraft can detect a landing when at full throttle in stabilize and upside down. Now the aircraft will corret detect a crash.
I'm a little confused by this description. I would have expected full throttle in stabilize to result in throttle mix man so the throttle_mix_at_min
would not pass and landing would never be detected.
You mention that the aircraft now correctly detects a crash, but there is no change to crash detection here? Maybe there is a race and currently landing detection triggers first? So by preventing the landing detection the crash detection will trigger after slightly more time?
The TLDR is that I would have expected the existing throttle mix check to protect against this case.
Those checks seem sensible for checking for a successful landing. However, I think that this indirectly fixes the issue. The problem to me seems to be that we cannot reliably infer if we are taking off from flightmode->is_taking_off() in stabilise because that mode doesn't have the user_takeoff flag. I think a more direct fix to the issue would be to bring the has_user_takeoff() check, up to line 56 of land_detector.cpp:
https://github.com/ArduPilot/ardupilot/blob/3c8b3be7a730255927d64265bcaf0d98ebb3c0b1/ArduCopter/land_detector.cpp#L56
So it would look something like this:
if (has_user_takeoff(false) && !flightmode->is_taking_off() && motors->get_throttle_out() > get_non_takeoff_throttle() && motors->get_spool_state() == AP_Motors::SpoolState::THROTTLE_UNLIMITED) {
This would mean that we can then only use this check for the modes that support the user_takeoff() function.
I finished the PR description and I explain there why this is actually a landing detection problem. In this case the takeoff is being correctly detected in both Stabilize and by the flow of control error.
The new checks added here are the same as those in
update_throttle_mix
here:https://github.com/ArduPilot/ardupilot/blob/c9f7a3c03d7ef58e328c7ebbe6b4be0d8b030394/ArduCopter/land_detector.cpp#L230-L235
So if they are set then throttle mix will also be set to max, so the existing
update_land_detector
check forthrottle_mix_at_min
will fail. I don't think there will be any change in behavior in none manual throttle modes? The only change would be in a manual throttle mode with throttle at zero? That would be this case inupdate_throttle_mix
:https://github.com/ArduPilot/ardupilot/blob/c9f7a3c03d7ef58e328c7ebbe6b4be0d8b030394/ArduCopter/land_detector.cpp#L222
This PR fixes #26864 where the aircraft can detect a landing when at full throttle in stabilize and upside down. Now the aircraft will corret detect a crash.
I'm a little confused by this description. I would have expected full throttle in stabilize to result in throttle mix man so the
throttle_mix_at_min
would not pass and landing would never be detected.You mention that the aircraft now correctly detects a crash, but there is no change to crash detection here? Maybe there is a race and currently landing detection triggers first? So by preventing the landing detection the crash detection will trigger after slightly more time?
The TLDR is that I would have expected the existing throttle mix check to protect against this case.
Sorry Pete, I addressed your questions in the description above. In short you are correct with everything you said but there are two additional points
- throttle_mix_at_min = throttle_mix_at_man.
- angle boost means the output throttle is zero.
I have confirmed the failing test is due to a problem with the heli autorotation code rather than the landing detector. We should not be detecting a landing with a lean angle of 50 degrees:
@bnsgeyer What do you think?
@lthall first of all, I did not spend much time reading thru all of the posts but this PR has me concerned with inverted flight for heli which currently doesn’t have a test in the autotest.
As for the failing autorotation test, this may be due to the fact that I am only looking for the declaration that it is in glide phase. The code as it currently stands doesn’t have the ability to autonomously complete the landing. So I was probably just letting it hit the ground and declare landed to stop the test. I will need to look into this further.
@lthall first of all, I did not spend much time reading thru all of the posts but this PR has me concerned with inverted flight for heli which currently doesn’t have a test in the autotest.
As for the failing autorotation test, this may be due to the fact that I am only looking for the declaration that it is in glide phase. The code as it currently stands doesn’t have the ability to autonomously complete the landing. So I was probably just letting it hit the ground and declare landed to stop the test. I will need to look into this further.
There are a number of other checks but yes, this PR should make that safer.
I had a bit of a look at the autorotation autotest. The test is failing because the aircraft it not disarming after landing. But I am really not sure why this PR is causing it to not disarm though. Desired and actual roll and pitch angles are all close to 0 and the aircraft is neither climbing or descending. So I don't really see how the changes in this PR are causing this to fail.
@lthall I fixed the AutoRotation autotest. For some reason the autorotation mode caused the aircraft to pitch forward on landing. The changes that I pushed to your branch will fix the test failing. I had to push a second commit to cleanup changes I made to the file for testing it. Anyway, it should pass CI now.
Legend Bill, Thanks!