mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 14:38:30 -04:00
AP_Menu: allow menus to work on ports other than UART0
This commit is contained in:
parent
e194c6c740
commit
ba4b9b9961
@ -16,6 +16,8 @@
|
|||||||
// statics
|
// statics
|
||||||
char Menu::_inbuf[MENU_COMMANDLINE_MAX];
|
char Menu::_inbuf[MENU_COMMANDLINE_MAX];
|
||||||
Menu::arg Menu::_argv[MENU_ARGS_MAX + 1];
|
Menu::arg Menu::_argv[MENU_ARGS_MAX + 1];
|
||||||
|
FastSerial *Menu::_port;
|
||||||
|
|
||||||
|
|
||||||
// constructor
|
// constructor
|
||||||
Menu::Menu(const prog_char *prompt, const Menu::command *commands, uint8_t entries, preprompt ppfunc) :
|
Menu::Menu(const prog_char *prompt, const Menu::command *commands, uint8_t entries, preprompt ppfunc) :
|
||||||
@ -36,6 +38,11 @@ Menu::run(void)
|
|||||||
int c;
|
int c;
|
||||||
char *s;
|
char *s;
|
||||||
|
|
||||||
|
if (_port == NULL) {
|
||||||
|
// default to main serial port
|
||||||
|
_port = &Serial;
|
||||||
|
}
|
||||||
|
|
||||||
// loop performing commands
|
// loop performing commands
|
||||||
for (;; ) {
|
for (;; ) {
|
||||||
|
|
||||||
@ -45,32 +52,32 @@ Menu::run(void)
|
|||||||
|
|
||||||
// loop reading characters from the input
|
// loop reading characters from the input
|
||||||
len = 0;
|
len = 0;
|
||||||
Serial.printf("%S] ", FPSTR(_prompt));
|
_port->printf_P(PSTR("%S] "), FPSTR(_prompt));
|
||||||
for (;; ) {
|
for (;; ) {
|
||||||
c = Serial.read();
|
c = _port->read();
|
||||||
if (-1 == c)
|
if (-1 == c)
|
||||||
continue;
|
continue;
|
||||||
// carriage return -> process command
|
// carriage return -> process command
|
||||||
if ('\r' == c) {
|
if ('\r' == c) {
|
||||||
_inbuf[len] = '\0';
|
_inbuf[len] = '\0';
|
||||||
Serial.write('\r');
|
_port->write('\r');
|
||||||
Serial.write('\n');
|
_port->write('\n');
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
// backspace
|
// backspace
|
||||||
if ('\b' == c) {
|
if ('\b' == c) {
|
||||||
if (len > 0) {
|
if (len > 0) {
|
||||||
len--;
|
len--;
|
||||||
Serial.write('\b');
|
_port->write('\b');
|
||||||
Serial.write(' ');
|
_port->write(' ');
|
||||||
Serial.write('\b');
|
_port->write('\b');
|
||||||
continue;
|
continue;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
// printable character
|
// printable character
|
||||||
if (isprint(c) && (len < (MENU_COMMANDLINE_MAX - 1))) {
|
if (isprint(c) && (len < (MENU_COMMANDLINE_MAX - 1))) {
|
||||||
_inbuf[len++] = c;
|
_inbuf[len++] = c;
|
||||||
Serial.write((char)c);
|
_port->write((char)c);
|
||||||
continue;
|
continue;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
@ -127,7 +134,7 @@ Menu::run(void)
|
|||||||
|
|
||||||
if (cmd_found==false)
|
if (cmd_found==false)
|
||||||
{
|
{
|
||||||
Serial.println("Invalid command, type 'help'");
|
_port->println_P(PSTR("Invalid command, type 'help'"));
|
||||||
}
|
}
|
||||||
|
|
||||||
}
|
}
|
||||||
@ -139,9 +146,11 @@ Menu::_help(void)
|
|||||||
{
|
{
|
||||||
int i;
|
int i;
|
||||||
|
|
||||||
Serial.println("Commands:");
|
_port->println_P(PSTR("Commands:"));
|
||||||
for (i = 0; i < _entries; i++)
|
for (i = 0; i < _entries; i++) {
|
||||||
Serial.printf(" %S\n", FPSTR(_commands[i].command));
|
delay(10);
|
||||||
|
_port->printf_P(PSTR(" %S\n"), FPSTR(_commands[i].command));
|
||||||
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
// run the n'th command in the menu
|
// run the n'th command in the menu
|
||||||
|
@ -56,6 +56,10 @@ public:
|
|||||||
///
|
///
|
||||||
typedef int8_t (*func)(uint8_t argc, const struct arg *argv);
|
typedef int8_t (*func)(uint8_t argc, const struct arg *argv);
|
||||||
|
|
||||||
|
static void set_port(FastSerial *port) {
|
||||||
|
_port = port;
|
||||||
|
}
|
||||||
|
|
||||||
/// menu pre-prompt function
|
/// menu pre-prompt function
|
||||||
///
|
///
|
||||||
/// Called immediately before waiting for the user to type a command; can be
|
/// Called immediately before waiting for the user to type a command; can be
|
||||||
@ -120,6 +124,9 @@ private:
|
|||||||
|
|
||||||
static char _inbuf[MENU_COMMANDLINE_MAX]; ///< input buffer
|
static char _inbuf[MENU_COMMANDLINE_MAX]; ///< input buffer
|
||||||
static arg _argv[MENU_ARGS_MAX + 1]; ///< arguments
|
static arg _argv[MENU_ARGS_MAX + 1]; ///< arguments
|
||||||
|
|
||||||
|
// port to run on
|
||||||
|
static FastSerial *_port;
|
||||||
};
|
};
|
||||||
|
|
||||||
/// Macros used to define a menu.
|
/// Macros used to define a menu.
|
||||||
|
Loading…
Reference in New Issue
Block a user