Describe the issues that requires the +=2 on arg[c|v] for NuttX (#5293)

This may be moot and should be revisited if only px4_getops is used, but this pr politely documents the reson for the logic.
This commit is contained in:
David Sidrane 2016-08-10 06:19:59 -10:00 committed by GitHub
parent 17561daefb
commit deeefe5dd1
2 changed files with 7 additions and 2 deletions

View File

@ -1634,7 +1634,7 @@ Mavlink::task_main(int argc, char *argv[])
/* the NuttX optarg handler does not
* ignore argv[0] like the POSIX handler
* does, nor does it deal with non-flag
* verbs well. Remove the application
* verbs well. So we remove the application
* name and the verb.
*/
argc -= 2;

View File

@ -977,7 +977,12 @@ int sdlog2_thread_main(int argc, char *argv[])
flag_system_armed = false;
#ifdef __PX4_NUTTX
/* work around some stupidity in NuttX's task_create's argv handling */
/* the NuttX optarg handler does not
* ignore argv[0] like the POSIX handler
* does, nor does it deal with non-flag
* verbs well. So we Remove the application
* name and the verb.
*/
argc -= 2;
argv += 2;
#endif