mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-22 16:48:29 -04:00
DataFlash: added logging_started() API
This commit is contained in:
parent
8755747da0
commit
ef28d087d2
@ -52,6 +52,8 @@ public:
|
||||
void Log_Write_Message(const char *message);
|
||||
void Log_Write_Message_P(const prog_char_t *message);
|
||||
|
||||
bool logging_started(void) const { return log_write_started; }
|
||||
|
||||
/*
|
||||
every logged packet starts with 3 bytes
|
||||
*/
|
||||
@ -76,6 +78,7 @@ protected:
|
||||
const struct LogStructure *_structures;
|
||||
uint8_t _num_types;
|
||||
bool _writes_enabled;
|
||||
bool log_write_started;
|
||||
|
||||
/*
|
||||
read a block
|
||||
|
@ -54,7 +54,6 @@ private:
|
||||
uint16_t df_Read_PageAdr;
|
||||
uint16_t df_FileNumber;
|
||||
uint16_t df_FilePage;
|
||||
bool log_write_started;
|
||||
|
||||
// offset from adding FMT messages to log data
|
||||
bool adding_fmt_headers;
|
||||
|
@ -349,6 +349,7 @@ void DataFlash_File::stop_logging(void)
|
||||
if (_write_fd != -1) {
|
||||
int fd = _write_fd;
|
||||
_write_fd = -1;
|
||||
log_write_started = false;
|
||||
::close(fd);
|
||||
}
|
||||
}
|
||||
@ -382,6 +383,7 @@ uint16_t DataFlash_File::start_new_log(void)
|
||||
return 0xFFFF;
|
||||
}
|
||||
_write_offset = 0;
|
||||
log_write_started = true;
|
||||
|
||||
// now update lastlog.txt with the new log number
|
||||
fname = _lastlog_file_name();
|
||||
|
Loading…
Reference in New Issue
Block a user