Copter: add parameter "set" and "show" commands to setup menu.

Squashed commit of the following:

commit 4243a0bb89de2f850606c623aac6a5b583c333ae
Author: John Stack <stack@spotify.com>
Date:   Thu Mar 7 09:28:16 2013 +0100

    Undo change to system.pde, not needed.

commit dae2dbbbd6e13621fccc1d0a221aae8d83240417
Author: John Stack <stack@spotify.com>
Date:   Wed Mar 6 22:47:50 2013 +0100

    Remove leftover bits of old menu setup

commit ccefc8fe0d237364b06a1478348f8552720d7598
Author: John Stack <stack@spotify.com>
Date:   Wed Mar 6 22:40:30 2013 +0100

    Roll the param menu into setup.

commit c61dad17bf32a3080d8eca2389c6e25f98767545
Author: John Stack <stack@spotify.com>
Date:   Wed Mar 6 08:08:42 2013 +0100

    Make the param menu a compile-time option, by defining PARAM_MENU

commit 0f35c4e88ec7aba5035b4880e9994e4783da75a9
Author: John Stack <stack@spotify.com>
Date:   Wed Mar 6 07:57:22 2013 +0100

    Use find(), which works well.

commit 3b81b29597fcee49193330d7b6d3f3aed99a476c
Author: John Stack <stack@spotify.com>
Date:   Tue Mar 5 07:57:33 2013 +0100

    Whitespace fixes

commit 6b9ccc5fe1de1e40a24eb9ff89006b9bd80e3662
Author: John Stack <stack@spotify.com>
Date:   Tue Mar 5 07:28:20 2013 +0100

    Add cli menu to change any parameter.
This commit is contained in:
John Stäck 2013-03-07 09:30:45 +01:00 committed by Randy Mackay
parent 54cb722f9a
commit 46a831fc03

View File

@ -21,12 +21,13 @@ static int8_t setup_range (uint8_t argc, const Menu::arg *argv);
static int8_t setup_declination (uint8_t argc, const Menu::arg *argv);
static int8_t setup_optflow (uint8_t argc, const Menu::arg *argv);
#if FRAME_CONFIG == HELI_FRAME
static int8_t setup_heli (uint8_t argc, const Menu::arg *argv);
static int8_t setup_gyro (uint8_t argc, const Menu::arg *argv);
#endif
static int8_t setup_set (uint8_t argc, const Menu::arg *argv);
// Command/function table for the setup menu
const struct Menu::command setup_menu_commands[] PROGMEM = {
// command function called
@ -52,7 +53,8 @@ const struct Menu::command setup_menu_commands[] PROGMEM = {
{"heli", setup_heli},
{"gyro", setup_gyro},
#endif
{"show", setup_show}
{"show", setup_show},
{"set", setup_set}
};
// Create the setup menu object.
@ -87,6 +89,43 @@ setup_mode(uint8_t argc, const Menu::arg *argv)
static int8_t
setup_show(uint8_t argc, const Menu::arg *argv)
{
AP_Param *param;
ap_var_type type;
//If a parameter name is given as an argument to show, print only that parameter
if(argc>=2)
{
param=AP_Param::find(argv[1].str, &type);
if(!param)
{
cliSerial->printf_P(PSTR("Parameter not found: '%s'\n"), argv[1]);
return 0;
}
//Print differently for different types, and include parameter type in output.
switch (type) {
case AP_PARAM_INT8:
cliSerial->printf_P(PSTR("INT8 %s: %d\n"), argv[1].str, (int)((AP_Int8 *)param)->get());
break;
case AP_PARAM_INT16:
cliSerial->printf_P(PSTR("INT16 %s: %d\n"), argv[1].str, (int)((AP_Int16 *)param)->get());
break;
case AP_PARAM_INT32:
cliSerial->printf_P(PSTR("INT32 %s: %ld\n"), argv[1].str, (long)((AP_Int32 *)param)->get());
break;
case AP_PARAM_FLOAT:
cliSerial->printf_P(PSTR("FLOAT %s: %f\n"), argv[1].str, ((AP_Float *)param)->get());
break;
default:
cliSerial->printf_P(PSTR("Unhandled parameter type for %s: %d.\n"), argv[1].str, type);
break;
}
return 0;
}
// clear the area
print_blanks(8);
@ -991,7 +1030,64 @@ setup_optflow(uint8_t argc, const Menu::arg *argv)
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;
}
/***************************************************************************/
// CLI reports