Copter: set Notify firmware_update flag before reboot

This commit is contained in:
Randy Mackay 2015-03-05 17:34:50 +09:00
parent 7675160e33
commit e0acd250d1

View File

@ -1199,6 +1199,9 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg)
case MAV_CMD_PREFLIGHT_REBOOT_SHUTDOWN:
if (packet.param1 == 1 || packet.param1 == 3) {
AP_Notify::events.firmware_update = 1;
update_notify();
hal.scheduler->delay(50);
// when packet.param1 == 3 we reboot to hold in bootloader
hal.scheduler->reboot(packet.param1 == 3);
result = MAV_RESULT_ACCEPTED;