diff --git a/libraries/AP_HAL_SITL/SITL_State.h b/libraries/AP_HAL_SITL/SITL_State.h index b117d8333e..d4b0bcc556 100644 --- a/libraries/AP_HAL_SITL/SITL_State.h +++ b/libraries/AP_HAL_SITL/SITL_State.h @@ -14,6 +14,7 @@ #include #include #include +#include #include #include @@ -105,6 +106,7 @@ public: "tcp:5", "tcp:6", }; + std::vector cmdline_param; /* parse a home location string */ static bool parse_home(const char *home_str, diff --git a/libraries/AP_HAL_SITL/SITL_cmdline.cpp b/libraries/AP_HAL_SITL/SITL_cmdline.cpp index a7a57f40a9..5622e24d27 100644 --- a/libraries/AP_HAL_SITL/SITL_cmdline.cpp +++ b/libraries/AP_HAL_SITL/SITL_cmdline.cpp @@ -8,6 +8,7 @@ #include "UARTDriver.h" #include #include +#include #include #include @@ -201,6 +202,7 @@ void SITL_State::_parse_command_line(int argc, char * const argv[]) uint16_t simulator_port_in = SIM_IN_PORT; uint16_t simulator_port_out = SIM_OUT_PORT; _irlock_port = IRLOCK_PORT; + struct AP_Param::defaults_table_struct temp_cmdline_param{}; // Set default start time to the real system time. // This will be overwritten if argument provided. @@ -280,7 +282,6 @@ void SITL_State::_parse_command_line(int argc, char * const argv[]) GetOptLong gopt(argc, argv, "hwus:r:CI:P:SO:M:F:c:", options); - while ((opt = gopt.getoption()) != -1) { switch (opt) { case 'w': @@ -292,9 +293,9 @@ void SITL_State::_parse_command_line(int argc, char * const argv[]) break; case 's': speedup = strtof(gopt.optarg, nullptr); - char speedup_string[18]; - snprintf(speedup_string, sizeof(speedup_string), "SIM_SPEEDUP=%s", gopt.optarg); - _set_param_default(speedup_string); + temp_cmdline_param = {"SIM_SPEEDUP", speedup}; + cmdline_param.push_back(temp_cmdline_param); + printf("Setting SIM_SPEEDUP=%f\n", speedup); break; case 'r': _framerate = (unsigned)atoi(gopt.optarg); @@ -394,9 +395,9 @@ void SITL_State::_parse_command_line(int argc, char * const argv[]) fprintf(stderr, "You must specify a SYSID greater than 0 and less than 256\n"); exit(1); } - char sysid_string[18]; - snprintf(sysid_string, sizeof(sysid_string), "SYSID_THISMAV=%s", gopt.optarg); - _set_param_default(sysid_string); + temp_cmdline_param = {"SYSID_THISMAV", static_cast(sysid)}; + cmdline_param.push_back(temp_cmdline_param); + printf("Setting SYSID_THISMAV=%d\n", sysid); break; } default: diff --git a/libraries/AP_HAL_SITL/Util.cpp b/libraries/AP_HAL_SITL/Util.cpp index 7c368972a9..b984cb04ab 100644 --- a/libraries/AP_HAL_SITL/Util.cpp +++ b/libraries/AP_HAL_SITL/Util.cpp @@ -1,5 +1,6 @@ #include "Util.h" #include +#include #ifdef WITH_SITL_TONEALARM HALSITL::ToneAlarm_SF HALSITL::Util::_toneAlarm; @@ -138,3 +139,10 @@ enum AP_HAL::Util::safety_state HALSITL::Util::safety_switch_state(void) } return sitl->safety_switch_state(); } + +void HALSITL::Util::set_cmdline_parameters() +{ + for (auto param: sitlState->cmdline_param) { + AP_Param::set_default_by_name(param.name, param.value); + } +} diff --git a/libraries/AP_HAL_SITL/Util.h b/libraries/AP_HAL_SITL/Util.h index 7895aa740b..ed06fe249f 100644 --- a/libraries/AP_HAL_SITL/Util.h +++ b/libraries/AP_HAL_SITL/Util.h @@ -68,6 +68,7 @@ public: #endif } + void set_cmdline_parameters() override; private: SITL_State *sitlState;