AP_Logger: create and use INTERNAL_ERROR macro so we get line numbers
This commit is contained in:
parent
f0b38fa11c
commit
7befe84f0c
@ -834,7 +834,7 @@ void AP_Logger::WriteV(const char *name, const char *labels, const char *units,
|
||||
if (f == nullptr) {
|
||||
// unable to map name to a messagetype; could be out of
|
||||
// msgtypes, could be out of slots, ...
|
||||
AP::internalerror().error(AP_InternalError::error_t::logger_mapfailure);
|
||||
INTERNAL_ERROR(AP_InternalError::error_t::logger_mapfailure);
|
||||
return;
|
||||
}
|
||||
|
||||
|
@ -159,7 +159,7 @@ bool AP_Logger_Backend::Write_Emit_FMT(uint8_t msg_type)
|
||||
// this is a bug; we've been asked to write out the FMT
|
||||
// message for a msg_type, but the frontend can't supply the
|
||||
// required information
|
||||
AP::internalerror().error(AP_InternalError::error_t::logger_missing_logstructure);
|
||||
INTERNAL_ERROR(AP_InternalError::error_t::logger_missing_logstructure);
|
||||
return false;
|
||||
}
|
||||
|
||||
@ -189,7 +189,7 @@ bool AP_Logger_Backend::Write(const uint8_t msg_type, va_list arg_list, bool is_
|
||||
}
|
||||
}
|
||||
if (fmt == nullptr) {
|
||||
AP::internalerror().error(AP_InternalError::error_t::logger_logwrite_missingfmt);
|
||||
INTERNAL_ERROR(AP_InternalError::error_t::logger_logwrite_missingfmt);
|
||||
return false;
|
||||
}
|
||||
if (bufferspace_available() < msg_len) {
|
||||
|
@ -301,12 +301,12 @@ void AP_Logger_File::Prep_MinSpace()
|
||||
}
|
||||
if (count++ > MAX_LOG_FILES+10) {
|
||||
// *way* too many deletions going on here. Possible internal error.
|
||||
AP::internalerror().error(AP_InternalError::error_t::logger_too_many_deletions);
|
||||
INTERNAL_ERROR(AP_InternalError::error_t::logger_too_many_deletions);
|
||||
break;
|
||||
}
|
||||
char *filename_to_remove = _log_file_name(log_to_remove);
|
||||
if (filename_to_remove == nullptr) {
|
||||
AP::internalerror().error(AP_InternalError::error_t::logger_bad_getfilename);
|
||||
INTERNAL_ERROR(AP_InternalError::error_t::logger_bad_getfilename);
|
||||
break;
|
||||
}
|
||||
if (file_exists(filename_to_remove)) {
|
||||
@ -895,7 +895,7 @@ void AP_Logger_File::flush(void)
|
||||
}
|
||||
write_fd_semaphore.give();
|
||||
} else {
|
||||
AP::internalerror().error(AP_InternalError::error_t::logger_flushing_without_sem);
|
||||
INTERNAL_ERROR(AP_InternalError::error_t::logger_flushing_without_sem);
|
||||
}
|
||||
}
|
||||
#else
|
||||
|
@ -149,7 +149,7 @@ bool AP_Logger_MAVLink::_WritePrioritisedBlock(const void *pBuffer, uint16_t siz
|
||||
_current_block = next_block();
|
||||
if (_current_block == nullptr) {
|
||||
// should not happen - there's a sanity check above
|
||||
AP::internalerror().error(AP_InternalError::error_t::logger_bad_current_block);
|
||||
INTERNAL_ERROR(AP_InternalError::error_t::logger_bad_current_block);
|
||||
semaphore.give();
|
||||
return false;
|
||||
}
|
||||
@ -401,7 +401,7 @@ void AP_Logger_MAVLink::stats_collect()
|
||||
uint8_t sfree = stack_size(_blocks_free);
|
||||
|
||||
if (sfree != _blockcount_free) {
|
||||
AP::internalerror().error(AP_InternalError::error_t::logger_blockcount_mismatch);
|
||||
INTERNAL_ERROR(AP_InternalError::error_t::logger_blockcount_mismatch);
|
||||
}
|
||||
semaphore.give();
|
||||
|
||||
@ -456,7 +456,7 @@ bool AP_Logger_MAVLink::send_log_blocks_from_queue(dm_block_queue_t &queue)
|
||||
if (tmp != nullptr) { // should never be nullptr
|
||||
enqueue_block(_blocks_sent, tmp);
|
||||
} else {
|
||||
AP::internalerror().error(AP_InternalError::error_t::logger_dequeue_failure);
|
||||
INTERNAL_ERROR(AP_InternalError::error_t::logger_dequeue_failure);
|
||||
}
|
||||
}
|
||||
return true;
|
||||
|
@ -1684,6 +1684,7 @@ struct PACKED log_Arm_Disarm {
|
||||
// @Field: Task: Current scheduler task number
|
||||
// @Field: IErr: Internal error mask; which internal errors have been detected
|
||||
// @Field: IErrCnt: Internal error count; how many internal errors have been detected
|
||||
// @Field: IErrLn: Line on which internal error ocurred
|
||||
// @Field: MavMsg: Id of the last mavlink message processed
|
||||
// @Field: MavCmd: Id of the last mavlink command processed
|
||||
// @Field: SemLine: Line number of semaphore most recently taken
|
||||
|
Loading…
Reference in New Issue
Block a user