mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-26 18:48:30 -04:00
AP_Common: create and use INTERNAL_ERROR macro so we get line numbers
This commit is contained in:
parent
119eef9954
commit
8e82ea2540
@ -43,7 +43,7 @@ public:
|
||||
void set(uint16_t bit) {
|
||||
// ignore an invalid bit number
|
||||
if (bit >= numbits) {
|
||||
AP::internalerror().error(AP_InternalError::error_t::bitmask_range);
|
||||
INTERNAL_ERROR(AP_InternalError::error_t::bitmask_range);
|
||||
return;
|
||||
}
|
||||
uint16_t word = bit/32;
|
||||
@ -80,7 +80,7 @@ public:
|
||||
uint8_t ofs = bit & 0x1f;
|
||||
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL
|
||||
if (bit >= numbits) {
|
||||
AP::internalerror().error(AP_InternalError::error_t::bitmask_range);
|
||||
INTERNAL_ERROR(AP_InternalError::error_t::bitmask_range);
|
||||
return false;
|
||||
}
|
||||
#endif
|
||||
|
Loading…
Reference in New Issue
Block a user