ardupilot/libraries/AP_Menu/AP_Menu.cpp

165 lines
4.1 KiB
C++
Raw Normal View History

// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: t -*-
//
// Simple commandline menu system.
//
#include <FastSerial.h>
#include <AP_Common.h>
#include <ctype.h>
#include <string.h>
#include <avr/pgmspace.h>
#include "AP_Menu.h"
// statics
char Menu::_inbuf[MENU_COMMANDLINE_MAX];
Menu::arg Menu::_argv[MENU_ARGS_MAX + 1];
FastSerial *Menu::_port;
// constructor
Menu::Menu(const prog_char *prompt, const Menu::command *commands, uint8_t entries, preprompt ppfunc) :
2011-10-28 15:43:43 -03:00
_prompt(prompt),
_commands(commands),
_entries(entries),
_ppfunc(ppfunc)
{
}
// run the menu
void
Menu::run(void)
{
int8_t ret;
uint8_t len, i;
uint8_t argc;
int c;
char *s;
2011-10-28 15:43:43 -03:00
if (_port == NULL) {
// default to main serial port
_port = &Serial;
}
2011-10-28 15:43:43 -03:00
// loop performing commands
for (;; ) {
2011-10-28 15:43:43 -03:00
// run the pre-prompt function, if one is defined
if ((NULL != _ppfunc) && !_ppfunc())
return;
// loop reading characters from the input
len = 0;
_port->printf_P(PSTR("%S] "), FPSTR(_prompt));
for (;; ) {
c = _port->read();
2011-10-28 15:43:43 -03:00
if (-1 == c)
continue;
// carriage return -> process command
if ('\r' == c) {
_inbuf[len] = '\0';
_port->write('\r');
_port->write('\n');
2011-10-28 15:43:43 -03:00
break;
}
// backspace
if ('\b' == c) {
if (len > 0) {
len--;
_port->write('\b');
_port->write(' ');
_port->write('\b');
2011-10-28 15:43:43 -03:00
continue;
}
}
// printable character
if (isprint(c) && (len < (MENU_COMMANDLINE_MAX - 1))) {
_inbuf[len++] = c;
_port->write((char)c);
2011-10-28 15:43:43 -03:00
continue;
}
}
// split the input line into tokens
argc = 0;
_argv[argc++].str = strtok_r(_inbuf, " ", &s);
// XXX should an empty line by itself back out of the current menu?
while (argc <= MENU_ARGS_MAX) {
_argv[argc].str = strtok_r(NULL, " ", &s);
if ('\0' == _argv[argc].str)
break;
_argv[argc].i = atol(_argv[argc].str);
_argv[argc].f = atof(_argv[argc].str); // calls strtod, > 700B !
2011-10-28 15:43:43 -03:00
argc++;
}
if (_argv[0].str == NULL) {
continue;
}
2011-10-28 15:43:43 -03:00
// populate arguments that have not been specified with "" and 0
// this is safer than NULL in the case where commands may look
// without testing argc
i = argc;
while (i <= MENU_ARGS_MAX) {
_argv[i].str = "";
_argv[i].i = 0;
_argv[i].f = 0;
i++;
}
bool cmd_found = false;
2011-10-28 15:43:43 -03:00
// look for a command matching the first word (note that it may be empty)
for (i = 0; i < _entries; i++) {
if (!strcasecmp_P(_argv[0].str, _commands[i].command)) {
ret = _call(i, argc);
cmd_found=true;
2011-10-28 15:43:43 -03:00
if (-2 == ret)
return;
break;
}
}
// implicit commands
if (i == _entries) {
if (!strcmp(_argv[0].str, "?") || (!strcasecmp_P(_argv[0].str, PSTR("help")))) {
_help();
cmd_found=true;
2011-10-28 15:43:43 -03:00
} else if (!strcasecmp_P(_argv[0].str, PSTR("exit"))) {
return;
}
}
2012-01-11 03:41:20 -04:00
if (cmd_found==false)
{
_port->println_P(PSTR("Invalid command, type 'help'"));
}
2012-01-11 03:41:20 -04:00
2011-10-28 15:43:43 -03:00
}
}
// display the list of commands in response to the 'help' command
void
Menu::_help(void)
{
int i;
2011-10-28 15:43:43 -03:00
_port->println_P(PSTR("Commands:"));
for (i = 0; i < _entries; i++) {
delay(10);
_port->printf_P(PSTR(" %S\n"), FPSTR(_commands[i].command));
}
}
// run the n'th command in the menu
int8_t
Menu::_call(uint8_t n, uint8_t argc)
{
func fn;
fn = (func)pgm_read_pointer(&_commands[n].func);
2011-10-28 15:43:43 -03:00
return(fn(argc, &_argv[0]));
}