From c61412d2d12522928c8917b27f284c8eb1bcaa8d Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Wed, 5 Jun 2019 14:05:41 +1000 Subject: [PATCH] Rover: correct get_distance_to_destination in loiter mode --- APMrover2/mode_guided.cpp | 3 +-- 1 file changed, 1 insertion(+), 2 deletions(-) diff --git a/APMrover2/mode_guided.cpp b/APMrover2/mode_guided.cpp index a40567e9f8..098f016b8b 100644 --- a/APMrover2/mode_guided.cpp +++ b/APMrover2/mode_guided.cpp @@ -121,8 +121,7 @@ float ModeGuided::get_distance_to_destination() const case Guided_TurnRateAndSpeed: return 0.0f; case Guided_Loiter: - rover.mode_loiter.get_distance_to_destination(); - break; + return rover.mode_loiter.get_distance_to_destination(); } // we should never reach here but just in case, return 0