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

This commit is contained in:
Peter Barker 2020-04-30 10:40:46 +10:00 committed by Peter Barker
parent a30cdabb34
commit f0b38fa11c
1 changed files with 2 additions and 2 deletions

View File

@ -987,7 +987,7 @@ void AP_IOMCU::handle_repeated_failures(void)
// initial sync with IOMCU
return;
}
AP::internalerror().error(AP_InternalError::error_t::iomcu_fail);
INTERNAL_ERROR(AP_InternalError::error_t::iomcu_fail);
}
/*
@ -1009,7 +1009,7 @@ void AP_IOMCU::check_iomcu_reset(void)
return;
}
detected_io_reset = true;
AP::internalerror().error(AP_InternalError::error_t::iomcu_reset);
INTERNAL_ERROR(AP_InternalError::error_t::iomcu_reset);
hal.console->printf("IOMCU reset t=%u %u %u dt=%u\n",
unsigned(AP_HAL::millis()), unsigned(ts1), unsigned(reg_status.timestamp_ms), unsigned(dt_ms));
// we need to ensure the mixer data and the rates are sent over to