mirror of https://github.com/ArduPilot/ardupilot
AP_HAL_ChibiOS: improve gating of use of AP_InternalError library
- gate calls into library directly on the define - INTERNAL_ERROR becomes empty if library not compiled in
This commit is contained in:
parent
c2f4fb5def
commit
bb6f0ae527
|
@ -829,14 +829,18 @@ void Scheduler::check_stack_free(void)
|
||||||
|
|
||||||
if (stack_free(&__main_stack_base__) < min_stack) {
|
if (stack_free(&__main_stack_base__) < min_stack) {
|
||||||
// use "line number" of 0xFFFF for ISR stack low
|
// use "line number" of 0xFFFF for ISR stack low
|
||||||
|
#if AP_INTERNALERROR_ENABLED
|
||||||
AP::internalerror().error(AP_InternalError::error_t::stack_overflow, 0xFFFF);
|
AP::internalerror().error(AP_InternalError::error_t::stack_overflow, 0xFFFF);
|
||||||
|
#endif
|
||||||
}
|
}
|
||||||
|
|
||||||
for (thread_t *tp = chRegFirstThread(); tp; tp = chRegNextThread(tp)) {
|
for (thread_t *tp = chRegFirstThread(); tp; tp = chRegNextThread(tp)) {
|
||||||
if (stack_free(tp->wabase) < min_stack) {
|
if (stack_free(tp->wabase) < min_stack) {
|
||||||
// use task priority for line number. This allows us to
|
// use task priority for line number. This allows us to
|
||||||
// identify the task fairly reliably
|
// identify the task fairly reliably
|
||||||
|
#if AP_INTERNALERROR_ENABLED
|
||||||
AP::internalerror().error(AP_InternalError::error_t::stack_overflow, tp->realprio);
|
AP::internalerror().error(AP_InternalError::error_t::stack_overflow, tp->realprio);
|
||||||
|
#endif
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
|
@ -37,3 +37,7 @@
|
||||||
|
|
||||||
// allow the IOMCU to have its allowed protocols to be set:
|
// allow the IOMCU to have its allowed protocols to be set:
|
||||||
#define AP_RCPROTOCOL_ENABLE_SET_RC_PROTOCOLS 1
|
#define AP_RCPROTOCOL_ENABLE_SET_RC_PROTOCOLS 1
|
||||||
|
|
||||||
|
#ifndef AP_INTERNALERROR_ENABLED
|
||||||
|
#define AP_INTERNALERROR_ENABLED 0
|
||||||
|
#endif
|
||||||
|
|
Loading…
Reference in New Issue