Skip to content

Commit

Permalink
AP_IOMCU: create and use INTERNAL_ERROR macro so we get line numbers
Browse files Browse the repository at this point in the history
  • Loading branch information
peterbarker committed Apr 30, 2020
1 parent a30cdab commit f0b38fa
Showing 1 changed file with 2 additions and 2 deletions.
4 changes: 2 additions & 2 deletions libraries/AP_IOMCU/AP_IOMCU.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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);
}

/*
Expand All @@ -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
Expand Down

0 comments on commit f0b38fa

Please sign in to comment.