50 if (
'\r' == c ||
'\n' == c) {
103 _argv[argc].
str = strtok_r(
nullptr,
" ", &s);
104 if (
_argv[argc].str ==
nullptr ||
'\0' ==
_argv[argc].str[0])
111 if (
_argv[0].str ==
nullptr) {
113 if (prompt_on_enter) {
130 bool cmd_found =
false;
134 ret =
_call(i, argc);
144 if (!strcmp(
_argv[0].str,
"?") || (!strcasecmp(
_argv[0].str,
"help"))) {
147 }
else if (!strcasecmp(
_argv[0].str,
"exit")) {
153 if (cmd_found==
false)
166 if (
_port ==
nullptr) {
206 if (
_port ==
nullptr) {
250 if (
_argv !=
nullptr) {
267 if (
_argv ==
nullptr) {
AP_HAL::UARTDriver * console
virtual void delay(uint16_t ms)=0
virtual void printf(const char *,...) FMT_PRINTF(2
virtual size_t write(uint8_t)=0
Common definitions and utility routines for the ArduPilot libraries.
virtual uint32_t available()=0
AP_HAL::Scheduler * scheduler