DataFlash: base class method for resetting state on log open

This commit is contained in:
Peter Barker 2016-04-15 19:53:54 +10:00 committed by Andrew Tridgell
parent eea2d5dcb5
commit 334af1ecd7
4 changed files with 9 additions and 2 deletions

View File

@ -50,6 +50,10 @@ void DataFlash_Backend::periodic_tasks()
periodic_fullrate(now);
}
void DataFlash_Backend::start_new_log_reset_variables()
{
_startup_messagewriter->reset();
}
void DataFlash_Backend::internal_error() {
_internal_errors++;

View File

@ -132,6 +132,9 @@ protected:
uint32_t _internal_errors;
uint32_t _dropped;
// must be called when a new log is being started:
virtual void start_new_log_reset_variables();
private:
uint32_t _last_periodic_1Hz;

View File

@ -803,7 +803,7 @@ uint16_t DataFlash_File::start_new_log(void)
{
stop_logging();
_startup_messagewriter->reset();
start_new_log_reset_variables();
if (_open_error) {
// we have previously failed to open a file - don't try again

View File

@ -231,7 +231,7 @@ void DataFlash_MAVLink::handle_ack(mavlink_channel_t chan,
_target_component_id = msg->compid;
_chan = chan;
_next_seq_num = 0;
_startup_messagewriter->reset();
start_new_log_reset_variables();
_last_response_time = AP_HAL::millis();
Debug("Target: (%u/%u)", _target_system_id, _target_component_id);
}