AP_HAL_ChibiOS: create and use INTERNAL_ERROR macro so we get line numbers

This commit is contained in:
Peter Barker 2020-04-30 10:40:45 +10:00 committed by Peter Barker
parent 37cddbeea6
commit 48da4e523c
4 changed files with 8 additions and 6 deletions

View File

@ -222,7 +222,7 @@ static void main_loop()
#ifndef HAL_NO_LOGGING #ifndef HAL_NO_LOGGING
if (hal.util->was_watchdog_reset()) { if (hal.util->was_watchdog_reset()) {
AP::internalerror().error(AP_InternalError::error_t::watchdog_reset); INTERNAL_ERROR(AP_InternalError::error_t::watchdog_reset);
} }
#endif // HAL_NO_LOGGING #endif // HAL_NO_LOGGING
#endif // IOMCU_FW #endif // IOMCU_FW

View File

@ -294,7 +294,7 @@ bool I2CDevice::_transfer(const uint8_t *send, uint32_t send_len,
bus.dma_handle->unlock(); bus.dma_handle->unlock();
if (I2CD[bus.busnum].i2c->errors & I2C_ISR_LIMIT) { if (I2CD[bus.busnum].i2c->errors & I2C_ISR_LIMIT) {
AP::internalerror().error(AP_InternalError::error_t::i2c_isr); INTERNAL_ERROR(AP_InternalError::error_t::i2c_isr);
break; break;
} }

View File

@ -208,7 +208,7 @@ bool SPIDevice::do_transfer(const uint8_t *send, uint8_t *recv, uint32_t len)
if (msg == MSG_TIMEOUT) { if (msg == MSG_TIMEOUT) {
ret = false; ret = false;
if (!hal.scheduler->in_expected_delay()) { if (!hal.scheduler->in_expected_delay()) {
AP::internalerror().error(AP_InternalError::error_t::spi_fail); INTERNAL_ERROR(AP_InternalError::error_t::spi_fail);
} }
spiAbort(spi_devices[device_desc.bus].driver); spiAbort(spi_devices[device_desc.bus].driver);
} }

View File

@ -368,12 +368,13 @@ void Scheduler::_monitor_thread(void *arg)
// 200ms. Starting logging the main loop state // 200ms. Starting logging the main loop state
const AP_HAL::Util::PersistentData &pd = hal.util->persistent_data; const AP_HAL::Util::PersistentData &pd = hal.util->persistent_data;
if (AP_Logger::get_singleton()) { if (AP_Logger::get_singleton()) {
AP::logger().Write("MON", "TimeUS,LDelay,Task,IErr,IErrCnt,MavMsg,MavCmd,SemLine,SPICnt,I2CCnt", "QIbIIHHHII", AP::logger().Write("MON", "TimeUS,LDelay,Task,IErr,IErrCnt,IErrLn,MavMsg,MavCmd,SemLine,SPICnt,I2CCnt", "QIbIHHHHHII",
AP_HAL::micros64(), AP_HAL::micros64(),
loop_delay, loop_delay,
pd.scheduler_task, pd.scheduler_task,
pd.internal_errors, pd.internal_errors,
pd.internal_error_count, pd.internal_error_count,
pd.internal_error_last_line,
pd.last_mavlink_msgid, pd.last_mavlink_msgid,
pd.last_mavlink_cmd, pd.last_mavlink_cmd,
pd.semaphore_line, pd.semaphore_line,
@ -383,7 +384,7 @@ void Scheduler::_monitor_thread(void *arg)
} }
if (loop_delay >= 500) { if (loop_delay >= 500) {
// at 500ms we declare an internal error // at 500ms we declare an internal error
AP::internalerror().error(AP_InternalError::error_t::main_loop_stuck); INTERNAL_ERROR(AP_InternalError::error_t::main_loop_stuck);
} }
#ifndef HAL_NO_LOGGING #ifndef HAL_NO_LOGGING
@ -391,11 +392,12 @@ void Scheduler::_monitor_thread(void *arg)
log_wd_counter = 0; log_wd_counter = 0;
// log watchdog message once a second // log watchdog message once a second
const AP_HAL::Util::PersistentData &pd = hal.util->last_persistent_data; const AP_HAL::Util::PersistentData &pd = hal.util->last_persistent_data;
AP::logger().WriteCritical("WDOG", "TimeUS,Tsk,IE,IEC,MvMsg,MvCmd,SmLn,FL,FT,FA,FP,ICSR,LR,TN", "QbIIHHHHHIBIIn", AP::logger().WriteCritical("WDOG", "TimeUS,Tsk,IE,IEC,IEL,MvMsg,MvCmd,SmLn,FL,FT,FA,FP,ICSR,LR,TN", "QbIHHHHHHHIBIIn",
AP_HAL::micros64(), AP_HAL::micros64(),
pd.scheduler_task, pd.scheduler_task,
pd.internal_errors, pd.internal_errors,
pd.internal_error_count, pd.internal_error_count,
pd.internal_error_last_line,
pd.last_mavlink_msgid, pd.last_mavlink_msgid,
pd.last_mavlink_cmd, pd.last_mavlink_cmd,
pd.semaphore_line, pd.semaphore_line,