mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-23 17:18:28 -04:00
DataFlash: remove duplicate variables
This commit is contained in:
parent
e298e87791
commit
776d88bb6b
@ -528,7 +528,6 @@ uint32_t DataFlash_Class::num_dropped() const
|
||||
// end functions pass straight through to backend
|
||||
|
||||
void DataFlash_Class::internal_error() const {
|
||||
// _internal_errors++;
|
||||
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL
|
||||
abort();
|
||||
#endif
|
||||
|
@ -122,8 +122,6 @@ public:
|
||||
virtual void vehicle_was_disarmed() { };
|
||||
|
||||
protected:
|
||||
uint32_t dropped;
|
||||
uint8_t internal_errors; // uint8_t - wishful thinking?
|
||||
|
||||
DataFlash_Class &_front;
|
||||
|
||||
@ -154,7 +152,7 @@ protected:
|
||||
DFMessageWriter_DFLogStart *_startup_messagewriter;
|
||||
bool _writing_startup_messages;
|
||||
|
||||
uint32_t _internal_errors;
|
||||
uint8_t _internal_errors;
|
||||
uint32_t _dropped;
|
||||
|
||||
// must be called when a new log is being started:
|
||||
|
@ -174,7 +174,6 @@ bool DataFlash_File::log_exists(const uint16_t lognum) const
|
||||
{
|
||||
char *filename = _log_file_name(lognum);
|
||||
if (filename == nullptr) {
|
||||
// internal_error();
|
||||
return false; // ?!
|
||||
}
|
||||
bool ret = file_exists(filename);
|
||||
@ -290,7 +289,7 @@ uint16_t DataFlash_File::find_oldest_log()
|
||||
// doing a *lot* of asprintf()s and stat()s
|
||||
DIR *d = opendir(_log_directory);
|
||||
if (d == nullptr) {
|
||||
// internal_error();
|
||||
internal_error();
|
||||
return 0;
|
||||
}
|
||||
|
||||
@ -353,7 +352,7 @@ void DataFlash_File::Prep_MinSpace()
|
||||
do {
|
||||
float avail = avail_space_percent();
|
||||
if (is_equal(avail, -1.0f)) {
|
||||
// internal_error()
|
||||
internal_error();
|
||||
break;
|
||||
}
|
||||
if (avail >= min_avail_space_percent) {
|
||||
@ -361,12 +360,12 @@ void DataFlash_File::Prep_MinSpace()
|
||||
}
|
||||
if (count++ > MAX_LOG_FILES+10) {
|
||||
// *way* too many deletions going on here. Possible internal error.
|
||||
// internal_error();
|
||||
internal_error();
|
||||
break;
|
||||
}
|
||||
char *filename_to_remove = _log_file_name(log_to_remove);
|
||||
if (filename_to_remove == nullptr) {
|
||||
// internal_error();
|
||||
internal_error();
|
||||
break;
|
||||
}
|
||||
if (file_exists(filename_to_remove)) {
|
||||
@ -380,7 +379,7 @@ void DataFlash_File::Prep_MinSpace()
|
||||
// sequence of files... however, there may be still
|
||||
// files out there, so keep going.
|
||||
} else {
|
||||
// internal_error();
|
||||
internal_error();
|
||||
break;
|
||||
}
|
||||
} else {
|
||||
|
@ -133,7 +133,7 @@ bool DataFlash_MAVLink::WritesOK() const
|
||||
bool DataFlash_MAVLink::_WritePrioritisedBlock(const void *pBuffer, uint16_t size, bool is_critical)
|
||||
{
|
||||
if (!semaphore->take_nonblocking()) {
|
||||
dropped++;
|
||||
_dropped++;
|
||||
return false;
|
||||
}
|
||||
|
||||
@ -145,7 +145,7 @@ bool DataFlash_MAVLink::_WritePrioritisedBlock(const void *pBuffer, uint16_t siz
|
||||
if (bufferspace_available() < size) {
|
||||
if (_startup_messagewriter->finished()) {
|
||||
// do not count the startup packets as being dropped...
|
||||
dropped++;
|
||||
_dropped++;
|
||||
}
|
||||
semaphore->give();
|
||||
return false;
|
||||
@ -306,13 +306,9 @@ void DataFlash_MAVLink::handle_retry(uint32_t seqno)
|
||||
}
|
||||
}
|
||||
|
||||
void DataFlash_MAVLink::internal_error() {
|
||||
internal_errors++;
|
||||
DataFlash_Backend::internal_error();
|
||||
}
|
||||
void DataFlash_MAVLink::stats_init() {
|
||||
dropped = 0;
|
||||
internal_errors = 0;
|
||||
_dropped = 0;
|
||||
_internal_errors = 0;
|
||||
stats.resends = 0;
|
||||
stats_reset();
|
||||
}
|
||||
@ -341,10 +337,10 @@ void DataFlash_MAVLink::Log_Write_DF_MAV(DataFlash_MAVLink &df)
|
||||
LOG_PACKET_HEADER_INIT(LOG_DF_MAV_STATS),
|
||||
timestamp : AP_HAL::millis(),
|
||||
seqno : df._next_seq_num-1,
|
||||
dropped : df.dropped,
|
||||
dropped : df._dropped,
|
||||
retries : df._blocks_retry.sent_count,
|
||||
resends : df.stats.resends,
|
||||
internal_errors : df.internal_errors,
|
||||
internal_errors : df._internal_errors,
|
||||
state_free_avg : (uint8_t)(df.stats.state_free/df.stats.collection_count),
|
||||
state_free_min : df.stats.state_free_min,
|
||||
state_free_max : df.stats.state_free_max,
|
||||
|
@ -151,7 +151,6 @@ private:
|
||||
|
||||
void Log_Write_DF_MAV(DataFlash_MAVLink &df);
|
||||
|
||||
void internal_error();
|
||||
uint32_t bufferspace_available() override; // in bytes
|
||||
uint8_t remaining_space_in_current_block();
|
||||
// write buffer
|
||||
|
Loading…
Reference in New Issue
Block a user