Copter: recalc distance to home during arming

fixes an rare edge case in which the fence could trigger immediately
after arming
This commit is contained in:
Randy Mackay 2013-11-01 23:54:32 +09:00
parent c824ccfb38
commit 81ac548e2c

View File

@ -151,8 +151,10 @@ static void init_arm_motors()
// Reset home position // Reset home position
// ------------------- // -------------------
if(ap.home_is_set) if (ap.home_is_set) {
init_home(); init_home();
calc_distance_and_bearing();
}
// all I terms are invalid // all I terms are invalid
// ----------------------- // -----------------------