diff --git a/ArduCopter/planner.pde b/ArduCopter/planner.pde deleted file mode 100644 index d6f6465b78..0000000000 --- a/ArduCopter/planner.pde +++ /dev/null @@ -1,52 +0,0 @@ -// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- - -// These are function definitions so the Menu can be constructed before the functions -// are defined below. Order matters to the compiler. -static int8_t planner_gcs(uint8_t argc, const Menu::arg *argv); - -// Creates a constant array of structs representing menu options -// and stores them in Flash memory, not RAM. -// User enters the string in the console to call the functions on the right. -// See class Menu in AP_Common for implementation details -const struct Menu::command planner_menu_commands[] PROGMEM = { - {"gcs", planner_gcs}, -}; - -// A Macro to create the Menu -MENU(planner_menu, "planner", planner_menu_commands); - -static int8_t -planner_mode(uint8_t argc, const Menu::arg *argv) -{ - Serial.printf_P(PSTR("Planner Mode\nNot intended for manual use\n\n")); - planner_menu.run(); - return (0); -} - -static int8_t -planner_gcs(uint8_t argc, const Menu::arg *argv) -{ - gcs0.init(&Serial); - - int16_t loopcount = 0; - - while (1) { - if (millis()-fast_loopTimer > 19) { - fast_loopTimer = millis(); - - gcs_update(); - - read_radio(); - - gcs_data_stream_send(); - - if ((loopcount % 16) == 0) { // 3 hz - gcs_send_message(MSG_HEARTBEAT); - } - - loopcount++; - } - } - return 0; -} - diff --git a/ArduCopter/system.pde b/ArduCopter/system.pde index ffb0bbe56c..86ec7dd89f 100644 --- a/ArduCopter/system.pde +++ b/ArduCopter/system.pde @@ -11,7 +11,6 @@ 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 planner_mode(uint8_t argc, const Menu::arg *argv); // in planner.pde // This is the help function // PSTR is an AVR macro to read strings from flash memory @@ -37,7 +36,6 @@ const struct Menu::command main_menu_commands[] PROGMEM = { {"setup", setup_mode}, {"test", test_mode}, {"help", main_menu_help}, - {"planner", planner_mode} }; // Create the top-level menu object. diff --git a/ArduPlane/planner.pde b/ArduPlane/planner.pde deleted file mode 100644 index 4d920f97d7..0000000000 --- a/ArduPlane/planner.pde +++ /dev/null @@ -1,53 +0,0 @@ -// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*- - -// These are function definitions so the Menu can be constructed before the functions -// are defined below. Order matters to the compiler. -static int8_t planner_gcs(uint8_t argc, const Menu::arg *argv); - -// Creates a constant array of structs representing menu options -// and stores them in Flash memory, not RAM. -// User enters the string in the console to call the functions on the right. -// See class Menu in AP_Common for implementation details -static const struct Menu::command planner_menu_commands[] PROGMEM = { - {"gcs", planner_gcs}, -}; - -// A Macro to create the Menu -MENU(planner_menu, "planner", planner_menu_commands); - -static int8_t -planner_mode(uint8_t argc, const Menu::arg *argv) -{ - Serial.printf_P(PSTR("Planner Mode\n\nThis mode is not intended for manual use\n\n")); - planner_menu.run(); - return 0; -} -static int8_t -planner_gcs(uint8_t argc, const Menu::arg *argv) -{ - gcs0.init(&Serial); - -#if USB_MUX_PIN < 0 - // we don't have gcs3 if we have the USB mux setup - gcs3.init(&Serial3); -#endif - - int16_t loopcount = 0; - while (1) { - if (millis()-fast_loopTimer_ms > 19) { - fast_loopTimer_ms = millis(); - - gcs_update(); - - read_radio(); - - gcs_data_stream_send(); - if ((loopcount % 16) == 0) { // 3 hz - gcs_send_message(MSG_HEARTBEAT); - } - loopcount++; - } - } - return 0; -} - diff --git a/ArduPlane/system.pde b/ArduPlane/system.pde index c4bf7821a4..aa7dc58c8c 100644 --- a/ArduPlane/system.pde +++ b/ArduPlane/system.pde @@ -12,7 +12,6 @@ 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 planner_mode(uint8_t argc, const Menu::arg *argv); // in planner.pde // This is the help function // PSTR is an AVR macro to read strings from flash memory @@ -37,7 +36,6 @@ static const struct Menu::command main_menu_commands[] PROGMEM = { {"setup", setup_mode}, {"test", test_mode}, {"help", main_menu_help}, - {"planner", planner_mode} }; // Create the top-level menu object.