mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-11 02:13:57 -04:00
AP_HAL: turn panic() into a variadic method
Change the declaration on all HAL implementations so panic() in future may implement a printf-like interface.
This commit is contained in:
parent
0b4aa5ac85
commit
ad61a93c14
@ -56,7 +56,7 @@ public:
|
||||
virtual bool system_initializing() = 0;
|
||||
virtual void system_initialized() = 0;
|
||||
|
||||
virtual void panic(const prog_char_t *errormsg) NORETURN = 0;
|
||||
virtual void panic(const prog_char_t *errormsg, ...) NORETURN = 0;
|
||||
virtual void reboot(bool hold_in_bootloader) = 0;
|
||||
|
||||
/**
|
||||
|
@ -225,7 +225,7 @@ void AVRScheduler::system_initialized() {
|
||||
_initialized = true;
|
||||
}
|
||||
|
||||
void AVRScheduler::panic(const prog_char_t* errormsg) {
|
||||
void AVRScheduler::panic(const prog_char_t* errormsg, ...) {
|
||||
/* Suspend timer processes. We still want the timer event to go off
|
||||
* to run the _failsafe code, however. */
|
||||
_timer_suspended = true;
|
||||
|
@ -45,7 +45,7 @@ public:
|
||||
bool system_initializing();
|
||||
void system_initialized();
|
||||
|
||||
void panic(const prog_char_t *errormsg) NORETURN;
|
||||
void panic(const prog_char_t *errormsg, ...) NORETURN;
|
||||
void reboot(bool hold_in_bootloader);
|
||||
|
||||
void set_timer_speed(uint16_t timer_hz);
|
||||
|
@ -69,7 +69,7 @@ bool EmptyScheduler::system_initializing() {
|
||||
void EmptyScheduler::system_initialized()
|
||||
{}
|
||||
|
||||
void EmptyScheduler::panic(const prog_char_t *errormsg) {
|
||||
void EmptyScheduler::panic(const prog_char_t *errormsg, ...) {
|
||||
hal.console->println_P(errormsg);
|
||||
for(;;);
|
||||
}
|
||||
|
@ -32,7 +32,7 @@ public:
|
||||
bool system_initializing();
|
||||
void system_initialized();
|
||||
|
||||
void panic(const prog_char_t *errormsg) NORETURN;
|
||||
void panic(const prog_char_t *errormsg, ...) NORETURN;
|
||||
void reboot(bool hold_in_bootloader);
|
||||
|
||||
};
|
||||
|
@ -228,7 +228,7 @@ void FLYMAPLEScheduler::system_initialized()
|
||||
_initialized = true;
|
||||
}
|
||||
|
||||
void FLYMAPLEScheduler::panic(const prog_char_t *errormsg) {
|
||||
void FLYMAPLEScheduler::panic(const prog_char_t *errormsg, ...) {
|
||||
/* Suspend timer processes. We still want the timer event to go off
|
||||
* to run the _failsafe code, however. */
|
||||
// REVISIT: not tested on FLYMAPLE
|
||||
|
@ -53,7 +53,7 @@ public:
|
||||
bool system_initializing();
|
||||
void system_initialized();
|
||||
|
||||
void panic(const prog_char_t *errormsg) NORETURN;
|
||||
void panic(const prog_char_t *errormsg, ...) NORETURN;
|
||||
void reboot(bool hold_in_bootloader);
|
||||
|
||||
private:
|
||||
|
@ -407,7 +407,7 @@ void *Scheduler::_io_thread(void* arg)
|
||||
return NULL;
|
||||
}
|
||||
|
||||
void Scheduler::panic(const prog_char_t *errormsg)
|
||||
void Scheduler::panic(const prog_char_t *errormsg, ...)
|
||||
{
|
||||
write(1, errormsg, strlen(errormsg));
|
||||
write(1, "\n", 1);
|
||||
|
@ -43,7 +43,7 @@ public:
|
||||
bool system_initializing();
|
||||
void system_initialized();
|
||||
|
||||
void panic(const prog_char_t *errormsg) NORETURN;
|
||||
void panic(const prog_char_t *errormsg, ...) NORETURN;
|
||||
void reboot(bool hold_in_bootloader);
|
||||
|
||||
void stop_clock(uint64_t time_usec);
|
||||
|
@ -374,7 +374,7 @@ void *PX4Scheduler::_storage_thread(void)
|
||||
return NULL;
|
||||
}
|
||||
|
||||
void PX4Scheduler::panic(const prog_char_t *errormsg)
|
||||
void PX4Scheduler::panic(const prog_char_t *errormsg, ...)
|
||||
{
|
||||
write(1, errormsg, strlen(errormsg));
|
||||
write(1, "\n", 1);
|
||||
|
@ -60,7 +60,7 @@ public:
|
||||
void suspend_timer_procs();
|
||||
void resume_timer_procs();
|
||||
void reboot(bool hold_in_bootloader);
|
||||
void panic(const prog_char_t *errormsg) NORETURN;
|
||||
void panic(const prog_char_t *errormsg, ...) NORETURN;
|
||||
|
||||
bool in_timerprocess();
|
||||
bool system_initializing();
|
||||
|
@ -259,7 +259,7 @@ void SITLScheduler::_run_io_procs(bool called_from_isr)
|
||||
_in_io_proc = false;
|
||||
}
|
||||
|
||||
void SITLScheduler::panic(const prog_char_t *errormsg) {
|
||||
void SITLScheduler::panic(const prog_char_t *errormsg, ...) {
|
||||
hal.console->println_P(errormsg);
|
||||
for(;;);
|
||||
}
|
||||
|
@ -41,7 +41,7 @@ public:
|
||||
void system_initialized();
|
||||
|
||||
void reboot(bool hold_in_bootloader);
|
||||
void panic(const prog_char_t *errormsg) NORETURN;
|
||||
void panic(const prog_char_t *errormsg, ...) NORETURN;
|
||||
|
||||
bool interrupts_are_blocked(void) {
|
||||
return _nested_atomic_ctr != 0;
|
||||
|
@ -325,7 +325,7 @@ void *VRBRAINScheduler::_io_thread(void)
|
||||
return NULL;
|
||||
}
|
||||
|
||||
void VRBRAINScheduler::panic(const prog_char_t *errormsg)
|
||||
void VRBRAINScheduler::panic(const prog_char_t *errormsg, ...)
|
||||
{
|
||||
write(1, errormsg, strlen(errormsg));
|
||||
write(1, "\n", 1);
|
||||
|
@ -39,7 +39,7 @@ public:
|
||||
void suspend_timer_procs();
|
||||
void resume_timer_procs();
|
||||
void reboot(bool hold_in_bootloader);
|
||||
void panic(const prog_char_t *errormsg) NORETURN;
|
||||
void panic(const prog_char_t *errormsg, ...) NORETURN;
|
||||
|
||||
bool in_timerprocess();
|
||||
bool system_initializing();
|
||||
|
Loading…
Reference in New Issue
Block a user