Browse Source

DataFlash: move starting of new logs into DataFlash

master
Peter Barker 8 years ago committed by Francisco Ferreira
parent
commit
b572c13ca9
  1. 11
      libraries/DataFlash/DataFlash.cpp
  2. 3
      libraries/DataFlash/DataFlash.h
  3. 25
      libraries/DataFlash/DataFlash_Backend.cpp
  4. 6
      libraries/DataFlash/DataFlash_Backend.h
  5. 19
      libraries/DataFlash/DataFlash_File.cpp
  6. 3
      libraries/DataFlash/DataFlash_File.h
  7. 2
      libraries/DataFlash/DataFlash_MAVLink.cpp
  8. 2
      libraries/DataFlash/DataFlash_MAVLink.h

11
libraries/DataFlash/DataFlash.cpp

@ -296,17 +296,6 @@ void DataFlash_Class::backend_starting_new_log(const DataFlash_Backend *backend) @@ -296,17 +296,6 @@ void DataFlash_Class::backend_starting_new_log(const DataFlash_Backend *backend)
}
}
// start any backend which hasn't started; this is only called from
// the vehicle code
void DataFlash_Class::StartUnstartedLogging(void)
{
for (uint8_t i=0; i<_next_backend; i++) {
if (!backends[i]->logging_started()) {
backends[i]->start_new_log();
}
}
}
bool DataFlash_Class::should_log(const uint32_t mask) const
{
if (!(mask & _log_bitmask)) {

3
libraries/DataFlash/DataFlash.h

@ -101,9 +101,6 @@ public: @@ -101,9 +101,6 @@ public:
void setVehicle_Startup_Log_Writer(vehicle_startup_message_Log_Writer writer);
/* poke backends to start if they're not already started */
void StartUnstartedLogging(void);
void EnableWrites(bool enable) { _writes_enabled = enable; }
bool WritesEnabled() const { return _writes_enabled; }

25
libraries/DataFlash/DataFlash_Backend.cpp

@ -260,6 +260,31 @@ bool DataFlash_Backend::Log_Write(const uint8_t msg_type, va_list arg_list, bool @@ -260,6 +260,31 @@ bool DataFlash_Backend::Log_Write(const uint8_t msg_type, va_list arg_list, bool
return WritePrioritisedBlock(buffer, msg_len, is_critical);
}
bool DataFlash_Backend::StartNewLogOK() const
{
if (logging_started()) {
return false;
}
if (_front._log_bitmask == 0) {
return false;
}
if (_front.in_log_download()) {
return false;
}
if (!DataFlash_Backend::WritesOK()) {
return false;
}
return true;
}
bool DataFlash_Backend::WritePrioritisedBlock(const void *pBuffer, uint16_t size, bool is_critical)
{
if (StartNewLogOK()) {
start_new_log();
}
return _WritePrioritisedBlock(pBuffer, size, is_critical);
}
bool DataFlash_Backend::WritesOK() const
{
if (!_front.WritesEnabled()) {

6
libraries/DataFlash/DataFlash_Backend.h

@ -35,7 +35,7 @@ public: @@ -35,7 +35,7 @@ public:
return WritePrioritisedBlock(pBuffer, size, true);
}
virtual bool WritePrioritisedBlock(const void *pBuffer, uint16_t size, bool is_critical) = 0;
bool WritePrioritisedBlock(const void *pBuffer, uint16_t size, bool is_critical);
// high level interface
virtual uint16_t find_last_log() = 0;
@ -138,6 +138,7 @@ protected: @@ -138,6 +138,7 @@ protected:
AP_HAL::BetterStream *port);
virtual bool WritesOK() const;
virtual bool StartNewLogOK() const;
/*
read a block
@ -157,10 +158,13 @@ protected: @@ -157,10 +158,13 @@ protected:
// must be called when a new log is being started:
virtual void start_new_log_reset_variables();
virtual bool _WritePrioritisedBlock(const void *pBuffer, uint16_t size, bool is_critical) = 0;
bool _initialised;
private:
uint32_t _last_periodic_1Hz;
uint32_t _last_periodic_10Hz;
};

19
libraries/DataFlash/DataFlash_File.cpp

@ -525,8 +525,17 @@ bool DataFlash_File::WritesOK() const @@ -525,8 +525,17 @@ bool DataFlash_File::WritesOK() const
return true;
}
bool DataFlash_File::StartNewLogOK() const
{
if (_open_error) {
return false;
}
return DataFlash_Backend::StartNewLogOK();
}
/* Write a block of data at current offset */
bool DataFlash_File::WritePrioritisedBlock(const void *pBuffer, uint16_t size, bool is_critical)
bool DataFlash_File::_WritePrioritisedBlock(const void *pBuffer, uint16_t size, bool is_critical)
{
if (!WritesOK()) {
return false;
@ -870,6 +879,7 @@ uint16_t DataFlash_File::start_new_log(void) @@ -870,6 +879,7 @@ uint16_t DataFlash_File::start_new_log(void)
}
char *fname = _log_file_name(log_num);
if (fname == nullptr) {
_open_error = true;
return 0xFFFF;
}
_write_fd = ::open(fname, O_WRONLY|O_CREAT|O_TRUNC|O_CLOEXEC, 0666);
@ -899,6 +909,7 @@ uint16_t DataFlash_File::start_new_log(void) @@ -899,6 +909,7 @@ uint16_t DataFlash_File::start_new_log(void)
int fd = open(fname, O_WRONLY|O_CREAT|O_CLOEXEC, 0644);
free(fname);
if (fd == -1) {
_open_error = true;
return 0xFFFF;
}
@ -909,6 +920,7 @@ uint16_t DataFlash_File::start_new_log(void) @@ -909,6 +920,7 @@ uint16_t DataFlash_File::start_new_log(void)
close(fd);
if (written < to_write) {
_open_error = true;
return 0xFFFF;
}
@ -1172,11 +1184,6 @@ bool DataFlash_File::io_thread_alive() const @@ -1172,11 +1184,6 @@ bool DataFlash_File::io_thread_alive() const
bool DataFlash_File::logging_failed() const
{
if (_write_fd == -1 &&
(hal.util->get_soft_armed() ||
_front.log_while_disarmed())) {
return true;
}
if (_open_error) {
return true;
}

3
libraries/DataFlash/DataFlash_File.h

@ -43,7 +43,7 @@ public: @@ -43,7 +43,7 @@ public:
void Prep() override;
/* Write a block of data at current offset */
bool WritePrioritisedBlock(const void *pBuffer, uint16_t size, bool is_critical) override;
bool _WritePrioritisedBlock(const void *pBuffer, uint16_t size, bool is_critical) override;
uint32_t bufferspace_available() override;
// high level interface
@ -76,6 +76,7 @@ public: @@ -76,6 +76,7 @@ public:
protected:
bool WritesOK() const override;
bool StartNewLogOK() const override;
private:
int _write_fd;

2
libraries/DataFlash/DataFlash_MAVLink.cpp

@ -133,7 +133,7 @@ bool DataFlash_MAVLink::WritesOK() const @@ -133,7 +133,7 @@ bool DataFlash_MAVLink::WritesOK() const
/* Write a block of data at current offset */
// DM_write: 70734 events, 0 overruns, 167806us elapsed, 2us avg, min 1us max 34us 0.620us rms
bool DataFlash_MAVLink::WritePrioritisedBlock(const void *pBuffer, uint16_t size, bool is_critical)
bool DataFlash_MAVLink::_WritePrioritisedBlock(const void *pBuffer, uint16_t size, bool is_critical)
{
if (!WritesOK()) {
return false;

2
libraries/DataFlash/DataFlash_MAVLink.h

@ -36,7 +36,7 @@ public: @@ -36,7 +36,7 @@ public:
void stop_logging() override;
/* Write a block of data at current offset */
bool WritePrioritisedBlock(const void *pBuffer, uint16_t size,
bool _WritePrioritisedBlock(const void *pBuffer, uint16_t size,
bool is_critical) override;
// initialisation

Loading…
Cancel
Save