mirror of https://github.com/ArduPilot/ardupilot
AP_HAL_SITL: fix rebooting while in sensor config error loop
This commit is contained in:
parent
9afb334f0c
commit
848a70acd4
|
@ -191,6 +191,11 @@ void HAL_SITL::run(int argc, char * const argv[], Callbacks* callbacks) const
|
|||
}
|
||||
}
|
||||
|
||||
actually_reboot();
|
||||
}
|
||||
|
||||
void HAL_SITL::actually_reboot()
|
||||
{
|
||||
execv(new_argv[0], new_argv);
|
||||
AP_HAL::panic("PANIC: REBOOT FAILED: %s", strerror(errno));
|
||||
}
|
||||
|
|
|
@ -12,6 +12,7 @@ class HAL_SITL : public AP_HAL::HAL {
|
|||
public:
|
||||
HAL_SITL();
|
||||
void run(int argc, char * const argv[], Callbacks* callbacks) const override;
|
||||
static void actually_reboot();
|
||||
|
||||
private:
|
||||
HALSITL::SITL_State *_sitl_state;
|
||||
|
|
|
@ -5,6 +5,7 @@
|
|||
#include "UARTDriver.h"
|
||||
#include <sys/time.h>
|
||||
#include <fenv.h>
|
||||
#include <AP_BoardConfig/AP_BoardConfig.h>
|
||||
#if defined (__clang__)
|
||||
#include <stdlib.h>
|
||||
#else
|
||||
|
@ -137,6 +138,12 @@ void Scheduler::sitl_end_atomic() {
|
|||
|
||||
void Scheduler::reboot(bool hold_in_bootloader)
|
||||
{
|
||||
if (AP_BoardConfig::in_sensor_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;
|
||||
}
|
||||
|
||||
|
|
Loading…
Reference in New Issue