mirror of https://github.com/ArduPilot/ardupilot
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:
parent
798c4e2278
commit
94f301181e
|
@ -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
|
||||
// -----------------------
|
||||
|
|
Loading…
Reference in New Issue