From 42c202a08ff3acb76aaa6f93a4a03a5ce10cbe07 Mon Sep 17 00:00:00 2001 From: Randy Mackay Date: Sat, 30 May 2015 17:31:14 +0900 Subject: [PATCH] Copter: move set_land_complete_maybe to landing_detector.cpp --- ArduCopter/AP_State.cpp | 15 --------------- ArduCopter/land_detector.cpp | 13 +++++++++++++ 2 files changed, 13 insertions(+), 15 deletions(-) diff --git a/ArduCopter/AP_State.cpp b/ArduCopter/AP_State.cpp index d3fa4a0042..7ce40dd41b 100644 --- a/ArduCopter/AP_State.cpp +++ b/ArduCopter/AP_State.cpp @@ -96,21 +96,6 @@ void Copter::set_failsafe_gcs(bool b) // --------------------------------------------- -// set land complete maybe flag -void Copter::set_land_complete_maybe(bool b) -{ - // if no change, exit immediately - if (ap.land_complete_maybe == b) - return; - - if (b) { - Log_Write_Event(DATA_LAND_COMPLETE_MAYBE); - } - ap.land_complete_maybe = b; -} - -// --------------------------------------------- - void Copter::set_pre_arm_check(bool b) { if(ap.pre_arm_check != b) { diff --git a/ArduCopter/land_detector.cpp b/ArduCopter/land_detector.cpp index 1c63d0c2ce..33cc07ba98 100644 --- a/ArduCopter/land_detector.cpp +++ b/ArduCopter/land_detector.cpp @@ -77,6 +77,19 @@ void Copter::set_land_complete(bool b) ap.land_complete = b; } +// set land complete maybe flag +void Copter::set_land_complete_maybe(bool b) +{ + // if no change, exit immediately + if (ap.land_complete_maybe == b) + return; + + if (b) { + Log_Write_Event(DATA_LAND_COMPLETE_MAYBE); + } + ap.land_complete_maybe = b; +} + // update_throttle_thr_mix - sets motors throttle_low_comp value depending upon vehicle state // low values favour pilot/autopilot throttle over attitude control, high values favour attitude control over throttle // has no effect when throttle is above hover throttle