From e3da6d69d55f5aec2aa74cc2ee7d444897666404 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Thu, 13 Jun 2019 12:11:12 +1000 Subject: [PATCH] Copter: mode_auto: don't set takeoff dest from bad current location --- ArduCopter/mode_auto.cpp | 6 ++++++ 1 file changed, 6 insertions(+) diff --git a/ArduCopter/mode_auto.cpp b/ArduCopter/mode_auto.cpp index d5138d47e5..142886dcc2 100644 --- a/ArduCopter/mode_auto.cpp +++ b/ArduCopter/mode_auto.cpp @@ -143,6 +143,12 @@ void ModeAuto::takeoff_start(const Location& dest_loc) Location dest(dest_loc); + if (!copter.current_loc.initialised()) { + // vehicle doesn't know where it is ATM. We should not + // initialise our takeoff destination without knowing this! + return; + } + // set horizontal target dest.lat = copter.current_loc.lat; dest.lng = copter.current_loc.lng;