mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
DataFlash: base class method for resetting state on log open
This commit is contained in:
parent
eea2d5dcb5
commit
334af1ecd7
@ -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++;
|
||||
|
@ -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;
|
||||
|
@ -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
|
||||
|
@ -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);
|
||||
}
|
||||
|
Loading…
Reference in New Issue
Block a user