APM:Libraries
AP_Menu.cpp
Go to the documentation of this file.
1 //
2 // Simple commandline menu system.
3 #include "AP_Menu.h"
4 
5 #include <ctype.h>
6 #include <stdlib.h>
7 #include <string.h>
8 
9 #include <AP_Common/AP_Common.h>
10 #include <AP_HAL/AP_HAL.h>
11 
12 extern const AP_HAL::HAL& hal;
13 
14 // statics
15 char *Menu::_inbuf;
18 
19 
20 // constructor
21 Menu::Menu(const char *prompt, const Menu::command *commands, uint8_t entries, preprompt ppfunc) :
22  _prompt(prompt),
23  _commands(commands),
24  _entries(entries),
25  _ppfunc(ppfunc),
26  _commandline_max(MENU_COMMANDLINE_MAX),
27  _args_max(MENU_ARGS_MAX)
28 {
29  // the buffers are initially nullptr, then they are allocated on
30  // first use
31  _inbuf = nullptr;
32  _argv = nullptr;
33 }
34 
39 bool
41 {
42  if (_port->available() <= 0) {
43  return false;
44  }
45 
46  // loop reading characters from the input
47  int c = _port->read();
48 
49  // carriage return -> process command
50  if ('\r' == c || '\n' == c) {
51  _inbuf[_input_len] = '\0';
52  _port->write('\r');
53  _port->write('\n');
54  // we have a full line to process
55  return true;
56  }
57 
58  // backspace
59  if ('\b' == c) {
60  if (_input_len > 0) {
61  _input_len--;
62  _port->write('\b');
63  _port->write(' ');
64  _port->write('\b');
65  return false;
66  }
67  }
68 
69  // printable character
70  if (isprint(c) && (_input_len < (_commandline_max - 1))) {
71  _inbuf[_input_len++] = c;
72  _port->write((char)c);
73  }
74 
75  return false;
76 }
77 
78 // display the prompt
79 void
81 {
82  _port->printf("%s] ", _prompt);
83 }
84 
85 // run the menu
86 bool
87 Menu::_run_command(bool prompt_on_enter)
88 {
89  int8_t ret;
90  uint8_t i;
91  uint8_t argc;
92  char *s = nullptr;
93 
94  _input_len = 0;
95 
96  // split the input line into tokens
97  argc = 0;
98  s = nullptr;
99  _argv[argc++].str = strtok_r(_inbuf, " ", &s);
100 
101  // XXX should an empty line by itself back out of the current menu?
102  while (argc <= _args_max) {
103  _argv[argc].str = strtok_r(nullptr, " ", &s);
104  if (_argv[argc].str == nullptr || '\0' == _argv[argc].str[0])
105  break;
106  _argv[argc].i = atol(_argv[argc].str);
107  _argv[argc].f = atof(_argv[argc].str); // calls strtod, > 700B !
108  argc++;
109  }
110 
111  if (_argv[0].str == nullptr) {
112  // we got a blank line, re-display the prompt
113  if (prompt_on_enter) {
114  _display_prompt();
115  }
116  return false;
117  }
118 
119  // populate arguments that have not been specified with "" and 0
120  // this is safer than NULL in the case where commands may look
121  // without testing argc
122  i = argc;
123  while (i <= _args_max) {
124  _argv[i].str = "";
125  _argv[i].i = 0;
126  _argv[i].f = 0;
127  i++;
128  }
129 
130  bool cmd_found = false;
131  // look for a command matching the first word (note that it may be empty)
132  for (i = 0; i < _entries; i++) {
133  if (!strcasecmp(_argv[0].str, _commands[i].command)) {
134  ret = _call(i, argc);
135  cmd_found=true;
136  if (-2 == ret)
137  return true;
138  break;
139  }
140  }
141 
142  // implicit commands
143  if (i == _entries) {
144  if (!strcmp(_argv[0].str, "?") || (!strcasecmp(_argv[0].str, "help"))) {
145  _help();
146  cmd_found=true;
147  } else if (!strcasecmp(_argv[0].str, "exit")) {
148  // exit the menu
149  return true;
150  }
151  }
152 
153  if (cmd_found==false)
154  {
155  _port->printf("Invalid command, type 'help'\n");
156  }
157 
158  return false;
159 }
160 
161 
162 // run the menu
163 void
165 {
166  if (_port == nullptr) {
167  // default to main serial port
168  _port = hal.console;
169  }
170 
172 
173  _display_prompt();
174 
175  // loop performing commands
176  for (;;) {
177 
178  // run the pre-prompt function, if one is defined
179  if (_ppfunc) {
180  if (!_ppfunc())
181  return;
182  _display_prompt();
183  }
184 
185  // loop reading characters from the input
186  _input_len = 0;
187 
188  for (;; ) {
189  if (_check_for_input()) {
190  break;
191  }
192  hal.scheduler->delay(20);
193  }
194 
195  // we have a full command to run
196  if (_run_command(false)) break;
197 
198  _display_prompt();
199  }
200 }
201 
202 // check for new user input
203 bool
205 {
206  if (_port == nullptr) {
207  // default to main serial port
208  _port = hal.console;
209  }
210 
212 
213  if (_check_for_input()) {
214  return _run_command(true);
215  }
216 
217  return false;
218 }
219 
220 // display the list of commands in response to the 'help' command
221 void
223 {
224  int i;
225 
226  _port->printf("Commands:\n");
227  for (i = 0; i < _entries; i++) {
228  hal.scheduler->delay(10);
229  _port->printf(" %s\n", _commands[i].command);
230  }
231 }
232 
233 // run the n'th command in the menu
234 int8_t
235 Menu::_call(uint8_t n, uint8_t argc)
236 {
237  return _commands[n].func(argc, &_argv[0]);
238 }
239 
243 void
244 Menu::set_limits(uint8_t commandline_max, uint8_t args_max)
245 {
246  if (_inbuf != nullptr) {
247  delete[] _inbuf;
248  _inbuf = nullptr;
249  }
250  if (_argv != nullptr) {
251  delete[] _argv;
252  _argv = nullptr;
253  }
254  // remember limits, the buffers will be allocated by allocate_buffers()
255  _commandline_max = commandline_max;
256  _args_max = args_max;
257 }
258 
259 void
261 {
262  /* only allocate if the buffers are nullptr */
263  if (_inbuf == nullptr) {
264  _inbuf = new char[_commandline_max];
265  memset(_inbuf, 0, _commandline_max);
266  }
267  if (_argv == nullptr) {
268  _argv = new arg[_args_max+1];
269  memset(_argv, 0, (_args_max+1) * sizeof(_argv[0]));
270  }
271 }
Menu_Commands commands
Definition: RCOutput.cpp:33
bool check_input(void)
Definition: AP_Menu.cpp:204
AP_HAL::UARTDriver * console
Definition: HAL.h:110
bool _check_for_input(void)
Definition: AP_Menu.cpp:40
Menu(const char *prompt, const struct command *commands, uint8_t entries, preprompt ppfunc=0)
Definition: AP_Menu.cpp:21
float f
floating point form of the argument (if a number)
Definition: AP_Menu.h:37
const char * str
string form of the argument
Definition: AP_Menu.h:35
static arg * _argv
arguments
Definition: AP_Menu.h:131
#define MENU_ARGS_MAX
maximum number of arguments
Definition: AP_Menu.h:19
virtual void delay(uint16_t ms)=0
void _allocate_buffers(void)
Definition: AP_Menu.cpp:260
void _help(void)
implements the &#39;help&#39; command
Definition: AP_Menu.cpp:222
virtual void printf(const char *,...) FMT_PRINTF(2
Definition: BetterStream.cpp:5
void run(void)
menu runner
Definition: AP_Menu.cpp:164
virtual size_t write(uint8_t)=0
virtual int16_t read()=0
const AP_HAL::HAL & hal
-*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
Definition: AC_PID_test.cpp:14
uint8_t _commandline_max
Definition: AP_Menu.h:133
const preprompt _ppfunc
optional pre-prompt action
Definition: AP_Menu.h:128
const command * _commands
array of commands
Definition: AP_Menu.h:126
Common definitions and utility routines for the ArduPilot libraries.
virtual uint32_t available()=0
bool _run_command(bool prompt_on_enter)
Definition: AP_Menu.cpp:87
static AP_HAL::BetterStream * _port
Definition: AP_Menu.h:152
uint8_t _args_max
Definition: AP_Menu.h:134
int8_t _call(uint8_t n, uint8_t argc)
Definition: AP_Menu.cpp:235
#define MENU_COMMANDLINE_MAX
maximum input line length
Definition: AP_Menu.h:18
const uint8_t _entries
size of the menu
Definition: AP_Menu.h:127
uint8_t _input_len
Definition: AP_Menu.h:140
long i
integer form of the argument (if a number)
Definition: AP_Menu.h:36
const char * _prompt
prompt to display
Definition: AP_Menu.h:125
static char * _inbuf
input buffer
Definition: AP_Menu.h:130
void set_limits(uint8_t commandline_max, uint8_t args_max)
set command line length limit
Definition: AP_Menu.cpp:244
void _display_prompt()
Definition: AP_Menu.cpp:80
AP_HAL::Scheduler * scheduler
Definition: HAL.h:114