From 00f9843e40298b46d7e726e39cedb16a4ccf7092 Mon Sep 17 00:00:00 2001 From: Randy Mackay Date: Wed, 5 Mar 2014 11:43:21 +0900 Subject: [PATCH] Copter: remove CLI tests for gps, logging, radio Required to shrink the firmware down so that it can fit on the APM2 boards --- ArduCopter/setup.pde | 34 -------------- ArduCopter/test.pde | 107 ------------------------------------------- 2 files changed, 141 deletions(-) diff --git a/ArduCopter/setup.pde b/ArduCopter/setup.pde index 8da280c057..1b8484c01f 100644 --- a/ArduCopter/setup.pde +++ b/ArduCopter/setup.pde @@ -5,7 +5,6 @@ // Functions called from the setup menu static int8_t setup_factory (uint8_t argc, const Menu::arg *argv); static int8_t setup_show (uint8_t argc, const Menu::arg *argv); -static int8_t setup_sonar (uint8_t argc, const Menu::arg *argv); // Command/function table for the setup menu @@ -254,24 +253,6 @@ print_switch(uint8_t p, uint8_t m, bool b) cliSerial->printf_P(PSTR("OFF\n")); } -static void -print_done() -{ - cliSerial->printf_P(PSTR("\nSaved\n")); -} - - -static void zero_eeprom(void) -{ - cliSerial->printf_P(PSTR("\nErasing EEPROM\n")); - - for (uint16_t i = 0; i < EEPROM_MAX_ADDR; i++) { - hal.storage->write_byte(i, 0); - } - - cliSerial->printf_P(PSTR("done\n")); -} - static void print_accel_offsets_and_scaling(void) { @@ -349,18 +330,3 @@ static void report_version() print_divider(); print_blanks(2); } - - -static void report_tuning() -{ - cliSerial->printf_P(PSTR("\nTUNE:\n")); - print_divider(); - if (g.radio_tuning == 0) { - print_enabled(g.radio_tuning.get()); - }else{ - float low = (float)g.radio_tuning_low.get() / 1000; - float high = (float)g.radio_tuning_high.get() / 1000; - cliSerial->printf_P(PSTR(" %d, Low:%1.4f, High:%1.4f\n"),(int)g.radio_tuning.get(), low, high); - } - print_blanks(2); -} diff --git a/ArduCopter/test.pde b/ArduCopter/test.pde index a62510e97b..3a9d8e3df4 100644 --- a/ArduCopter/test.pde +++ b/ArduCopter/test.pde @@ -8,14 +8,10 @@ static int8_t test_baro(uint8_t argc, const Menu::arg *argv); #endif static int8_t test_compass(uint8_t argc, const Menu::arg *argv); -static int8_t test_gps(uint8_t argc, const Menu::arg *argv); static int8_t test_ins(uint8_t argc, const Menu::arg *argv); -static int8_t test_logging(uint8_t argc, const Menu::arg *argv); static int8_t test_motors(uint8_t argc, const Menu::arg *argv); static int8_t test_motorsync(uint8_t argc, const Menu::arg *argv); static int8_t test_optflow(uint8_t argc, const Menu::arg *argv); -static int8_t test_radio_pwm(uint8_t argc, const Menu::arg *argv); -static int8_t test_radio(uint8_t argc, const Menu::arg *argv); static int8_t test_relay(uint8_t argc, const Menu::arg *argv); #if CONFIG_HAL_BOARD == HAL_BOARD_PX4 static int8_t test_shell(uint8_t argc, const Menu::arg *argv); @@ -33,14 +29,10 @@ const struct Menu::command test_menu_commands[] PROGMEM = { {"baro", test_baro}, #endif {"compass", test_compass}, - {"gps", test_gps}, {"ins", test_ins}, - {"logging", test_logging}, {"motors", test_motors}, {"motorsync", test_motorsync}, {"optflow", test_optflow}, - {"pwm", test_radio_pwm}, - {"radio", test_radio}, {"relay", test_relay}, #if CONFIG_HAL_BOARD == HAL_BOARD_PX4 {"shell", test_shell}, @@ -172,36 +164,6 @@ test_compass(uint8_t argc, const Menu::arg *argv) return (0); } -static int8_t -test_gps(uint8_t argc, const Menu::arg *argv) -{ - print_hit_enter(); - delay(1000); - - while(1) { - delay(100); - - g_gps->update(); - - if (g_gps->new_data) { - cliSerial->printf_P(PSTR("Lat: ")); - print_latlon(cliSerial, g_gps->latitude); - cliSerial->printf_P(PSTR(", Lon ")); - print_latlon(cliSerial, g_gps->longitude); - cliSerial->printf_P(PSTR(", Alt: %ldm, #sats: %d\n"), - g_gps->altitude_cm/100, - g_gps->num_sats); - g_gps->new_data = false; - }else{ - cliSerial->print_P(PSTR(".")); - } - if(cliSerial->available() > 0) { - return (0); - } - } - return 0; -} - static int8_t test_ins(uint8_t argc, const Menu::arg *argv) { @@ -236,17 +198,6 @@ test_ins(uint8_t argc, const Menu::arg *argv) } } -/* - * test the dataflash is working - */ -static int8_t -test_logging(uint8_t argc, const Menu::arg *argv) -{ - cliSerial->println_P(PSTR("Testing dataflash logging")); - DataFlash.ShowDeviceInfo(cliSerial); - return 0; -} - static int8_t test_motors(uint8_t argc, const Menu::arg *argv) { @@ -430,64 +381,6 @@ test_optflow(uint8_t argc, const Menu::arg *argv) #endif // OPTFLOW == ENABLED } -static int8_t -test_radio_pwm(uint8_t argc, const Menu::arg *argv) -{ - print_hit_enter(); - delay(1000); - - while(1) { - delay(20); - - // Filters radio input - adjust filters in the radio.pde file - // ---------------------------------------------------------- - read_radio(); - - // servo Yaw - //APM_RC.OutputCh(CH_7, g.rc_4.radio_out); - - cliSerial->printf_P(PSTR("IN: 1: %d\t2: %d\t3: %d\t4: %d\t5: %d\t6: %d\t7: %d\t8: %d\n"), - g.rc_1.radio_in, - g.rc_2.radio_in, - g.rc_3.radio_in, - g.rc_4.radio_in, - g.rc_5.radio_in, - g.rc_6.radio_in, - g.rc_7.radio_in, - g.rc_8.radio_in); - - if(cliSerial->available() > 0) { - return (0); - } - } -} - -static int8_t -test_radio(uint8_t argc, const Menu::arg *argv) -{ - print_hit_enter(); - delay(1000); - - while(1) { - delay(20); - read_radio(); - - - cliSerial->printf_P(PSTR("IN 1: %d\t2: %d\t3: %d\t4: %d\t5: %d\t6: %d\t7: %d\n"), - g.rc_1.control_in, - g.rc_2.control_in, - g.rc_3.control_in, - g.rc_4.control_in, - g.rc_5.control_in, - g.rc_6.control_in, - g.rc_7.control_in); - - if(cliSerial->available() > 0) { - return (0); - } - } -} - static int8_t test_relay(uint8_t argc, const Menu::arg *argv) { print_hit_enter();