mirror of https://github.com/ArduPilot/ardupilot
HAL_SITL: avoid std::vector in command line handling
use ObjectArray instead
This commit is contained in:
parent
c764e60aa0
commit
4f6653e5c7
|
@ -1,6 +1,7 @@
|
|||
#pragma once
|
||||
|
||||
#include <AP_HAL/AP_HAL.h>
|
||||
#include <AP_HAL/utility/RingBuffer.h>
|
||||
|
||||
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL
|
||||
|
||||
|
@ -40,7 +41,7 @@ public:
|
|||
"tcp:7",
|
||||
"tcp:8",
|
||||
};
|
||||
std::vector<struct AP_Param::defaults_table_struct> cmdline_param;
|
||||
ObjectArray<struct AP_Param::defaults_table_struct> cmdline_param{100};
|
||||
|
||||
/* parse a home location string */
|
||||
static bool parse_home(const char *home_str,
|
||||
|
|
|
@ -384,13 +384,13 @@ void SITL_State::_parse_command_line(int argc, char * const argv[])
|
|||
case 's':
|
||||
speedup = strtof(gopt.optarg, nullptr);
|
||||
temp_cmdline_param = {"SIM_SPEEDUP", speedup};
|
||||
cmdline_param.push_back(temp_cmdline_param);
|
||||
cmdline_param.push(temp_cmdline_param);
|
||||
printf("Setting SIM_SPEEDUP=%f\n", speedup);
|
||||
break;
|
||||
case 'r':
|
||||
sim_rate_hz = strtof(gopt.optarg, nullptr);
|
||||
temp_cmdline_param = {"SIM_RATE_HZ", sim_rate_hz};
|
||||
cmdline_param.push_back(temp_cmdline_param);
|
||||
cmdline_param.push(temp_cmdline_param);
|
||||
printf("Setting SIM_RATE_HZ=%f\n", sim_rate_hz);
|
||||
break;
|
||||
case 'C':
|
||||
|
@ -513,7 +513,7 @@ void SITL_State::_parse_command_line(int argc, char * const argv[])
|
|||
exit(1);
|
||||
}
|
||||
temp_cmdline_param = {"SYSID_THISMAV", static_cast<float>(sysid)};
|
||||
cmdline_param.push_back(temp_cmdline_param);
|
||||
cmdline_param.push(temp_cmdline_param);
|
||||
printf("Setting SYSID_THISMAV=%d\n", sysid);
|
||||
break;
|
||||
}
|
||||
|
|
|
@ -160,8 +160,11 @@ enum AP_HAL::Util::safety_state HALSITL::Util::safety_switch_state(void)
|
|||
|
||||
void HALSITL::Util::set_cmdline_parameters()
|
||||
{
|
||||
for (auto param: sitlState->cmdline_param) {
|
||||
AP_Param::set_default_by_name(param.name, param.value);
|
||||
for (uint16_t i=0; i<sitlState->cmdline_param.available(); i++) {
|
||||
const auto param = sitlState->cmdline_param[i];
|
||||
if (param != nullptr) {
|
||||
AP_Param::set_default_by_name(param->name, param->value);
|
||||
}
|
||||
}
|
||||
}
|
||||
#endif
|
||||
|
|
Loading…
Reference in New Issue