Browse Source

Copter: move mavlink reboot code up to base class

mission-4.1.18
Peter Barker 8 years ago committed by Peter Barker
parent
commit
c84b102c1c
  1. 11
      ArduCopter/GCS_Mavlink.cpp

11
ArduCopter/GCS_Mavlink.cpp

@ -979,17 +979,6 @@ void GCS_MAVLINK_Copter::handleMessage(mavlink_message_t* msg) @@ -979,17 +979,6 @@ void GCS_MAVLINK_Copter::handleMessage(mavlink_message_t* msg)
}
break;
case MAV_CMD_PREFLIGHT_REBOOT_SHUTDOWN:
if (is_equal(packet.param1,1.0f) || is_equal(packet.param1,3.0f)) {
AP_Notify::flags.firmware_update = 1;
copter.notify.update();
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;
}
break;
case MAV_CMD_DO_FENCE_ENABLE:
#if AC_FENCE == ENABLED
result = MAV_RESULT_ACCEPTED;

Loading…
Cancel
Save