@ -37,7 +37,7 @@ public:
virtual void system_initialized() = 0;
virtual void panic(const prog_char_t *errormsg) = 0;
virtual void reboot() = 0;
virtual void reboot(bool hold_in_bootloader) = 0;
};
#endif // __AP_HAL_SCHEDULER_H__
@ -212,7 +212,7 @@ void AVRScheduler::panic(const prog_char_t* errormsg) {
for(;;);
}
void AVRScheduler::reboot() {
void AVRScheduler::reboot(bool hold_in_bootloader) {
hal.uartA->println_P(PSTR("GOING DOWN FOR A REBOOT\r\n"));
hal.scheduler->delay(100);
#if CONFIG_HAL_BOARD == HAL_BOARD_APM2
@ -44,7 +44,7 @@ public:
void system_initialized();
void panic(const prog_char_t *errormsg);
void reboot();
void reboot(bool hold_in_bootloader);
private:
static AVRTimer _timer;
@ -161,7 +161,7 @@ void SITLScheduler::sitl_end_atomic() {
_nested_atomic_ctr--;
void SITLScheduler::reboot()
void SITLScheduler::reboot(bool hold_in_bootloader)
{
hal.uartA->println_P(PSTR("REBOOT NOT IMPLEMENTED\r\n"));
@ -34,7 +34,7 @@ public:
bool system_initializing();
bool interrupts_are_blocked(void) { return _nested_atomic_ctr != 0; }
@ -64,6 +64,6 @@ void EmptyScheduler::panic(const prog_char_t *errormsg) {
void EmptyScheduler::reboot() {
void EmptyScheduler::reboot(bool hold_in_bootloader) {
@ -31,7 +31,7 @@ public:
@ -168,9 +168,9 @@ void PX4Scheduler::resume_timer_procs()
void PX4Scheduler::reboot()
void PX4Scheduler::reboot(bool hold_in_bootloader)
systemreset(false);
systemreset(hold_in_bootloader);
void PX4Scheduler::_run_timers(bool called_from_timer_thread)
@ -35,7 +35,7 @@ public:
void register_timer_failsafe(AP_HAL::TimedProc, uint32_t period_us);
void suspend_timer_procs();
void resume_timer_procs();
bool in_timerprocess();
@ -246,7 +246,7 @@ void SMACCMScheduler::panic(const prog_char_t *errormsg)
;
void SMACCMScheduler::reboot()
void SMACCMScheduler::reboot(bool hold_in_bootloader)
for(;;)
@ -88,7 +88,7 @@ public:
/** Reboot the firmware. Not implemented. */
/**
* Run timed and deferred processes. This should not be called from