AP_HAL_SITL: do not return from reboot command

This structure was set up to mimic the should_exit code originally from the Linux HAL.  It runs contrary to the intent of the HAL reboot call, which is not expected to return.  This oddity leads us to emit wo acks sequentially, one success, one failure, which is just weird.
This commit is contained in:
Peter Barker 2022-09-14 10:18:19 +10:00 committed by Peter Barker
parent 25c3665277
commit fb3a7d0d10
3 changed files with 3 additions and 10 deletions

View File

@ -264,7 +264,7 @@ void HAL_SITL::run(int argc, char * const argv[], Callbacks* callbacks) const
uint32_t last_watchdog_save = AP_HAL::millis();
uint8_t fill_count = 0;
while (!HALSITL::Scheduler::_should_reboot) {
while (true) {
if (HALSITL::Scheduler::_should_exit) {
::fprintf(stderr, "Exitting\n");
exit(0);

View File

@ -38,7 +38,6 @@ bool Scheduler::_in_timer_proc = false;
AP_HAL::MemberProc Scheduler::_io_proc[SITL_SCHEDULER_MAX_TIMER_PROCS] = {nullptr};
uint8_t Scheduler::_num_io_procs = 0;
bool Scheduler::_in_io_proc = false;
bool Scheduler::_should_reboot = false;
bool Scheduler::_should_exit = false;
bool Scheduler::_in_semaphore_take_wait = false;
@ -217,13 +216,8 @@ void Scheduler::sitl_end_atomic() {
void Scheduler::reboot(bool hold_in_bootloader)
{
if (AP_BoardConfig::in_config_error()) {
// the _should_reboot flag set below is not checked by the
// sensor-config-error loop, so force the reboot here:
HAL_SITL::actually_reboot();
abort();
}
_should_reboot = true;
HAL_SITL::actually_reboot();
abort();
}
void Scheduler::_run_timer_procs()

View File

@ -50,7 +50,6 @@ public:
uint64_t stopped_clock_usec() const { return _stopped_clock_usec; }
static void _run_io_procs();
static bool _should_reboot;
static bool _should_exit;
/*