Copter: delay for 200ms instead of 50ms before reboot

This commit is contained in:
Randy Mackay 2015-03-05 17:34:50 +09:00
parent 1fbdf11eca
commit 8efc02fe0c

View File

@ -1382,7 +1382,7 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg)
if (is_equal(packet.param1,1.0f) || is_equal(packet.param1,3.0f)) {
AP_Notify::flags.firmware_update = 1;
copter.update_notify();
hal.scheduler->delay(50);
hal.scheduler->delay(200);
// when packet.param1 == 3 we reboot to hold in bootloader
hal.scheduler->reboot(is_equal(packet.param1,3.0f));
result = MAV_RESULT_ACCEPTED;