AP_Menu: dynamically allocate the menu buffers

this saves memory when the menus are not used, and allows for the
commandline and argument limits to be changed
This commit is contained in:
Andrew Tridgell 2013-11-06 09:10:31 +11:00
parent ea09aebed0
commit 470e5f570d
2 changed files with 53 additions and 5 deletions

View File

@ -17,8 +17,8 @@
extern const AP_HAL::HAL& hal; extern const AP_HAL::HAL& hal;
// statics // statics
char Menu::_inbuf[MENU_COMMANDLINE_MAX]; char *Menu::_inbuf;
Menu::arg Menu::_argv[MENU_ARGS_MAX + 1]; Menu::arg *Menu::_argv;
AP_HAL::BetterStream *Menu::_port; AP_HAL::BetterStream *Menu::_port;
@ -27,8 +27,14 @@ Menu::Menu(const prog_char *prompt, const Menu::command *commands, uint8_t entri
_prompt(prompt), _prompt(prompt),
_commands(commands), _commands(commands),
_entries(entries), _entries(entries),
_ppfunc(ppfunc) _ppfunc(ppfunc),
_commandline_max(MENU_COMMANDLINE_MAX),
_args_max(MENU_ARGS_MAX)
{ {
// the buffers are initially NULL, then they are allocated on
// first use
_inbuf = NULL;
_argv = NULL;
} }
// run the menu // run the menu
@ -46,6 +52,8 @@ Menu::run(void)
_port = hal.console; _port = hal.console;
} }
_allocate_buffers();
// loop performing commands // loop performing commands
for (;;) { for (;;) {
@ -168,3 +176,34 @@ Menu::_call(uint8_t n, uint8_t argc)
fn = (func)pgm_read_pointer(&_commands[n].func); fn = (func)pgm_read_pointer(&_commands[n].func);
return(fn(argc, &_argv[0])); return(fn(argc, &_argv[0]));
} }
/**
set limits on max args and command line length
*/
void
Menu::set_limits(uint8_t commandline_max, uint8_t args_max)
{
if (_inbuf != NULL) {
delete[] _inbuf;
_inbuf = NULL;
}
if (_argv != NULL) {
delete[] _argv;
_argv = NULL;
}
// remember limits, the buffers will be allocated by allocate_buffers()
_commandline_max = commandline_max;
_args_max = args_max;
}
void
Menu::_allocate_buffers(void)
{
/* only allocate if the buffers are NULL */
if (_inbuf == NULL) {
_inbuf = new char[_commandline_max];
}
if (_argv == NULL) {
_argv = new arg[_args_max+1];
}
}

View File

@ -103,6 +103,9 @@ public:
/// ///
Menu(const char *prompt, const struct command *commands, uint8_t entries, preprompt ppfunc = 0); Menu(const char *prompt, const struct command *commands, uint8_t entries, preprompt ppfunc = 0);
/// set command line length limit
void set_limits(uint8_t commandline_max, uint8_t args_max);
/// menu runner /// menu runner
void run(void); void run(void);
@ -123,8 +126,14 @@ private:
const uint8_t _entries; ///< size of the menu const uint8_t _entries; ///< size of the menu
const preprompt _ppfunc; ///< optional pre-prompt action const preprompt _ppfunc; ///< optional pre-prompt action
static char _inbuf[MENU_COMMANDLINE_MAX]; ///< input buffer static char *_inbuf; ///< input buffer
static arg _argv[MENU_ARGS_MAX + 1]; ///< arguments static arg *_argv; ///< arguments
uint8_t _commandline_max;
uint8_t _args_max;
// allocate inbuf and args buffers
void _allocate_buffers(void);
// port to run on // port to run on
static AP_HAL::BetterStream *_port; static AP_HAL::BetterStream *_port;