Copter: reset battery_fs after dis/rearming

This commit is contained in:
Andre Kjellstrup 2014-09-17 12:28:02 +02:00 committed by Randy Mackay
parent 3f687733e6
commit b4c6d6395e

View File

@ -132,6 +132,9 @@ static void init_arm_motors()
// disable inertial nav errors temporarily
inertial_nav.ignore_next_error();
// reset battery failsafe
set_failsafe_battery(false);
// notify that arming will occur (we do this early to give plenty of warning)
AP_Notify::flags.armed = true;
// call update_notify a few times to ensure the message gets out