Browse Source

Copter: support reboot to bootloader

master
Andrew Tridgell 12 years ago
parent
commit
979636936d
  1. 5
      ArduCopter/GCS_Mavlink.pde
  2. 9
      ArduCopter/system.pde

5
ArduCopter/GCS_Mavlink.pde

@ -1236,8 +1236,9 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg) @@ -1236,8 +1236,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;

9
ArduCopter/system.pde

@ -43,7 +43,7 @@ MENU(main_menu, THISFIRMWARE, main_menu_commands); @@ -43,7 +43,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;
}
@ -626,13 +626,6 @@ uint16_t board_voltage(void) @@ -626,13 +626,6 @@ uint16_t board_voltage(void)
return board_vcc_analog_source->read_latest();
}
/*
force a software reset of the APM
*/
static void reboot_apm(void) {
hal.scheduler->reboot();
}
//
// print_flight_mode - prints flight mode to serial port.
//

Loading…
Cancel
Save