mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
Sub: Make ap.land_complete always false
This flag should eventually be removed completely from the code.
This commit is contained in:
parent
577240b8d4
commit
39fd3054c9
@ -24,11 +24,11 @@ void Sub::update_land_and_crash_detectors()
|
||||
// called at MAIN_LOOP_RATE
|
||||
void Sub::update_land_detector()
|
||||
{
|
||||
if(barometer.num_instances() > 1 && barometer.get_altitude() > LAND_END_DEPTH && ap.throttle_zero) {
|
||||
set_land_complete(true);
|
||||
} else {
|
||||
// if(barometer.num_instances() > 1 && barometer.get_altitude() > LAND_END_DEPTH && ap.throttle_zero) {
|
||||
// set_land_complete(true);
|
||||
// } else {
|
||||
set_land_complete(false);
|
||||
}
|
||||
// }
|
||||
}
|
||||
|
||||
void Sub::set_land_complete(bool b)
|
||||
|
Loading…
Reference in New Issue
Block a user