mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 14:38:30 -04:00
AP_HAL: added hold_in_bootloader parameter to scheduler->reboot()
This commit is contained in:
parent
1328316bfc
commit
7082e0f8aa
@ -37,7 +37,7 @@ public:
|
|||||||
virtual void system_initialized() = 0;
|
virtual void system_initialized() = 0;
|
||||||
|
|
||||||
virtual void panic(const prog_char_t *errormsg) = 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__
|
#endif // __AP_HAL_SCHEDULER_H__
|
||||||
|
@ -212,7 +212,7 @@ void AVRScheduler::panic(const prog_char_t* errormsg) {
|
|||||||
for(;;);
|
for(;;);
|
||||||
}
|
}
|
||||||
|
|
||||||
void AVRScheduler::reboot() {
|
void AVRScheduler::reboot(bool hold_in_bootloader) {
|
||||||
hal.uartA->println_P(PSTR("GOING DOWN FOR A REBOOT\r\n"));
|
hal.uartA->println_P(PSTR("GOING DOWN FOR A REBOOT\r\n"));
|
||||||
hal.scheduler->delay(100);
|
hal.scheduler->delay(100);
|
||||||
#if CONFIG_HAL_BOARD == HAL_BOARD_APM2
|
#if CONFIG_HAL_BOARD == HAL_BOARD_APM2
|
||||||
|
@ -44,7 +44,7 @@ public:
|
|||||||
void system_initialized();
|
void system_initialized();
|
||||||
|
|
||||||
void panic(const prog_char_t *errormsg);
|
void panic(const prog_char_t *errormsg);
|
||||||
void reboot();
|
void reboot(bool hold_in_bootloader);
|
||||||
|
|
||||||
private:
|
private:
|
||||||
static AVRTimer _timer;
|
static AVRTimer _timer;
|
||||||
|
@ -161,7 +161,7 @@ void SITLScheduler::sitl_end_atomic() {
|
|||||||
_nested_atomic_ctr--;
|
_nested_atomic_ctr--;
|
||||||
}
|
}
|
||||||
|
|
||||||
void SITLScheduler::reboot()
|
void SITLScheduler::reboot(bool hold_in_bootloader)
|
||||||
{
|
{
|
||||||
hal.uartA->println_P(PSTR("REBOOT NOT IMPLEMENTED\r\n"));
|
hal.uartA->println_P(PSTR("REBOOT NOT IMPLEMENTED\r\n"));
|
||||||
}
|
}
|
||||||
|
@ -34,7 +34,7 @@ public:
|
|||||||
bool system_initializing();
|
bool system_initializing();
|
||||||
void system_initialized();
|
void system_initialized();
|
||||||
|
|
||||||
void reboot();
|
void reboot(bool hold_in_bootloader);
|
||||||
void panic(const prog_char_t *errormsg);
|
void panic(const prog_char_t *errormsg);
|
||||||
|
|
||||||
bool interrupts_are_blocked(void) { return _nested_atomic_ctr != 0; }
|
bool interrupts_are_blocked(void) { return _nested_atomic_ctr != 0; }
|
||||||
|
@ -64,6 +64,6 @@ void EmptyScheduler::panic(const prog_char_t *errormsg) {
|
|||||||
for(;;);
|
for(;;);
|
||||||
}
|
}
|
||||||
|
|
||||||
void EmptyScheduler::reboot() {
|
void EmptyScheduler::reboot(bool hold_in_bootloader) {
|
||||||
for(;;);
|
for(;;);
|
||||||
}
|
}
|
||||||
|
@ -31,7 +31,7 @@ public:
|
|||||||
void system_initialized();
|
void system_initialized();
|
||||||
|
|
||||||
void panic(const prog_char_t *errormsg);
|
void panic(const prog_char_t *errormsg);
|
||||||
void reboot();
|
void reboot(bool hold_in_bootloader);
|
||||||
|
|
||||||
};
|
};
|
||||||
|
|
||||||
|
@ -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)
|
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 register_timer_failsafe(AP_HAL::TimedProc, uint32_t period_us);
|
||||||
void suspend_timer_procs();
|
void suspend_timer_procs();
|
||||||
void resume_timer_procs();
|
void resume_timer_procs();
|
||||||
void reboot();
|
void reboot(bool hold_in_bootloader);
|
||||||
void panic(const prog_char_t *errormsg);
|
void panic(const prog_char_t *errormsg);
|
||||||
|
|
||||||
bool in_timerprocess();
|
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(;;)
|
for(;;)
|
||||||
;
|
;
|
||||||
|
@ -88,7 +88,7 @@ public:
|
|||||||
void panic(const prog_char_t *errormsg);
|
void panic(const prog_char_t *errormsg);
|
||||||
|
|
||||||
/** Reboot the firmware. Not implemented. */
|
/** Reboot the firmware. Not implemented. */
|
||||||
void reboot();
|
void reboot(bool hold_in_bootloader);
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Run timed and deferred processes. This should not be called from
|
* Run timed and deferred processes. This should not be called from
|
||||||
|
Loading…
Reference in New Issue
Block a user