From 5fe86a657e739a19e2e6b41ecb43cd1dd635b9b0 Mon Sep 17 00:00:00 2001 From: Randy Mackay Date: Sun, 27 Apr 2014 15:38:56 +0900 Subject: [PATCH] Copter: land_do_not_use_GPS has no return value --- ArduCopter/control_land.pde | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/ArduCopter/control_land.pde b/ArduCopter/control_land.pde index 13529add24..8935776675 100644 --- a/ArduCopter/control_land.pde +++ b/ArduCopter/control_land.pde @@ -176,7 +176,7 @@ static bool update_land_detector() // land_do_not_use_GPS - forces land-mode to not use the GPS but instead rely on pilot input for roll and pitch // called during GPS failsafe to ensure that if we were already in LAND mode that we do not use the GPS // has no effect if we are not already in LAND mode -static bool land_do_not_use_GPS() +static void land_do_not_use_GPS() { land_with_gps = false; }