AP_HAL_SITL: remove command-line option enabling synthetic clock

it's always on, all the time

this has always been set for many years
This commit is contained in:
Peter Barker 2025-01-13 16:16:17 +11:00 committed by Peter Barker
parent af908c5d2f
commit 6d31555236
3 changed files with 3 additions and 10 deletions

View File

@ -106,10 +106,8 @@ void SITL_State::_sitl_setup()
_sitl->rcin_port = _rcin_port;
}
if (_synthetic_clock_mode) {
// start with non-zero clock
hal.scheduler->stop_clock(1);
}
// start with non-zero clock
hal.scheduler->stop_clock(1);
}
@ -284,7 +282,6 @@ void SITL_State::_fdm_input_local(void)
set_height_agl();
_synthetic_clock_mode = true;
_update_count++;
}

View File

@ -87,8 +87,6 @@ private:
uint16_t _fg_view_port;
uint16_t _irlock_port;
bool _synthetic_clock_mode;
bool _use_rtscts;
bool _use_fg_view;

View File

@ -209,7 +209,6 @@ void SITL_State::_parse_command_line(int argc, char * const argv[])
float speedup = 1.0f;
float sim_rate_hz = 0;
_instance = 0;
_synthetic_clock_mode = false;
// default to CMAC
const char *home_str = nullptr;
const char *model_str = nullptr;
@ -422,7 +421,7 @@ void SITL_State::_parse_command_line(int argc, char * const argv[])
_set_param_default(gopt.optarg);
break;
case 'S':
_synthetic_clock_mode = true;
printf("Ignoring stale command-line parameter '-S'");
break;
case 'O':
home_str = gopt.optarg;
@ -586,7 +585,6 @@ void SITL_State::_parse_command_line(int argc, char * const argv[])
sitl_model->set_instance(_instance);
sitl_model->set_autotest_dir(autotest_dir);
sitl_model->set_config(config);
_synthetic_clock_mode = true;
break;
}
}