Copter: remove CLI set

Frees about 1k of flash
This commit is contained in:
Randy Mackay 2014-02-19 22:00:25 +09:00
parent 3a934357e9
commit fc85228d09
1 changed files with 0 additions and 91 deletions

View File

@ -4,7 +4,6 @@
// Functions called from the setup menu // Functions called from the setup menu
static int8_t setup_factory (uint8_t argc, const Menu::arg *argv); static int8_t setup_factory (uint8_t argc, const Menu::arg *argv);
static int8_t setup_set (uint8_t argc, const Menu::arg *argv);
static int8_t setup_show (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); static int8_t setup_sonar (uint8_t argc, const Menu::arg *argv);
@ -14,7 +13,6 @@ const struct Menu::command setup_menu_commands[] PROGMEM = {
// command function called // command function called
// ======= =============== // ======= ===============
{"reset", setup_factory}, {"reset", setup_factory},
{"set", setup_set},
{"show", setup_show}, {"show", setup_show},
}; };
@ -28,41 +26,11 @@ setup_mode(uint8_t argc, const Menu::arg *argv)
// Give the user some guidance // Give the user some guidance
cliSerial->printf_P(PSTR("Setup Mode\n\n\n")); cliSerial->printf_P(PSTR("Setup Mode\n\n\n"));
if(g.rc_1.radio_min >= 1300) {
delay(1000);
cliSerial->printf_P(PSTR("\n!Warning, radio not configured!"));
delay(1000);
cliSerial->printf_P(PSTR("\n Type 'radio' now.\n\n"));
}
// Run the setup menu. When the menu exits, we will return to the main menu. // Run the setup menu. When the menu exits, we will return to the main menu.
setup_menu.run(); setup_menu.run();
return 0; return 0;
} }
static int8_t
setup_optflow(uint8_t argc, const Menu::arg *argv)
{
#if OPTFLOW == ENABLED
if (!strcmp_P(argv[1].str, PSTR("on"))) {
g.optflow_enabled = true;
init_optflow();
} else if (!strcmp_P(argv[1].str, PSTR("off"))) {
g.optflow_enabled = false;
}else{
cliSerial->printf_P(PSTR("\nOp:[on, off]\n"));
report_optflow();
return 0;
}
g.optflow_enabled.save();
report_optflow();
#endif // OPTFLOW == ENABLED
return 0;
}
// Initialise the EEPROM to 'factory' settings (mostly defined in APM_Config.h or via defaults). // Initialise the EEPROM to 'factory' settings (mostly defined in APM_Config.h or via defaults).
// Called by the setup menu 'factoryreset' command. // Called by the setup menu 'factoryreset' command.
static int8_t static int8_t
@ -90,65 +58,6 @@ setup_factory(uint8_t argc, const Menu::arg *argv)
return(0); return(0);
} }
//Set a parameter to a specified value. It will cast the value to the current type of the
//parameter and make sure it fits in case of INT8 and INT16
static int8_t setup_set(uint8_t argc, const Menu::arg *argv)
{
int8_t value_int8;
int16_t value_int16;
AP_Param *param;
enum ap_var_type p_type;
if(argc!=3)
{
cliSerial->printf_P(PSTR("Invalid command. Usage: set <name> <value>\n"));
return 0;
}
param = AP_Param::find(argv[1].str, &p_type);
if(!param)
{
cliSerial->printf_P(PSTR("Param not found: %s\n"), argv[1].str);
return 0;
}
switch(p_type)
{
case AP_PARAM_INT8:
value_int8 = (int8_t)(argv[2].i);
if(argv[2].i!=value_int8)
{
cliSerial->printf_P(PSTR("Value out of range for type INT8\n"));
return 0;
}
((AP_Int8*)param)->set_and_save(value_int8);
break;
case AP_PARAM_INT16:
value_int16 = (int16_t)(argv[2].i);
if(argv[2].i!=value_int16)
{
cliSerial->printf_P(PSTR("Value out of range for type INT16\n"));
return 0;
}
((AP_Int16*)param)->set_and_save(value_int16);
break;
//int32 and float don't need bounds checking, just use the value provoded by Menu::arg
case AP_PARAM_INT32:
((AP_Int32*)param)->set_and_save(argv[2].i);
break;
case AP_PARAM_FLOAT:
((AP_Float*)param)->set_and_save(argv[2].f);
break;
default:
cliSerial->printf_P(PSTR("Cannot set parameter of type %d.\n"), p_type);
break;
}
return 0;
}
// Print the current configuration. // Print the current configuration.
// Called by the setup menu 'show' command. // Called by the setup menu 'show' command.
static int8_t static int8_t