AP_Logger: use AP_InternalError for tracking internal errors

This commit is contained in:
Peter Barker 2018-08-07 20:22:21 +10:00 committed by Peter Barker
parent b3203601f3
commit ee690e7ab9
7 changed files with 20 additions and 41 deletions

View File

@ -6,6 +6,8 @@
#include "AP_Logger_SITL.h" #include "AP_Logger_SITL.h"
#include "AP_Logger_DataFlash.h" #include "AP_Logger_DataFlash.h"
#include "AP_Logger_MAVLink.h" #include "AP_Logger_MAVLink.h"
#include <AP_InternalError/AP_InternalError.h>
#include <GCS_MAVLink/GCS.h> #include <GCS_MAVLink/GCS.h>
AP_Logger *AP_Logger::_singleton; AP_Logger *AP_Logger::_singleton;
@ -708,12 +710,6 @@ uint32_t AP_Logger::num_dropped() const
// end functions pass straight through to backend // end functions pass straight through to backend
void AP_Logger::internal_error() const {
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL
AP_HAL::panic("Internal AP_Logger error");
#endif
}
/* Write support */ /* Write support */
void AP_Logger::Write(const char *name, const char *labels, const char *fmt, ...) void AP_Logger::Write(const char *name, const char *labels, const char *fmt, ...)
{ {
@ -739,7 +735,7 @@ void AP_Logger::WriteV(const char *name, const char *labels, const char *units,
if (f == nullptr) { if (f == nullptr) {
// unable to map name to a messagetype; could be out of // unable to map name to a messagetype; could be out of
// msgtypes, could be out of slots, ... // msgtypes, could be out of slots, ...
internal_error(); AP::internalerror().error(AP_InternalError::error_t::logger_mapfailure);
return; return;
} }

View File

@ -309,8 +309,6 @@ private:
AP_Logger_Backend *backends[DATAFLASH_MAX_BACKENDS]; AP_Logger_Backend *backends[DATAFLASH_MAX_BACKENDS];
const AP_Int32 &_log_bitmask; const AP_Int32 &_log_bitmask;
void internal_error() const;
enum class Backend_Type : uint8_t { enum class Backend_Type : uint8_t {
NONE = 0, NONE = 0,
FILESYSTEM = (1<<0), FILESYSTEM = (1<<0),

View File

@ -2,6 +2,8 @@
#include "LoggerMessageWriter.h" #include "LoggerMessageWriter.h"
#include <AP_InternalError/AP_InternalError.h>
extern const AP_HAL::HAL& hal; extern const AP_HAL::HAL& hal;
AP_Logger_Backend::AP_Logger_Backend(AP_Logger &front, AP_Logger_Backend::AP_Logger_Backend(AP_Logger &front,
@ -76,13 +78,6 @@ void AP_Logger_Backend::start_new_log_reset_variables()
_front.backend_starting_new_log(this); _front.backend_starting_new_log(this);
} }
void AP_Logger_Backend::internal_error() {
_internal_errors++;
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL
abort();
#endif
}
// this method can be overridden to do extra things with your buffer. // this method can be overridden to do extra things with your buffer.
// for example, in AP_Logger_MAVLink we may push messages into the UART. // for example, in AP_Logger_MAVLink we may push messages into the UART.
void AP_Logger_Backend::push_log_blocks() { void AP_Logger_Backend::push_log_blocks() {
@ -164,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 // 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 // message for a msg_type, but the frontend can't supply the
// required information // required information
internal_error(); AP::internalerror().error(AP_InternalError::error_t::logger_missing_logstructure);
return false; return false;
} }
@ -194,8 +189,7 @@ bool AP_Logger_Backend::Write(const uint8_t msg_type, va_list arg_list, bool is_
} }
} }
if (fmt == nullptr) { if (fmt == nullptr) {
// this is a bug. AP::internalerror().error(AP_InternalError::error_t::logger_logwrite_missingfmt);
internal_error();
return false; return false;
} }
if (bufferspace_available() < msg_len) { if (bufferspace_available() < msg_len) {

View File

@ -15,8 +15,6 @@ public:
vehicle_startup_message_Writer vehicle_message_writer(); vehicle_startup_message_Writer vehicle_message_writer();
void internal_error();
virtual bool CardInserted(void) const = 0; virtual bool CardInserted(void) const = 0;
// erase handling // erase handling
@ -149,7 +147,6 @@ protected:
LoggerMessageWriter_DFLogStart *_startup_messagewriter; LoggerMessageWriter_DFLogStart *_startup_messagewriter;
bool _writing_startup_messages; bool _writing_startup_messages;
uint8_t _internal_errors;
uint32_t _dropped; uint32_t _dropped;
// must be called when a new log is being started: // must be called when a new log is being started:

View File

@ -16,6 +16,7 @@
#include "AP_Logger_File.h" #include "AP_Logger_File.h"
#include <AP_Common/AP_Common.h> #include <AP_Common/AP_Common.h>
#include <AP_InternalError/AP_InternalError.h>
#if HAL_OS_POSIX_IO #if HAL_OS_POSIX_IO
#include <unistd.h> #include <unistd.h>
@ -255,7 +256,7 @@ uint16_t AP_Logger_File::find_oldest_log()
// doing a *lot* of asprintf()s and stat()s // doing a *lot* of asprintf()s and stat()s
DIR *d = opendir(_log_directory); DIR *d = opendir(_log_directory);
if (d == nullptr) { if (d == nullptr) {
internal_error(); // SD card may have died? On linux someone may have rm-rf-d
return 0; return 0;
} }
@ -316,7 +317,6 @@ void AP_Logger_File::Prep_MinSpace()
do { do {
float avail = avail_space_percent(); float avail = avail_space_percent();
if (is_equal(avail, -1.0f)) { if (is_equal(avail, -1.0f)) {
internal_error();
break; break;
} }
if (avail >= min_avail_space_percent) { if (avail >= min_avail_space_percent) {
@ -324,12 +324,12 @@ void AP_Logger_File::Prep_MinSpace()
} }
if (count++ > MAX_LOG_FILES+10) { if (count++ > MAX_LOG_FILES+10) {
// *way* too many deletions going on here. Possible internal error. // *way* too many deletions going on here. Possible internal error.
internal_error(); AP::internalerror().error(AP_InternalError::error_t::logger_too_many_deletions);
break; break;
} }
char *filename_to_remove = _log_file_name(log_to_remove); char *filename_to_remove = _log_file_name(log_to_remove);
if (filename_to_remove == nullptr) { if (filename_to_remove == nullptr) {
internal_error(); AP::internalerror().error(AP_InternalError::error_t::logger_bad_getfilename);
break; break;
} }
if (file_exists(filename_to_remove)) { if (file_exists(filename_to_remove)) {
@ -343,7 +343,6 @@ void AP_Logger_File::Prep_MinSpace()
// sequence of files... however, there may be still // sequence of files... however, there may be still
// files out there, so keep going. // files out there, so keep going.
} else { } else {
internal_error();
break; break;
} }
} else { } else {
@ -810,7 +809,7 @@ void AP_Logger_File::stop_logging(void)
if (have_sem) { if (have_sem) {
write_fd_semaphore.give(); write_fd_semaphore.give();
} else { } else {
_internal_errors++; AP::internalerror().error(AP_InternalError::error_t::logger_stopping_without_sem);
} }
} }
@ -944,7 +943,7 @@ void AP_Logger_File::flush(void)
} }
write_fd_semaphore.give(); write_fd_semaphore.give();
} else { } else {
_internal_errors++; AP::internalerror().error(AP_InternalError::error_t::logger_flushing_without_sem);
} }
} }
#else #else
@ -1098,7 +1097,6 @@ void AP_Logger_File::Write_AP_Logger_Stats_File(const struct df_stats &_stats)
LOG_PACKET_HEADER_INIT(LOG_DF_FILE_STATS), LOG_PACKET_HEADER_INIT(LOG_DF_FILE_STATS),
time_us : AP_HAL::micros64(), time_us : AP_HAL::micros64(),
dropped : _dropped, dropped : _dropped,
internal_errors : _internal_errors,
blocks : _stats.blocks, blocks : _stats.blocks,
bytes : _stats.bytes, bytes : _stats.bytes,
buf_space_min : _stats.buf_space_min, buf_space_min : _stats.buf_space_min,

View File

@ -17,6 +17,7 @@
# define Debug(fmt, args ...) # define Debug(fmt, args ...)
#endif #endif
#include <AP_InternalError/AP_InternalError.h>
#include <GCS_MAVLink/GCS.h> #include <GCS_MAVLink/GCS.h>
extern const AP_HAL::HAL& hal; extern const AP_HAL::HAL& hal;
@ -148,7 +149,7 @@ bool AP_Logger_MAVLink::_WritePrioritisedBlock(const void *pBuffer, uint16_t siz
_current_block = next_block(); _current_block = next_block();
if (_current_block == nullptr) { if (_current_block == nullptr) {
// should not happen - there's a sanity check above // should not happen - there's a sanity check above
internal_error(); AP::internalerror().error(AP_InternalError::error_t::logger_bad_current_block);
semaphore.give(); semaphore.give();
return false; return false;
} }
@ -298,7 +299,6 @@ void AP_Logger_MAVLink::handle_retry(uint32_t seqno)
void AP_Logger_MAVLink::stats_init() { void AP_Logger_MAVLink::stats_init() {
_dropped = 0; _dropped = 0;
_internal_errors = 0;
stats.resends = 0; stats.resends = 0;
stats_reset(); stats_reset();
} }
@ -330,7 +330,6 @@ void AP_Logger_MAVLink::Write_DF_MAV(AP_Logger_MAVLink &df)
dropped : df._dropped, dropped : df._dropped,
retries : df._blocks_retry.sent_count, retries : df._blocks_retry.sent_count,
resends : df.stats.resends, resends : df.stats.resends,
internal_errors : df._internal_errors,
state_free_avg : (uint8_t)(df.stats.state_free/df.stats.collection_count), state_free_avg : (uint8_t)(df.stats.state_free/df.stats.collection_count),
state_free_min : df.stats.state_free_min, state_free_min : df.stats.state_free_min,
state_free_max : df.stats.state_free_max, state_free_max : df.stats.state_free_max,
@ -354,11 +353,10 @@ void AP_Logger_MAVLink::stats_log()
} }
Write_DF_MAV(*this); Write_DF_MAV(*this);
#if REMOTE_LOG_DEBUGGING #if REMOTE_LOG_DEBUGGING
printf("D:%d Retry:%d Resent:%d E:%d SF:%d/%d/%d SP:%d/%d/%d SS:%d/%d/%d SR:%d/%d/%d\n", printf("D:%d Retry:%d Resent:%d SF:%d/%d/%d SP:%d/%d/%d SS:%d/%d/%d SR:%d/%d/%d\n",
dropped, dropped,
_blocks_retry.sent_count, _blocks_retry.sent_count,
stats.resends, stats.resends,
internal_errors,
stats.state_free_min, stats.state_free_min,
stats.state_free_max, stats.state_free_max,
stats.state_free/stats.collection_count, stats.state_free/stats.collection_count,
@ -403,7 +401,7 @@ void AP_Logger_MAVLink::stats_collect()
uint8_t sfree = stack_size(_blocks_free); uint8_t sfree = stack_size(_blocks_free);
if (sfree != _blockcount_free) { if (sfree != _blockcount_free) {
internal_error(); AP::internalerror().error(AP_InternalError::error_t::logger_blockcount_mismatch);
} }
semaphore.give(); semaphore.give();
@ -458,7 +456,7 @@ bool AP_Logger_MAVLink::send_log_blocks_from_queue(dm_block_queue_t &queue)
if (tmp != nullptr) { // should never be nullptr if (tmp != nullptr) { // should never be nullptr
enqueue_block(_blocks_sent, tmp); enqueue_block(_blocks_sent, tmp);
} else { } else {
internal_error(); AP::internalerror().error(AP_InternalError::error_t::logger_dequeue_failure);
} }
} }
return true; return true;

View File

@ -151,7 +151,6 @@ struct PACKED log_DSF {
LOG_PACKET_HEADER; LOG_PACKET_HEADER;
uint64_t time_us; uint64_t time_us;
uint32_t dropped; uint32_t dropped;
uint8_t internal_errors;
uint16_t blocks; uint16_t blocks;
uint32_t bytes; uint32_t bytes;
uint32_t buf_space_min; uint32_t buf_space_min;
@ -907,7 +906,6 @@ struct PACKED log_DF_MAV_Stats {
uint32_t dropped; uint32_t dropped;
uint32_t retries; uint32_t retries;
uint32_t resends; uint32_t resends;
uint8_t internal_errors; // uint8_t - wishful thinking?
uint8_t state_free_avg; uint8_t state_free_avg;
uint8_t state_free_min; uint8_t state_free_min;
uint8_t state_free_max; uint8_t state_free_max;
@ -1305,7 +1303,7 @@ Format characters in the format string for binary log messages
{ LOG_RFND_MSG, sizeof(log_RFND), \ { LOG_RFND_MSG, sizeof(log_RFND), \
"RFND", "QCBBCBB", "TimeUS,Dist1,Stat1,Orient1,Dist2,Stat2,Orient2", "sm--m--", "FB--B--" }, \ "RFND", "QCBBCBB", "TimeUS,Dist1,Stat1,Orient1,Dist2,Stat2,Orient2", "sm--m--", "FB--B--" }, \
{ LOG_DF_MAV_STATS, sizeof(log_DF_MAV_Stats), \ { LOG_DF_MAV_STATS, sizeof(log_DF_MAV_Stats), \
"DMS", "IIIIIBBBBBBBBBB", "TimeMS,N,Dp,RT,RS,Er,Fa,Fmn,Fmx,Pa,Pmn,Pmx,Sa,Smn,Smx", "s--------------", "C--------------" }, \ "DMS", "IIIIIBBBBBBBBB", "TimeMS,N,Dp,RT,RS,Fa,Fmn,Fmx,Pa,Pmn,Pmx,Sa,Smn,Smx", "s-------------", "C-------------" }, \
{ LOG_BEACON_MSG, sizeof(log_Beacon), \ { LOG_BEACON_MSG, sizeof(log_Beacon), \
"BCN", "QBBfffffff", "TimeUS,Health,Cnt,D0,D1,D2,D3,PosX,PosY,PosZ", "s--mmmmmmm", "F--BBBBBBB" }, \ "BCN", "QBBfffffff", "TimeUS,Health,Cnt,D0,D1,D2,D3,PosX,PosY,PosZ", "s--mmmmmmm", "F--BBBBBBB" }, \
{ LOG_PROXIMITY_MSG, sizeof(log_Proximity), \ { LOG_PROXIMITY_MSG, sizeof(log_Proximity), \
@ -1458,7 +1456,7 @@ Format characters in the format string for binary log messages
{ LOG_ORGN_MSG, sizeof(log_ORGN), \ { LOG_ORGN_MSG, sizeof(log_ORGN), \
"ORGN","QBLLe","TimeUS,Type,Lat,Lng,Alt", "s-DUm", "F-GGB" }, \ "ORGN","QBLLe","TimeUS,Type,Lat,Lng,Alt", "s-DUm", "F-GGB" }, \
{ LOG_DF_FILE_STATS, sizeof(log_DSF), \ { LOG_DF_FILE_STATS, sizeof(log_DSF), \
"DSF", "QIBHIIII", "TimeUS,Dp,IErr,Blk,Bytes,FMn,FMx,FAv", "s---b---", "F---0---" }, \ "DSF", "QIHIIII", "TimeUS,Dp,Blk,Bytes,FMn,FMx,FAv", "s--b---", "F--0---" }, \
{ LOG_RPM_MSG, sizeof(log_RPM), \ { LOG_RPM_MSG, sizeof(log_RPM), \
"RPM", "Qff", "TimeUS,rpm1,rpm2", "sqq", "F00" }, \ "RPM", "Qff", "TimeUS,rpm1,rpm2", "sqq", "F00" }, \
{ LOG_GIMBAL1_MSG, sizeof(log_Gimbal1), \ { LOG_GIMBAL1_MSG, sizeof(log_Gimbal1), \