From de406da254a44e53ce903751af2a5e4ddce87db3 Mon Sep 17 00:00:00 2001 From: Randy Mackay Date: Mon, 18 Sep 2017 17:22:51 +0900 Subject: [PATCH] Rover: set home using EKF position previously the home position could be set from DCM This makes the setting of home slower but more accurate --- APMrover2/commands.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/APMrover2/commands.cpp b/APMrover2/commands.cpp index 08207e27b4..8a326f511e 100644 --- a/APMrover2/commands.cpp +++ b/APMrover2/commands.cpp @@ -17,7 +17,7 @@ bool Rover::set_home_to_current_location(bool lock) { // use position from EKF if available otherwise use GPS Location temp_loc; - if (ahrs.get_position(temp_loc)) { + if (ahrs.have_inertial_nav() && ahrs.get_position(temp_loc)) { return set_home(temp_loc, lock); } return false;