DataFlash: backend/frontend split
This commit is contained in:
parent
21c8a2d94a
commit
723c37bcf7
70
libraries/DataFlash/DataFlash.cpp
Normal file
70
libraries/DataFlash/DataFlash.cpp
Normal file
@ -0,0 +1,70 @@
|
|||||||
|
#include <DataFlash.h>
|
||||||
|
|
||||||
|
// start functions pass straight through to backend:
|
||||||
|
void DataFlash_Class::WriteBlock(const void *pBuffer, uint16_t size) {
|
||||||
|
backend->WriteBlock(pBuffer, size);
|
||||||
|
}
|
||||||
|
uint16_t DataFlash_Class::start_new_log() {
|
||||||
|
return backend->start_new_log();
|
||||||
|
}
|
||||||
|
|
||||||
|
// change me to "DoTimeConsumingPreparations"?
|
||||||
|
void DataFlash_Class::EraseAll() {
|
||||||
|
backend->EraseAll();
|
||||||
|
}
|
||||||
|
// change me to "LoggingAvailable"?
|
||||||
|
bool DataFlash_Class::CardInserted(void) {
|
||||||
|
return backend->CardInserted();
|
||||||
|
}
|
||||||
|
// remove me in favour of calling "DoTimeConsumingPreparations" all the time?
|
||||||
|
bool DataFlash_Class::NeedErase(void) {
|
||||||
|
return backend->NeedErase();
|
||||||
|
}
|
||||||
|
|
||||||
|
uint16_t DataFlash_Class::find_last_log(void) {
|
||||||
|
return backend->find_last_log();
|
||||||
|
}
|
||||||
|
void DataFlash_Class::get_log_boundaries(uint16_t log_num, uint16_t & start_page, uint16_t & end_page) {
|
||||||
|
backend->get_log_boundaries(log_num, start_page, end_page);
|
||||||
|
}
|
||||||
|
void DataFlash_Class::get_log_info(uint16_t log_num, uint32_t &size, uint32_t &time_utc) {
|
||||||
|
backend->get_log_info(log_num, size, time_utc);
|
||||||
|
}
|
||||||
|
int16_t DataFlash_Class::get_log_data(uint16_t log_num, uint16_t page, uint32_t offset, uint16_t len, uint8_t *data) {
|
||||||
|
return backend->get_log_data(log_num, page, offset, len, data);
|
||||||
|
}
|
||||||
|
uint16_t DataFlash_Class::get_num_logs(void) {
|
||||||
|
return backend->get_num_logs();
|
||||||
|
}
|
||||||
|
void DataFlash_Class::Log_Fill_Format(const struct LogStructure *s, struct log_Format &pkt) {
|
||||||
|
backend->Log_Fill_Format(s, pkt);
|
||||||
|
}
|
||||||
|
|
||||||
|
#ifndef DATAFLASH_NO_CLI
|
||||||
|
void DataFlash_Class::LogReadProcess(uint16_t log_num,
|
||||||
|
uint16_t start_page, uint16_t end_page,
|
||||||
|
print_mode_fn printMode,
|
||||||
|
AP_HAL::BetterStream *port) {
|
||||||
|
backend->LogReadProcess(log_num, start_page, end_page, printMode, port);
|
||||||
|
}
|
||||||
|
void DataFlash_Class::DumpPageInfo(AP_HAL::BetterStream *port) {
|
||||||
|
backend->DumpPageInfo(port);
|
||||||
|
}
|
||||||
|
void DataFlash_Class::ShowDeviceInfo(AP_HAL::BetterStream *port) {
|
||||||
|
backend->ShowDeviceInfo(port);
|
||||||
|
}
|
||||||
|
void DataFlash_Class::ListAvailableLogs(AP_HAL::BetterStream *port) {
|
||||||
|
backend->ListAvailableLogs(port);
|
||||||
|
}
|
||||||
|
#endif // DATAFLASH_NO_CLI
|
||||||
|
|
||||||
|
bool DataFlash_Class::logging_started(void) {
|
||||||
|
return backend->log_write_started;
|
||||||
|
}
|
||||||
|
|
||||||
|
void DataFlash_Class::EnableWrites(bool enable) {
|
||||||
|
backend->EnableWrites(enable);
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
|
// end functions pass straight through to backend
|
@ -17,15 +17,14 @@
|
|||||||
#include "../AP_Airspeed/AP_Airspeed.h"
|
#include "../AP_Airspeed/AP_Airspeed.h"
|
||||||
#include "../AP_BattMonitor/AP_BattMonitor.h"
|
#include "../AP_BattMonitor/AP_BattMonitor.h"
|
||||||
#include <stdint.h>
|
#include <stdint.h>
|
||||||
|
#include <DataFlash_Backend.h>
|
||||||
|
|
||||||
#if CONFIG_HAL_BOARD == HAL_BOARD_PX4
|
#if CONFIG_HAL_BOARD == HAL_BOARD_PX4
|
||||||
#include <uORB/topics/esc_status.h>
|
#include <uORB/topics/esc_status.h>
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
|
||||||
#if HAL_CPU_CLASS < HAL_CPU_CLASS_75
|
class DataFlash_Backend;
|
||||||
#define DATAFLASH_NO_CLI
|
|
||||||
#endif
|
|
||||||
|
|
||||||
class DataFlash_Class
|
class DataFlash_Class
|
||||||
{
|
{
|
||||||
@ -33,36 +32,36 @@ public:
|
|||||||
FUNCTOR_TYPEDEF(print_mode_fn, void, AP_HAL::BetterStream*, uint8_t);
|
FUNCTOR_TYPEDEF(print_mode_fn, void, AP_HAL::BetterStream*, uint8_t);
|
||||||
|
|
||||||
// initialisation
|
// initialisation
|
||||||
virtual void Init(const struct LogStructure *structure, uint8_t num_types);
|
void Init(const struct LogStructure *structure, uint8_t num_types);
|
||||||
virtual bool CardInserted(void) = 0;
|
bool CardInserted(void);
|
||||||
|
|
||||||
// erase handling
|
// erase handling
|
||||||
virtual bool NeedErase(void) = 0;
|
bool NeedErase(void);
|
||||||
virtual void EraseAll() = 0;
|
void EraseAll();
|
||||||
|
|
||||||
/* Write a block of data at current offset */
|
/* Write a block of data at current offset */
|
||||||
virtual void WriteBlock(const void *pBuffer, uint16_t size) = 0;
|
void WriteBlock(const void *pBuffer, uint16_t size);
|
||||||
|
|
||||||
// high level interface
|
// high level interface
|
||||||
virtual uint16_t find_last_log(void) = 0;
|
uint16_t find_last_log(void);
|
||||||
virtual void get_log_boundaries(uint16_t log_num, uint16_t & start_page, uint16_t & end_page) = 0;
|
void get_log_boundaries(uint16_t log_num, uint16_t & start_page, uint16_t & end_page);
|
||||||
virtual void get_log_info(uint16_t log_num, uint32_t &size, uint32_t &time_utc) = 0;
|
void get_log_info(uint16_t log_num, uint32_t &size, uint32_t &time_utc);
|
||||||
virtual int16_t get_log_data(uint16_t log_num, uint16_t page, uint32_t offset, uint16_t len, uint8_t *data) = 0;
|
int16_t get_log_data(uint16_t log_num, uint16_t page, uint32_t offset, uint16_t len, uint8_t *data);
|
||||||
virtual uint16_t get_num_logs(void) = 0;
|
uint16_t get_num_logs(void);
|
||||||
#ifndef DATAFLASH_NO_CLI
|
#ifndef DATAFLASH_NO_CLI
|
||||||
virtual void LogReadProcess(uint16_t log_num,
|
void LogReadProcess(uint16_t log_num,
|
||||||
uint16_t start_page, uint16_t end_page,
|
uint16_t start_page, uint16_t end_page,
|
||||||
print_mode_fn printMode,
|
print_mode_fn printMode,
|
||||||
AP_HAL::BetterStream *port) = 0;
|
AP_HAL::BetterStream *port);
|
||||||
virtual void DumpPageInfo(AP_HAL::BetterStream *port) = 0;
|
void DumpPageInfo(AP_HAL::BetterStream *port);
|
||||||
virtual void ShowDeviceInfo(AP_HAL::BetterStream *port) = 0;
|
void ShowDeviceInfo(AP_HAL::BetterStream *port);
|
||||||
virtual void ListAvailableLogs(AP_HAL::BetterStream *port) = 0;
|
void ListAvailableLogs(AP_HAL::BetterStream *port);
|
||||||
#endif // DATAFLASH_NO_CLI
|
#endif // DATAFLASH_NO_CLI
|
||||||
|
|
||||||
/* logging methods common to all vehicles */
|
/* logging methods common to all vehicles */
|
||||||
uint16_t StartNewLog(void);
|
uint16_t StartNewLog(void);
|
||||||
void AddLogFormats(const struct LogStructure *structures, uint8_t num_types);
|
void AddLogFormats(const struct LogStructure *structures, uint8_t num_types);
|
||||||
void EnableWrites(bool enable) { _writes_enabled = enable; }
|
void EnableWrites(bool enable);
|
||||||
void Log_Write_Format(const struct LogStructure *structure);
|
void Log_Write_Format(const struct LogStructure *structure);
|
||||||
void Log_Write_Parameter(const char *name, float value);
|
void Log_Write_Parameter(const char *name, float value);
|
||||||
void Log_Write_GPS(const AP_GPS &gps, uint8_t instance, int32_t relative_alt);
|
void Log_Write_GPS(const AP_GPS &gps, uint8_t instance, int32_t relative_alt);
|
||||||
@ -103,38 +102,19 @@ public:
|
|||||||
|
|
||||||
void Log_Write_PID(uint8_t msg_type, const PID_Info &info);
|
void Log_Write_PID(uint8_t msg_type, const PID_Info &info);
|
||||||
|
|
||||||
bool logging_started(void) const { return log_write_started; }
|
bool logging_started(void);
|
||||||
|
|
||||||
/*
|
|
||||||
every logged packet starts with 3 bytes
|
|
||||||
*/
|
|
||||||
struct log_Header {
|
|
||||||
uint8_t head1, head2, msgid;
|
|
||||||
};
|
|
||||||
|
|
||||||
protected:
|
protected:
|
||||||
/*
|
|
||||||
read and print a log entry using the format strings from the given structure
|
|
||||||
*/
|
|
||||||
void _print_log_entry(uint8_t msg_type,
|
|
||||||
print_mode_fn print_mode,
|
|
||||||
AP_HAL::BetterStream *port);
|
|
||||||
|
|
||||||
void Log_Fill_Format(const struct LogStructure *structure, struct log_Format &pkt);
|
void Log_Fill_Format(const struct LogStructure *structure, struct log_Format &pkt);
|
||||||
void Log_Write_Parameter(const AP_Param *ap, const AP_Param::ParamToken &token,
|
void Log_Write_Parameter(const AP_Param *ap, const AP_Param::ParamToken &token,
|
||||||
enum ap_var_type type);
|
enum ap_var_type type);
|
||||||
virtual uint16_t start_new_log(void) = 0;
|
uint16_t start_new_log(void);
|
||||||
|
|
||||||
const struct LogStructure *_structures;
|
const struct LogStructure *_structures;
|
||||||
uint8_t _num_types;
|
uint8_t _num_types;
|
||||||
bool _writes_enabled;
|
|
||||||
bool log_write_started;
|
|
||||||
|
|
||||||
/*
|
|
||||||
read a block
|
|
||||||
*/
|
|
||||||
virtual bool ReadBlock(void *pkt, uint16_t size) = 0;
|
|
||||||
|
|
||||||
|
private:
|
||||||
|
DataFlash_Backend *backend;
|
||||||
};
|
};
|
||||||
|
|
||||||
/*
|
/*
|
||||||
|
@ -89,7 +89,7 @@ bool DataFlash_APM1::_sem_take(uint8_t timeout)
|
|||||||
// Public Methods //////////////////////////////////////////////////////////////
|
// Public Methods //////////////////////////////////////////////////////////////
|
||||||
void DataFlash_APM1::Init(const struct LogStructure *structure, uint8_t num_types)
|
void DataFlash_APM1::Init(const struct LogStructure *structure, uint8_t num_types)
|
||||||
{
|
{
|
||||||
DataFlash_Class::Init(structure, num_types);
|
DataFlash_Backend::Init(structure, num_types);
|
||||||
// init to zero
|
// init to zero
|
||||||
df_NumPages = 0;
|
df_NumPages = 0;
|
||||||
|
|
||||||
|
@ -44,6 +44,8 @@ private:
|
|||||||
bool _sem_take(uint8_t timeout);
|
bool _sem_take(uint8_t timeout);
|
||||||
|
|
||||||
public:
|
public:
|
||||||
|
DataFlash_APM1(DataFlash_Class &front) :
|
||||||
|
DataFlash_Block(front) { }
|
||||||
void Init(const struct LogStructure *structure, uint8_t num_types);
|
void Init(const struct LogStructure *structure, uint8_t num_types);
|
||||||
void ReadManufacturerID();
|
void ReadManufacturerID();
|
||||||
bool CardInserted();
|
bool CardInserted();
|
||||||
|
@ -89,7 +89,7 @@ bool DataFlash_APM2::_sem_take(uint8_t timeout)
|
|||||||
// Public Methods //////////////////////////////////////////////////////////////
|
// Public Methods //////////////////////////////////////////////////////////////
|
||||||
void DataFlash_APM2::Init(const struct LogStructure *structure, uint8_t num_types)
|
void DataFlash_APM2::Init(const struct LogStructure *structure, uint8_t num_types)
|
||||||
{
|
{
|
||||||
DataFlash_Class::Init(structure, num_types);
|
DataFlash_Backend::Init(structure, num_types);
|
||||||
// init to zero
|
// init to zero
|
||||||
df_NumPages = 0;
|
df_NumPages = 0;
|
||||||
|
|
||||||
|
@ -7,7 +7,7 @@
|
|||||||
#define __DATAFLASH_APM2_H__
|
#define __DATAFLASH_APM2_H__
|
||||||
|
|
||||||
#include <AP_HAL.h>
|
#include <AP_HAL.h>
|
||||||
#include "DataFlash.h"
|
#include "DataFlash_Block.h"
|
||||||
|
|
||||||
class DataFlash_APM2 : public DataFlash_Block
|
class DataFlash_APM2 : public DataFlash_Block
|
||||||
{
|
{
|
||||||
@ -44,6 +44,9 @@ private:
|
|||||||
AP_HAL::Semaphore* _spi_sem;
|
AP_HAL::Semaphore* _spi_sem;
|
||||||
|
|
||||||
public:
|
public:
|
||||||
|
DataFlash_APM2(DataFlash_Class &front) :
|
||||||
|
DataFlash_Block(front) { }
|
||||||
|
|
||||||
void Init(const struct LogStructure *structure, uint8_t num_types);
|
void Init(const struct LogStructure *structure, uint8_t num_types);
|
||||||
void ReadManufacturerID();
|
void ReadManufacturerID();
|
||||||
bool CardInserted();
|
bool CardInserted();
|
||||||
|
92
libraries/DataFlash/DataFlash_Backend.h
Normal file
92
libraries/DataFlash/DataFlash_Backend.h
Normal file
@ -0,0 +1,92 @@
|
|||||||
|
#ifndef DATAFLASH_BACKEND_H
|
||||||
|
#define DATAFLASH_BACKEND_H
|
||||||
|
|
||||||
|
#if HAL_CPU_CLASS < HAL_CPU_CLASS_75
|
||||||
|
#define DATAFLASH_NO_CLI
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#include <AP_HAL.h>
|
||||||
|
#include <AP_Common.h>
|
||||||
|
#include <AP_Param.h>
|
||||||
|
#include <AP_GPS.h>
|
||||||
|
#include <AP_InertialSensor.h>
|
||||||
|
#include <AP_Baro.h>
|
||||||
|
#include <AP_AHRS.h>
|
||||||
|
#include <AP_Vehicle.h>
|
||||||
|
#include "../AP_Airspeed/AP_Airspeed.h"
|
||||||
|
#include "../AP_BattMonitor/AP_BattMonitor.h"
|
||||||
|
#include <stdint.h>
|
||||||
|
|
||||||
|
class DataFlash_Backend
|
||||||
|
{
|
||||||
|
public:
|
||||||
|
FUNCTOR_TYPEDEF(print_mode_fn, void, AP_HAL::BetterStream*, uint8_t);
|
||||||
|
|
||||||
|
DataFlash_Backend(DataFlash_Class &front) :
|
||||||
|
_front(front)
|
||||||
|
{ }
|
||||||
|
|
||||||
|
virtual bool CardInserted(void) = 0;
|
||||||
|
|
||||||
|
// erase handling
|
||||||
|
virtual bool NeedErase(void) = 0;
|
||||||
|
virtual void EraseAll() = 0;
|
||||||
|
|
||||||
|
/* Write a block of data at current offset */
|
||||||
|
virtual void WriteBlock(const void *pBuffer, uint16_t size) = 0;
|
||||||
|
|
||||||
|
// high level interface
|
||||||
|
virtual uint16_t find_last_log(void) = 0;
|
||||||
|
virtual void get_log_boundaries(uint16_t log_num, uint16_t & start_page, uint16_t & end_page) = 0;
|
||||||
|
virtual void get_log_info(uint16_t log_num, uint32_t &size, uint32_t &time_utc) = 0;
|
||||||
|
virtual int16_t get_log_data(uint16_t log_num, uint16_t page, uint32_t offset, uint16_t len, uint8_t *data) = 0;
|
||||||
|
virtual uint16_t get_num_logs(void) = 0;
|
||||||
|
#ifndef DATAFLASH_NO_CLI
|
||||||
|
virtual void LogReadProcess(uint16_t log_num,
|
||||||
|
uint16_t start_page, uint16_t end_page,
|
||||||
|
print_mode_fn printMode,
|
||||||
|
AP_HAL::BetterStream *port) = 0;
|
||||||
|
virtual void DumpPageInfo(AP_HAL::BetterStream *port) = 0;
|
||||||
|
virtual void ShowDeviceInfo(AP_HAL::BetterStream *port) = 0;
|
||||||
|
virtual void ListAvailableLogs(AP_HAL::BetterStream *port) = 0;
|
||||||
|
#endif // DATAFLASH_NO_CLI
|
||||||
|
|
||||||
|
void EnableWrites(bool enable) { _writes_enabled = enable; }
|
||||||
|
bool logging_started(void) const { return log_write_started; }
|
||||||
|
|
||||||
|
// initialisation this really shouldn't take structure and
|
||||||
|
// num_types, however the CLI LogReadProcess function requires it.
|
||||||
|
// That function needs to be split.
|
||||||
|
virtual void Init(const struct LogStructure *structure, uint8_t num_types) {
|
||||||
|
_writes_enabled = true;
|
||||||
|
_num_types = num_types;
|
||||||
|
_structures = structure;
|
||||||
|
}
|
||||||
|
|
||||||
|
virtual uint16_t start_new_log(void) = 0;
|
||||||
|
bool log_write_started;
|
||||||
|
|
||||||
|
void Log_Fill_Format(const struct LogStructure *structure, struct log_Format &pkt);
|
||||||
|
|
||||||
|
protected:
|
||||||
|
DataFlash_Class &_front;
|
||||||
|
|
||||||
|
/*
|
||||||
|
read and print a log entry using the format strings from the given structure
|
||||||
|
*/
|
||||||
|
void _print_log_entry(uint8_t msg_type,
|
||||||
|
print_mode_fn print_mode,
|
||||||
|
AP_HAL::BetterStream *port);
|
||||||
|
|
||||||
|
const struct LogStructure *_structures;
|
||||||
|
uint8_t _num_types = 0;
|
||||||
|
bool _writes_enabled = false;
|
||||||
|
|
||||||
|
/*
|
||||||
|
read a block
|
||||||
|
*/
|
||||||
|
virtual bool ReadBlock(void *pkt, uint16_t size) = 0;
|
||||||
|
|
||||||
|
};
|
||||||
|
|
||||||
|
#endif
|
@ -7,11 +7,16 @@
|
|||||||
#ifndef DataFlash_block_h
|
#ifndef DataFlash_block_h
|
||||||
#define DataFlash_block_h
|
#define DataFlash_block_h
|
||||||
|
|
||||||
|
#include <DataFlash_Backend.h>
|
||||||
|
|
||||||
#include <stdint.h>
|
#include <stdint.h>
|
||||||
|
|
||||||
class DataFlash_Block : public DataFlash_Class
|
class DataFlash_Block : public DataFlash_Backend
|
||||||
{
|
{
|
||||||
public:
|
public:
|
||||||
|
DataFlash_Block(DataFlash_Class &front) :
|
||||||
|
DataFlash_Backend(front) { }
|
||||||
|
|
||||||
// initialisation
|
// initialisation
|
||||||
virtual void Init(const struct LogStructure *structure, uint8_t num_types) = 0;
|
virtual void Init(const struct LogStructure *structure, uint8_t num_types) = 0;
|
||||||
virtual bool CardInserted(void) = 0;
|
virtual bool CardInserted(void) = 0;
|
||||||
|
@ -10,7 +10,7 @@
|
|||||||
// Public Methods //////////////////////////////////////////////////////////////
|
// Public Methods //////////////////////////////////////////////////////////////
|
||||||
void DataFlash_Empty::Init(const struct LogStructure *structure, uint8_t num_types)
|
void DataFlash_Empty::Init(const struct LogStructure *structure, uint8_t num_types)
|
||||||
{
|
{
|
||||||
DataFlash_Class::Init(structure, num_types);
|
DataFlash_Backend::Init(structure, num_types);
|
||||||
df_PageSize = DF_PAGE_SIZE;
|
df_PageSize = DF_PAGE_SIZE;
|
||||||
// reserve last page for config information
|
// reserve last page for config information
|
||||||
df_NumPages = DF_NUM_PAGES - 1;
|
df_NumPages = DF_NUM_PAGES - 1;
|
||||||
|
@ -7,7 +7,7 @@
|
|||||||
#define __DATAFLASH_EMPTY_H__
|
#define __DATAFLASH_EMPTY_H__
|
||||||
|
|
||||||
#include <AP_HAL.h>
|
#include <AP_HAL.h>
|
||||||
#include "DataFlash.h"
|
#include "DataFlash_Block.h"
|
||||||
|
|
||||||
class DataFlash_Empty : public DataFlash_Block
|
class DataFlash_Empty : public DataFlash_Block
|
||||||
{
|
{
|
||||||
@ -30,6 +30,8 @@ private:
|
|||||||
bool BlockRead(uint8_t BufferNum, uint16_t IntPageAdr, void *pBuffer, uint16_t size);
|
bool BlockRead(uint8_t BufferNum, uint16_t IntPageAdr, void *pBuffer, uint16_t size);
|
||||||
|
|
||||||
public:
|
public:
|
||||||
|
DataFlash_Empty(DataFlash_Class &front) :
|
||||||
|
DataFlash_Block(front) { }
|
||||||
void Init(const struct LogStructure *structure, uint8_t num_types);
|
void Init(const struct LogStructure *structure, uint8_t num_types);
|
||||||
void ReadManufacturerID();
|
void ReadManufacturerID();
|
||||||
bool CardInserted();
|
bool CardInserted();
|
||||||
|
@ -34,7 +34,8 @@ extern const AP_HAL::HAL& hal;
|
|||||||
/*
|
/*
|
||||||
constructor
|
constructor
|
||||||
*/
|
*/
|
||||||
DataFlash_File::DataFlash_File(const char *log_directory) :
|
DataFlash_File::DataFlash_File(DataFlash_Class &front, const char *log_directory) :
|
||||||
|
DataFlash_Backend(front),
|
||||||
_write_fd(-1),
|
_write_fd(-1),
|
||||||
_read_fd(-1),
|
_read_fd(-1),
|
||||||
_read_offset(0),
|
_read_offset(0),
|
||||||
@ -77,7 +78,7 @@ DataFlash_File::DataFlash_File(const char *log_directory) :
|
|||||||
// initialisation
|
// initialisation
|
||||||
void DataFlash_File::Init(const struct LogStructure *structure, uint8_t num_types)
|
void DataFlash_File::Init(const struct LogStructure *structure, uint8_t num_types)
|
||||||
{
|
{
|
||||||
DataFlash_Class::Init(structure, num_types);
|
DataFlash_Backend::Init(structure, num_types);
|
||||||
// create the log directory if need be
|
// create the log directory if need be
|
||||||
int ret;
|
int ret;
|
||||||
struct stat st;
|
struct stat st;
|
||||||
|
@ -19,11 +19,13 @@
|
|||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
|
||||||
class DataFlash_File : public DataFlash_Class
|
#include "DataFlash_Backend.h"
|
||||||
|
|
||||||
|
class DataFlash_File : public DataFlash_Backend
|
||||||
{
|
{
|
||||||
public:
|
public:
|
||||||
// constructor
|
// constructor
|
||||||
DataFlash_File(const char *log_directory);
|
DataFlash_File(DataFlash_Class &front, const char *log_directory);
|
||||||
|
|
||||||
// initialisation
|
// initialisation
|
||||||
void Init(const struct LogStructure *structure, uint8_t num_types);
|
void Init(const struct LogStructure *structure, uint8_t num_types);
|
||||||
|
@ -29,7 +29,7 @@ static uint8_t buffer[2][DF_PAGE_SIZE];
|
|||||||
// Public Methods //////////////////////////////////////////////////////////////
|
// Public Methods //////////////////////////////////////////////////////////////
|
||||||
void DataFlash_SITL::Init(const struct LogStructure *structure, uint8_t num_types)
|
void DataFlash_SITL::Init(const struct LogStructure *structure, uint8_t num_types)
|
||||||
{
|
{
|
||||||
DataFlash_Class::Init(structure, num_types);
|
DataFlash_Backend::Init(structure, num_types);
|
||||||
if (flash_fd == 0) {
|
if (flash_fd == 0) {
|
||||||
flash_fd = open("dataflash.bin", O_RDWR, 0777);
|
flash_fd = open("dataflash.bin", O_RDWR, 0777);
|
||||||
if (flash_fd == -1) {
|
if (flash_fd == -1) {
|
||||||
|
@ -7,7 +7,7 @@
|
|||||||
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL
|
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL
|
||||||
|
|
||||||
#include <AP_HAL.h>
|
#include <AP_HAL.h>
|
||||||
#include "DataFlash.h"
|
#include "DataFlash_Block.h"
|
||||||
|
|
||||||
class DataFlash_SITL : public DataFlash_Block
|
class DataFlash_SITL : public DataFlash_Block
|
||||||
{
|
{
|
||||||
@ -40,8 +40,8 @@ private:
|
|||||||
AP_HAL::SPIDeviceDriver *_spi;
|
AP_HAL::SPIDeviceDriver *_spi;
|
||||||
AP_HAL::Semaphore *_spi_sem;
|
AP_HAL::Semaphore *_spi_sem;
|
||||||
public:
|
public:
|
||||||
|
DataFlash_SITL(DataFlash_Class &front) :
|
||||||
DataFlash_SITL() {}
|
DataFlash_Block(front) { }
|
||||||
void Init(const struct LogStructure *structure, uint8_t num_types);
|
void Init(const struct LogStructure *structure, uint8_t num_types);
|
||||||
void ReadManufacturerID();
|
void ReadManufacturerID();
|
||||||
bool CardInserted();
|
bool CardInserted();
|
||||||
|
@ -16,7 +16,22 @@ void DataFlash_Class::Init(const struct LogStructure *structure, uint8_t num_typ
|
|||||||
{
|
{
|
||||||
_num_types = num_types;
|
_num_types = num_types;
|
||||||
_structures = structure;
|
_structures = structure;
|
||||||
_writes_enabled = true;
|
|
||||||
|
// DataFlash
|
||||||
|
#if CONFIG_HAL_BOARD == HAL_BOARD_APM1
|
||||||
|
backend = new DataFlash_APM1(*this);
|
||||||
|
#elif CONFIG_HAL_BOARD == HAL_BOARD_APM2
|
||||||
|
backend = new DataFlash_APM2(*this);
|
||||||
|
#elif defined(HAL_BOARD_LOG_DIRECTORY)
|
||||||
|
backend = new DataFlash_File(*this, HAL_BOARD_LOG_DIRECTORY);
|
||||||
|
#else
|
||||||
|
// no dataflash driver
|
||||||
|
backend = new DataFlash_Empty(*this);
|
||||||
|
#endif
|
||||||
|
if (backend == NULL) {
|
||||||
|
hal.scheduler->panic(PSTR("Unable to open dataflash"));
|
||||||
|
}
|
||||||
|
backend->Init(structure, num_types);
|
||||||
}
|
}
|
||||||
|
|
||||||
// This function determines the number of whole or partial log files in the DataFlash
|
// This function determines the number of whole or partial log files in the DataFlash
|
||||||
@ -275,10 +290,11 @@ uint16_t DataFlash_Block::find_last_page_of_log(uint16_t log_number)
|
|||||||
#ifndef DATAFLASH_NO_CLI
|
#ifndef DATAFLASH_NO_CLI
|
||||||
/*
|
/*
|
||||||
read and print a log entry using the format strings from the given structure
|
read and print a log entry using the format strings from the given structure
|
||||||
|
- this really should in in the frontend, not the backend
|
||||||
*/
|
*/
|
||||||
void DataFlash_Class::_print_log_entry(uint8_t msg_type,
|
void DataFlash_Backend::_print_log_entry(uint8_t msg_type,
|
||||||
print_mode_fn print_mode,
|
print_mode_fn print_mode,
|
||||||
AP_HAL::BetterStream *port)
|
AP_HAL::BetterStream *port)
|
||||||
{
|
{
|
||||||
uint8_t i;
|
uint8_t i;
|
||||||
for (i=0; i<_num_types; i++) {
|
for (i=0; i<_num_types; i++) {
|
||||||
@ -605,9 +621,9 @@ void DataFlash_Class::AddLogFormats(const struct LogStructure *structures, uint8
|
|||||||
}
|
}
|
||||||
|
|
||||||
/*
|
/*
|
||||||
write a structure format to the log
|
write a structure format to the log - should be in frontend
|
||||||
*/
|
*/
|
||||||
void DataFlash_Class::Log_Fill_Format(const struct LogStructure *s, struct log_Format &pkt)
|
void DataFlash_Backend::Log_Fill_Format(const struct LogStructure *s, struct log_Format &pkt)
|
||||||
{
|
{
|
||||||
memset(&pkt, 0, sizeof(pkt));
|
memset(&pkt, 0, sizeof(pkt));
|
||||||
pkt.head1 = HEAD_BYTE1;
|
pkt.head1 = HEAD_BYTE1;
|
||||||
|
Loading…
Reference in New Issue
Block a user