diff --git a/libraries/AP_HAL/AP_HAL_Macros.h b/libraries/AP_HAL/AP_HAL_Macros.h index e65d8eab86..18b843f882 100644 --- a/libraries/AP_HAL/AP_HAL_Macros.h +++ b/libraries/AP_HAL/AP_HAL_Macros.h @@ -17,4 +17,6 @@ # define constexpr const #endif +#define NORETURN __attribute__ ((noreturn)) + #endif // __AP_HAL_MACROS_H__ diff --git a/libraries/AP_HAL/Scheduler.h b/libraries/AP_HAL/Scheduler.h index f951d9a010..e9833780e7 100644 --- a/libraries/AP_HAL/Scheduler.h +++ b/libraries/AP_HAL/Scheduler.h @@ -54,7 +54,7 @@ public: virtual bool system_initializing() = 0; virtual void system_initialized() = 0; - virtual void panic(const prog_char_t *errormsg) = 0; + virtual void panic(const prog_char_t *errormsg) NORETURN = 0; virtual void reboot(bool hold_in_bootloader) = 0; /** diff --git a/libraries/AP_HAL_AVR/Scheduler.h b/libraries/AP_HAL_AVR/Scheduler.h index 239df7be78..3ccbd9f729 100644 --- a/libraries/AP_HAL_AVR/Scheduler.h +++ b/libraries/AP_HAL_AVR/Scheduler.h @@ -45,7 +45,7 @@ public: bool system_initializing(); void system_initialized(); - void panic(const prog_char_t *errormsg); + void panic(const prog_char_t *errormsg) NORETURN; void reboot(bool hold_in_bootloader); void set_timer_speed(uint16_t timer_hz); diff --git a/libraries/AP_HAL_Empty/Scheduler.h b/libraries/AP_HAL_Empty/Scheduler.h index 2afcbf460a..6f8f272343 100644 --- a/libraries/AP_HAL_Empty/Scheduler.h +++ b/libraries/AP_HAL_Empty/Scheduler.h @@ -32,7 +32,7 @@ public: bool system_initializing(); void system_initialized(); - void panic(const prog_char_t *errormsg); + void panic(const prog_char_t *errormsg) NORETURN; void reboot(bool hold_in_bootloader); }; diff --git a/libraries/AP_HAL_FLYMAPLE/Scheduler.h b/libraries/AP_HAL_FLYMAPLE/Scheduler.h index d9d7b0597c..ee48bc66f3 100644 --- a/libraries/AP_HAL_FLYMAPLE/Scheduler.h +++ b/libraries/AP_HAL_FLYMAPLE/Scheduler.h @@ -53,7 +53,7 @@ public: bool system_initializing(); void system_initialized(); - void panic(const prog_char_t *errormsg); + void panic(const prog_char_t *errormsg) NORETURN; void reboot(bool hold_in_bootloader); private: diff --git a/libraries/AP_HAL_Linux/Scheduler.h b/libraries/AP_HAL_Linux/Scheduler.h index 4432712d03..7d08ec371d 100644 --- a/libraries/AP_HAL_Linux/Scheduler.h +++ b/libraries/AP_HAL_Linux/Scheduler.h @@ -43,7 +43,7 @@ public: bool system_initializing(); void system_initialized(); - void panic(const prog_char_t *errormsg); + void panic(const prog_char_t *errormsg) NORETURN; void reboot(bool hold_in_bootloader); void stop_clock(uint64_t time_usec); diff --git a/libraries/AP_HAL_PX4/Scheduler.h b/libraries/AP_HAL_PX4/Scheduler.h index 518ec1e7dd..4a3eddf86a 100644 --- a/libraries/AP_HAL_PX4/Scheduler.h +++ b/libraries/AP_HAL_PX4/Scheduler.h @@ -59,7 +59,7 @@ public: void suspend_timer_procs(); void resume_timer_procs(); void reboot(bool hold_in_bootloader); - void panic(const prog_char_t *errormsg); + void panic(const prog_char_t *errormsg) NORETURN; bool in_timerprocess(); bool system_initializing(); diff --git a/libraries/AP_HAL_SITL/Scheduler.h b/libraries/AP_HAL_SITL/Scheduler.h index e46566411b..1e4be6c060 100644 --- a/libraries/AP_HAL_SITL/Scheduler.h +++ b/libraries/AP_HAL_SITL/Scheduler.h @@ -37,7 +37,7 @@ public: void system_initialized(); void reboot(bool hold_in_bootloader); - void panic(const prog_char_t *errormsg); + void panic(const prog_char_t *errormsg) NORETURN; bool interrupts_are_blocked(void) { return _nested_atomic_ctr != 0; diff --git a/libraries/AP_HAL_VRBRAIN/Scheduler.h b/libraries/AP_HAL_VRBRAIN/Scheduler.h index 4e5a886bcc..700d2d460a 100644 --- a/libraries/AP_HAL_VRBRAIN/Scheduler.h +++ b/libraries/AP_HAL_VRBRAIN/Scheduler.h @@ -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); + void panic(const prog_char_t *errormsg) NORETURN; bool in_timerprocess(); bool system_initializing();