From ea1e3f49289c49be09b2bdafdfd1cecd61c8e819 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Tue, 29 Dec 2015 18:53:05 +1100 Subject: [PATCH] HAL_QURT: pass argc and argv into main thread --- libraries/AP_HAL_QURT/dsp_main.cpp | 27 +++++++++++++++++++---- libraries/AP_HAL_QURT/mainapp/mainapp.cpp | 27 +++++++++++++++++++++-- libraries/AP_HAL_QURT/qurt_dsp.idl | 2 +- 3 files changed, 49 insertions(+), 7 deletions(-) diff --git a/libraries/AP_HAL_QURT/dsp_main.cpp b/libraries/AP_HAL_QURT/dsp_main.cpp index d94906487f..bd381f4acb 100644 --- a/libraries/AP_HAL_QURT/dsp_main.cpp +++ b/libraries/AP_HAL_QURT/dsp_main.cpp @@ -18,15 +18,34 @@ volatile int _last_dsp_line = __LINE__; volatile const char *_last_dsp_file = __FILE__; volatile uint32_t _last_counter; -static void *main_thread(void *) +static void *main_thread(void *cmdptr) { + char *cmdline = (char *)cmdptr; HAP_PRINTF("Ardupilot main_thread started"); - ArduPilot_main(0, NULL); + + // break cmdline into argc/argv + int argc = 0; + for (int i=0; cmdline[i]; i++) { + if (cmdline[i] == '\n') argc++; + } + const char **argv = (const char **)calloc(argc+2, sizeof(char *)); + argv[0] = &cmdline[0]; + argc = 0; + for (int i=0; cmdline[i]; i++) { + if (cmdline[i] == '\n') { + cmdline[i] = 0; + argv[argc+1] = &cmdline[i+1]; + argc++; + } + } + argv[argc] = nullptr; + + ArduPilot_main(argc, argv); return NULL; } -uint32_t ardupilot_start() +uint32_t ardupilot_start(const char *cmdline, int len) { HAP_PRINTF("Starting Ardupilot"); pthread_attr_t thread_attr; @@ -39,7 +58,7 @@ uint32_t ardupilot_start() param.sched_priority = APM_MAIN_PRIORITY; (void)pthread_attr_setschedparam(&thread_attr, ¶m); - pthread_create(&thread_ctx, &thread_attr, main_thread, NULL); + pthread_create(&thread_ctx, &thread_attr, main_thread, (void *)strdup((char*)cmdline)); return 0; } diff --git a/libraries/AP_HAL_QURT/mainapp/mainapp.cpp b/libraries/AP_HAL_QURT/mainapp/mainapp.cpp index 01ad16e8d0..c8752a03d7 100644 --- a/libraries/AP_HAL_QURT/mainapp/mainapp.cpp +++ b/libraries/AP_HAL_QURT/mainapp/mainapp.cpp @@ -108,6 +108,27 @@ static void socket_check(void) } } +/* + encode argv/argv as a sequence separated by \n + */ +static char *encode_argv(int argc, const char *argv[]) +{ + uint32_t len = 0; + for (int i=0; i 1000*1000) { diff --git a/libraries/AP_HAL_QURT/qurt_dsp.idl b/libraries/AP_HAL_QURT/qurt_dsp.idl index 727ecf1fd9..d813e29d50 100644 --- a/libraries/AP_HAL_QURT/qurt_dsp.idl +++ b/libraries/AP_HAL_QURT/qurt_dsp.idl @@ -2,7 +2,7 @@ interface ardupilot { // start main thread - uint32 start(); + uint32 start(in sequence cmdline); // a heartbeat for debugging uint32 heartbeat();