From d380447cd5f0ffd43b228f73e8664cf0dba50fa1 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Mon, 9 Nov 2020 08:48:25 +1100 Subject: [PATCH] HAL_SITL: support command line args for replay --- libraries/AP_HAL_SITL/HAL_SITL_Class.cpp | 1 + libraries/AP_HAL_SITL/UARTDriver.cpp | 2 ++ libraries/AP_HAL_SITL/Util.cpp | 9 +++++++++ libraries/AP_HAL_SITL/Util.h | 13 +++++++++++++ 4 files changed, 25 insertions(+) diff --git a/libraries/AP_HAL_SITL/HAL_SITL_Class.cpp b/libraries/AP_HAL_SITL/HAL_SITL_Class.cpp index 47dd2509c4..45ab9d3237 100644 --- a/libraries/AP_HAL_SITL/HAL_SITL_Class.cpp +++ b/libraries/AP_HAL_SITL/HAL_SITL_Class.cpp @@ -176,6 +176,7 @@ void HAL_SITL::run(int argc, char * const argv[], Callbacks* callbacks) const { assert(callbacks); + utilInstance.init(argc, argv); _sitl_state->init(argc, argv); scheduler->init(); diff --git a/libraries/AP_HAL_SITL/UARTDriver.cpp b/libraries/AP_HAL_SITL/UARTDriver.cpp index 0196e23a81..eca0ae62ac 100644 --- a/libraries/AP_HAL_SITL/UARTDriver.cpp +++ b/libraries/AP_HAL_SITL/UARTDriver.cpp @@ -593,6 +593,7 @@ bool UARTDriver::_select_check(int fd) if (fd == -1) { return false; } +#if !APM_BUILD_TYPE(APM_BUILD_Replay) fd_set fds; struct timeval tv; @@ -606,6 +607,7 @@ bool UARTDriver::_select_check(int fd) if (select(fd+1, &fds, nullptr, nullptr, &tv) == 1) { return true; } +#endif return false; } diff --git a/libraries/AP_HAL_SITL/Util.cpp b/libraries/AP_HAL_SITL/Util.cpp index d9d428151e..7c20fa2f54 100644 --- a/libraries/AP_HAL_SITL/Util.cpp +++ b/libraries/AP_HAL_SITL/Util.cpp @@ -147,4 +147,13 @@ void HALSITL::Util::set_cmdline_parameters() AP_Param::set_default_by_name(param.name, param.value); } } + +/** + return commandline arguments, if available +*/ +void HALSITL::Util::commandline_arguments(uint8_t &argc, char * const *&argv) +{ + argc = saved_argc; + argv = saved_argv; +} #endif diff --git a/libraries/AP_HAL_SITL/Util.h b/libraries/AP_HAL_SITL/Util.h index dacb7badf8..249f87f9df 100644 --- a/libraries/AP_HAL_SITL/Util.h +++ b/libraries/AP_HAL_SITL/Util.h @@ -33,6 +33,11 @@ public: return sitlState->defaults_path; } + /** + return commandline arguments, if available + */ + void commandline_arguments(uint8_t &argc, char * const *&argv) override; + uint64_t get_hw_rtc() const override; bool get_system_id(char buf[40]) override; @@ -71,6 +76,11 @@ public: #endif } + void init(int argc, char *const *argv) { + saved_argc = argc; + saved_argv = argv; + } + private: SITL_State *sitlState; @@ -88,4 +98,7 @@ private: size_t current_heap_usage; }; #endif // ENABLE_HEAP + + int saved_argc; + char *const *saved_argv; };