AP_Menu.cpp 5.8 KB

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