DataFlash: rotate files when vehicle is disarmed

This commit is contained in:
Peter Barker 2016-07-28 15:58:20 +10:00 committed by Tom Pittenger
parent fc79fb4ab4
commit 2c8a0a9123
5 changed files with 29 additions and 2 deletions

View File

@ -31,7 +31,14 @@ const AP_Param::GroupInfo DataFlash_Class::var_info[] = {
// @Values: 0:Disabled,1:Enabled
// @User: Standard
AP_GROUPINFO("_REPLAY", 3, DataFlash_Class, _params.log_replay, 0),
// @Param: _FILE_DSRMROT
// @DisplayName: Stop logging to current file on disarm
// @Description: When set, the current log file is closed when the vehicle is disarmed. If LOG_DISARMED is set then a fresh log will be opened.
// @Values: 0:Disabled,1:Enabled
// @User: Standard
AP_GROUPINFO("_FILE_DSRMROT", 4, DataFlash_Class, _params.file_disarm_rot, 0),
AP_GROUPEND
};
@ -78,8 +85,13 @@ void DataFlash_Class::set_vehicle_armed(const bool armed_state)
// no change in status
return;
}
_armed = armed_state;
if (!_armed) {
// went from armed to disarmed
FOR_EACH_BACKEND(vehicle_was_disarmed());
}
}

View File

@ -192,6 +192,7 @@ public:
struct {
AP_Int8 backend_types;
AP_Int8 file_bufsize; // in kilobytes
AP_Int8 file_disarm_rot;
AP_Int8 log_disarmed;
AP_Int8 log_replay;
} _params;

View File

@ -121,6 +121,8 @@ public:
virtual bool logging_enabled() const = 0;
virtual bool logging_failed() const = 0;
virtual void vehicle_was_disarmed() { };
protected:
uint32_t dropped;
uint8_t internal_errors; // uint8_t - wishful thinking?

View File

@ -1108,4 +1108,14 @@ bool DataFlash_File::logging_failed() const
}
void DataFlash_File::vehicle_was_disarmed()
{
if (_front._params.file_disarm_rot) {
// rotate our log. Closing the current one and letting the
// logging restart naturally based on log_disarmed should do
// the trick:
stop_logging();
}
}
#endif // HAL_OS_POSIX_IO

View File

@ -70,6 +70,8 @@ public:
bool logging_enabled() const;
bool logging_failed() const;
void vehicle_was_disarmed() override;
private:
int _write_fd;
int _read_fd;