From 420c9c9d364dfe3a4f336db513b88bd836358d91 Mon Sep 17 00:00:00 2001 From: Pierre Kancir Date: Sun, 23 Aug 2020 08:25:40 +0200 Subject: [PATCH] AP_Param: use hal.util->set_cmdline_parameters() on SITL on reload_defaults_file() This allow to pass cmdline parameter to Param on start for each vehicle in the same way as param file --- libraries/AP_Param/AP_Param.cpp | 6 ++++++ 1 file changed, 6 insertions(+) diff --git a/libraries/AP_Param/AP_Param.cpp b/libraries/AP_Param/AP_Param.cpp index 933b026106..9806e824ee 100644 --- a/libraries/AP_Param/AP_Param.cpp +++ b/libraries/AP_Param/AP_Param.cpp @@ -33,6 +33,9 @@ #include #include #include +#if CONFIG_HAL_BOARD == HAL_BOARD_SITL + #include +#endif extern const AP_HAL::HAL &hal; @@ -1486,6 +1489,9 @@ void AP_Param::reload_defaults_file(bool last_pass) } } #endif +#if CONFIG_HAL_BOARD == HAL_BOARD_SITL + hal.util->set_cmdline_parameters(); +#endif }