From 334af1ecd7946ff8a38adfc202f124e90d8c3e1d Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Fri, 15 Apr 2016 19:53:54 +1000 Subject: [PATCH] DataFlash: base class method for resetting state on log open --- libraries/DataFlash/DataFlash_Backend.cpp | 4 ++++ libraries/DataFlash/DataFlash_Backend.h | 3 +++ libraries/DataFlash/DataFlash_File.cpp | 2 +- libraries/DataFlash/DataFlash_MAVLink.cpp | 2 +- 4 files changed, 9 insertions(+), 2 deletions(-) diff --git a/libraries/DataFlash/DataFlash_Backend.cpp b/libraries/DataFlash/DataFlash_Backend.cpp index edcaa6d2fe..40f700566f 100644 --- a/libraries/DataFlash/DataFlash_Backend.cpp +++ b/libraries/DataFlash/DataFlash_Backend.cpp @@ -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++; diff --git a/libraries/DataFlash/DataFlash_Backend.h b/libraries/DataFlash/DataFlash_Backend.h index b172282190..916bafedd7 100644 --- a/libraries/DataFlash/DataFlash_Backend.h +++ b/libraries/DataFlash/DataFlash_Backend.h @@ -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; diff --git a/libraries/DataFlash/DataFlash_File.cpp b/libraries/DataFlash/DataFlash_File.cpp index 0aef56cea8..42c803ca74 100644 --- a/libraries/DataFlash/DataFlash_File.cpp +++ b/libraries/DataFlash/DataFlash_File.cpp @@ -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 diff --git a/libraries/DataFlash/DataFlash_MAVLink.cpp b/libraries/DataFlash/DataFlash_MAVLink.cpp index b9d1d6397b..d95999e514 100644 --- a/libraries/DataFlash/DataFlash_MAVLink.cpp +++ b/libraries/DataFlash/DataFlash_MAVLink.cpp @@ -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); }