mirror of https://github.com/ArduPilot/ardupilot
AP_Menu: fixed crash bug in strtok_r() handling
on PX4 this causes a hard fault in CLI menus
This commit is contained in:
parent
b05117f5cd
commit
68051f3ea6
|
@ -39,7 +39,7 @@ Menu::run(void)
|
||||||
uint8_t len, i;
|
uint8_t len, i;
|
||||||
uint8_t argc;
|
uint8_t argc;
|
||||||
int c;
|
int c;
|
||||||
char *s;
|
char *s = NULL;
|
||||||
|
|
||||||
if (_port == NULL) {
|
if (_port == NULL) {
|
||||||
// default to main serial port
|
// default to main serial port
|
||||||
|
@ -87,6 +87,7 @@ Menu::run(void)
|
||||||
|
|
||||||
// split the input line into tokens
|
// split the input line into tokens
|
||||||
argc = 0;
|
argc = 0;
|
||||||
|
s = NULL;
|
||||||
_argv[argc++].str = strtok_r(_inbuf, " ", &s);
|
_argv[argc++].str = strtok_r(_inbuf, " ", &s);
|
||||||
// XXX should an empty line by itself back out of the current menu?
|
// XXX should an empty line by itself back out of the current menu?
|
||||||
while (argc <= MENU_ARGS_MAX) {
|
while (argc <= MENU_ARGS_MAX) {
|
||||||
|
|
Loading…
Reference in New Issue