Plane: support reboot to bootloader

This commit is contained in:
Andrew Tridgell 2013-09-04 11:59:16 +10:00
parent 979636936d
commit 4a8c9a7765
2 changed files with 4 additions and 13 deletions

View File

@ -1235,8 +1235,9 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg)
break;
case MAV_CMD_PREFLIGHT_REBOOT_SHUTDOWN:
if (packet.param1 == 1) {
reboot_apm();
if (packet.param1 == 1 || packet.param1 == 3) {
// when packet.param1 == 3 we reboot to hold in bootloader
hal.scheduler->reboot(packet.param1 == 3);
result = MAV_RESULT_ACCEPTED;
}
break;

View File

@ -44,7 +44,7 @@ MENU(main_menu, THISFIRMWARE, main_menu_commands);
static int8_t reboot_board(uint8_t argc, const Menu::arg *argv)
{
reboot_apm();
hal.scheduler->reboot(false);
return 0;
}
@ -559,16 +559,6 @@ uint16_t board_voltage(void)
}
/*
force a software reset of the APM
*/
static void reboot_apm(void)
{
hal.scheduler->reboot();
while (1);
}
static void
print_flight_mode(AP_HAL::BetterStream *port, uint8_t mode)
{