mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-21 23:33:57 -04:00
HAL_SITL: avoid sitl command line processing for replay
avoids need for -- arguments for replay
This commit is contained in:
parent
019544ceb1
commit
08291a15fb
@ -209,6 +209,7 @@ void SITL_State::_parse_command_line(int argc, char * const argv[])
|
||||
static struct timeval first_tv;
|
||||
gettimeofday(&first_tv, nullptr);
|
||||
time_t start_time_UTC = first_tv.tv_sec;
|
||||
const bool is_replay = APM_BUILD_TYPE(APM_BUILD_Replay);
|
||||
|
||||
enum long_options {
|
||||
CMDLINE_GIMBAL = 1,
|
||||
@ -272,10 +273,10 @@ void SITL_State::_parse_command_line(int argc, char * const argv[])
|
||||
{0, false, 0, 0}
|
||||
};
|
||||
|
||||
#if APM_BUILD_TYPE(APM_BUILD_Replay)
|
||||
model_str = "quad";
|
||||
HALSITL::UARTDriver::_console = true;
|
||||
#endif
|
||||
if (is_replay) {
|
||||
model_str = "quad";
|
||||
HALSITL::UARTDriver::_console = true;
|
||||
}
|
||||
|
||||
if (asprintf(&autotest_dir, SKETCHBOOK "/Tools/autotest") <= 0) {
|
||||
AP_HAL::panic("out of memory");
|
||||
@ -287,7 +288,7 @@ 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) {
|
||||
while (!is_replay && (opt = gopt.getoption()) != -1) {
|
||||
switch (opt) {
|
||||
case 'w':
|
||||
AP_Param::erase_all();
|
||||
|
Loading…
Reference in New Issue
Block a user