|
|
@ -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)) { |
|
|
|
if (is_equal(packet.param1,1.0f) || is_equal(packet.param1,3.0f)) { |
|
|
|
AP_Notify::flags.firmware_update = 1; |
|
|
|
AP_Notify::flags.firmware_update = 1; |
|
|
|
copter.update_notify(); |
|
|
|
copter.update_notify(); |
|
|
|
hal.scheduler->delay(50); |
|
|
|
hal.scheduler->delay(200); |
|
|
|
// when packet.param1 == 3 we reboot to hold in bootloader
|
|
|
|
// when packet.param1 == 3 we reboot to hold in bootloader
|
|
|
|
hal.scheduler->reboot(is_equal(packet.param1,3.0f)); |
|
|
|
hal.scheduler->reboot(is_equal(packet.param1,3.0f)); |
|
|
|
result = MAV_RESULT_ACCEPTED; |
|
|
|
result = MAV_RESULT_ACCEPTED; |
|
|
|