From 94f301181ef2bc99ff318c60f4021f3bf96816a4 Mon Sep 17 00:00:00 2001 From: Randy Mackay Date: Fri, 1 Nov 2013 23:54:32 +0900 Subject: [PATCH] Copter: recalc distance to home during arming fixes an rare edge case in which the fence could trigger immediately after arming --- ArduCopter/motors.pde | 4 +++- 1 file changed, 3 insertions(+), 1 deletion(-) diff --git a/ArduCopter/motors.pde b/ArduCopter/motors.pde index 1648a6d040..7d0a56e6e4 100644 --- a/ArduCopter/motors.pde +++ b/ArduCopter/motors.pde @@ -151,8 +151,10 @@ static void init_arm_motors() // Reset home position // ------------------- - if(ap.home_is_set) + if (ap.home_is_set) { init_home(); + calc_distance_and_bearing(); + } // all I terms are invalid // -----------------------