diff --git a/ArduCopter/GCS_Mavlink.pde b/ArduCopter/GCS_Mavlink.pde index 107f961644..cef97ed2e6 100644 --- a/ArduCopter/GCS_Mavlink.pde +++ b/ArduCopter/GCS_Mavlink.pde @@ -1114,6 +1114,15 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg) result = MAV_RESULT_UNSUPPORTED; } break; + + case MAV_CMD_PREFLIGHT_REBOOT_SHUTDOWN: + if (packet.param1 == 1) { + reboot_apm(); + result = MAV_RESULT_ACCEPTED; + } + break; + + default: result = MAV_RESULT_UNSUPPORTED; break; diff --git a/ArduCopter/system.pde b/ArduCopter/system.pde index 6a10d1ca47..21334eaf1e 100644 --- a/ArduCopter/system.pde +++ b/ArduCopter/system.pde @@ -11,6 +11,7 @@ static int8_t process_logs(uint8_t argc, const Menu::arg *argv); // in Log.pde static int8_t setup_mode(uint8_t argc, const Menu::arg *argv); // in setup.pde static int8_t test_mode(uint8_t argc, const Menu::arg *argv); // in test.cpp +static int8_t reboot_board(uint8_t argc, const Menu::arg *argv); // This is the help function // PSTR is an AVR macro to read strings from flash memory @@ -21,9 +22,7 @@ static int8_t main_menu_help(uint8_t argc, const Menu::arg *argv) " logs\n" " setup\n" " test\n" - " planner\n" - "\n" - "Move the slide switch and reset to FLY.\n" + " reboot\n" "\n")); return(0); } @@ -35,12 +34,19 @@ const struct Menu::command main_menu_commands[] PROGMEM = { {"logs", process_logs}, {"setup", setup_mode}, {"test", test_mode}, + {"reboot", reboot_board}, {"help", main_menu_help}, }; // Create the top-level menu object. MENU(main_menu, THISFIRMWARE, main_menu_commands); +static int8_t reboot_board(uint8_t argc, const Menu::arg *argv) +{ + reboot_apm(); + return 0; +} + // the user wants the CLI. It never exits static void run_cli(FastSerial *port) { @@ -681,6 +687,28 @@ uint16_t board_voltage(void) } #endif +/* + force a software reset of the APM + */ +static void reboot_apm(void) +{ + cliSerial->printf_P(PSTR("REBOOTING\n")); + delay(100); // let serial flush + // see http://www.arduino.cc/cgi-bin/yabb2/YaBB.pl?num=1250663814/ + // for the method +#if CONFIG_APM_HARDWARE == APM_HARDWARE_APM2 + // this relies on the bootloader resetting the watchdog, which + // APM1 doesn't do + cli(); + wdt_enable(WDTO_15MS); +#else + // this works on APM1 + void (*fn)(void) = NULL; + fn(); +#endif + while (1); +} + // // print_flight_mode - prints flight mode to serial port. //