DataFlash: added structures to Init() of dataflash

this will allow the get_log_data() call to add FMT headers if a log
has wrapped
This commit is contained in:
Andrew Tridgell 2013-12-17 11:12:42 +11:00
parent 7642208c1a
commit e6bafa2d8f
13 changed files with 65 additions and 57 deletions

View File

@ -16,7 +16,7 @@ class DataFlash_Class
{
public:
// initialisation
virtual void Init(void) = 0;
virtual void Init(const struct LogStructure *structure, uint8_t num_types);
virtual bool CardInserted(void) = 0;
// erase handling
@ -34,8 +34,6 @@ public:
virtual uint16_t get_num_logs(void) = 0;
virtual void LogReadProcess(uint16_t log_num,
uint16_t start_page, uint16_t end_page,
uint8_t num_types,
const struct LogStructure *structure,
void (*printMode)(AP_HAL::BetterStream *port, uint8_t mode),
AP_HAL::BetterStream *port) = 0;
virtual void DumpPageInfo(AP_HAL::BetterStream *port) = 0;
@ -43,8 +41,7 @@ public:
virtual void ListAvailableLogs(AP_HAL::BetterStream *port) = 0;
/* logging methods common to all vehicles */
uint16_t StartNewLog(uint8_t num_types,
const struct LogStructure *structure);
uint16_t StartNewLog(void);
void Log_Write_Format(const struct LogStructure *structure);
void Log_Write_Parameter(const char *name, float value);
void Log_Write_GPS(const GPS *gps, int32_t relative_alt);
@ -66,16 +63,18 @@ protected:
read and print a log entry using the format strings from the given structure
*/
void _print_log_entry(uint8_t msg_type,
uint8_t num_types,
const struct LogStructure *structure,
void (*print_mode)(AP_HAL::BetterStream *port, uint8_t mode),
AP_HAL::BetterStream *port);
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,
enum ap_var_type type);
void Log_Write_Parameters(void);
virtual uint16_t start_new_log(void) = 0;
const struct LogStructure *_structures;
uint8_t _num_types;
/*
read a block
*/

View File

@ -87,8 +87,9 @@ bool DataFlash_APM1::_sem_take(uint8_t timeout)
// Public Methods //////////////////////////////////////////////////////////////
void DataFlash_APM1::Init(void)
void DataFlash_APM1::Init(const struct LogStructure *structure, uint8_t num_types)
{
DataFlash_Class::Init(structure, num_types);
// init to zero
df_NumPages = 0;

View File

@ -44,7 +44,7 @@ private:
bool _sem_take(uint8_t timeout);
public:
void Init();
void Init(const struct LogStructure *structure, uint8_t num_types);
void ReadManufacturerID();
bool CardInserted();
};

View File

@ -87,8 +87,9 @@ bool DataFlash_APM2::_sem_take(uint8_t timeout)
// Public Methods //////////////////////////////////////////////////////////////
void DataFlash_APM2::Init(void)
void DataFlash_APM2::Init(const struct LogStructure *structure, uint8_t num_types)
{
DataFlash_Class::Init(structure, num_types);
// init to zero
df_NumPages = 0;

View File

@ -45,7 +45,7 @@ private:
AP_HAL::Semaphore* _spi_sem;
public:
void Init();
void Init(const struct LogStructure *structure, uint8_t num_types);
void ReadManufacturerID();
bool CardInserted();
};

View File

@ -13,7 +13,7 @@ class DataFlash_Block : public DataFlash_Class
{
public:
// initialisation
virtual void Init(void) = 0;
virtual void Init(const struct LogStructure *structure, uint8_t num_types) = 0;
virtual bool CardInserted(void) = 0;
// erase handling
@ -27,13 +27,12 @@ public:
uint16_t find_last_log(void);
void get_log_boundaries(uint16_t log_num, uint16_t & start_page, uint16_t & end_page);
void get_log_info(uint16_t log_num, uint32_t &size, uint32_t &time_utc);
int16_t get_log_data_raw(uint16_t log_num, uint16_t page, uint32_t offset, uint16_t len, uint8_t *data);
int16_t get_log_data(uint16_t log_num, uint16_t page, uint32_t offset, uint16_t len, uint8_t *data);
uint16_t get_num_logs(void);
uint16_t start_new_log(void);
void LogReadProcess(uint16_t log_num,
uint16_t start_page, uint16_t end_page,
uint8_t num_types,
const struct LogStructure *structure,
void (*print_mode)(AP_HAL::BetterStream *port, uint8_t mode),
AP_HAL::BetterStream *port);
void DumpPageInfo(AP_HAL::BetterStream *port);
@ -97,9 +96,7 @@ private:
uint16_t GetFilePage();
uint16_t GetFileNumber();
void _print_log_formats(uint8_t num_types,
const struct LogStructure *structure,
AP_HAL::BetterStream *port);
void _print_log_formats(AP_HAL::BetterStream *port);
protected:
uint8_t df_manufacturer;

View File

@ -8,8 +8,9 @@
#define DF_NUM_PAGES 4096
// Public Methods //////////////////////////////////////////////////////////////
void DataFlash_Empty::Init(void)
void DataFlash_Empty::Init(const struct LogStructure *structure, uint8_t num_types)
{
DataFlash_Class::Init(structure, num_types);
df_PageSize = DF_PAGE_SIZE;
// reserve last page for config information
df_NumPages = DF_NUM_PAGES - 1;

View File

@ -31,7 +31,7 @@ private:
bool BlockRead(uint8_t BufferNum, uint16_t IntPageAdr, void *pBuffer, uint16_t size);
public:
void Init();
void Init(const struct LogStructure *structure, uint8_t num_types);
void ReadManufacturerID();
bool CardInserted();
};

View File

@ -46,8 +46,9 @@ DataFlash_File::DataFlash_File(const char *log_directory) :
// initialisation
void DataFlash_File::Init(void)
void DataFlash_File::Init(const struct LogStructure *structure, uint8_t num_types)
{
DataFlash_Class::Init(structure, num_types);
// create the log directory if need be
int ret;
struct stat st;
@ -360,8 +361,6 @@ uint16_t DataFlash_File::start_new_log(void)
*/
void DataFlash_File::LogReadProcess(uint16_t log_num,
uint16_t start_page, uint16_t end_page,
uint8_t num_types,
const struct LogStructure *structure,
void (*print_mode)(AP_HAL::BetterStream *port, uint8_t mode),
AP_HAL::BetterStream *port)
{
@ -414,7 +413,7 @@ void DataFlash_File::LogReadProcess(uint16_t log_num,
case 2:
log_step = 0;
_print_log_entry(data, num_types, structure, print_mode, port);
_print_log_entry(data, print_mode, port);
break;
}
if (_read_offset >= (end_page+1) * DATAFLASH_PAGE_SIZE) {

View File

@ -17,7 +17,7 @@ public:
DataFlash_File(const char *log_directory);
// initialisation
void Init(void);
void Init(const struct LogStructure *structure, uint8_t num_types);
bool CardInserted(void);
// erase handling
@ -36,8 +36,6 @@ public:
uint16_t start_new_log(void);
void LogReadProcess(uint16_t log_num,
uint16_t start_page, uint16_t end_page,
uint8_t num_types,
const struct LogStructure *structure,
void (*print_mode)(AP_HAL::BetterStream *port, uint8_t mode),
AP_HAL::BetterStream *port);
void DumpPageInfo(AP_HAL::BetterStream *port);

View File

@ -25,8 +25,9 @@ static int flash_fd;
static uint8_t buffer[2][DF_PAGE_SIZE];
// Public Methods //////////////////////////////////////////////////////////////
void DataFlash_SITL::Init(void)
void DataFlash_SITL::Init(const struct LogStructure *structure, uint8_t num_types)
{
DataFlash_Class::Init(structure, num_types);
if (flash_fd == 0) {
flash_fd = open("dataflash.bin", O_RDWR, 0777);
if (flash_fd == -1) {

View File

@ -43,7 +43,7 @@ private:
public:
DataFlash_SITL() {}
void Init();
void Init(const struct LogStructure *structure, uint8_t num_types);
void ReadManufacturerID();
bool CardInserted();
};

View File

@ -8,6 +8,14 @@
extern const AP_HAL::HAL& hal;
void DataFlash_Class::Init(const struct LogStructure *structure, uint8_t num_types)
{
_num_types = num_types;
_structures = structure;
}
// This function determines the number of whole or partial log files in the DataFlash
// Wholly overwritten files are (of course) lost.
uint16_t DataFlash_Block::get_num_logs(void)
@ -267,27 +275,25 @@ uint16_t DataFlash_Block::find_last_page_of_log(uint16_t log_number)
read and print a log entry using the format strings from the given structure
*/
void DataFlash_Class::_print_log_entry(uint8_t msg_type,
uint8_t num_types,
const struct LogStructure *structure,
void (*print_mode)(AP_HAL::BetterStream *port, uint8_t mode),
AP_HAL::BetterStream *port)
{
uint8_t i;
for (i=0; i<num_types; i++) {
if (msg_type == PGM_UINT8(&structure[i].msg_type)) {
for (i=0; i<_num_types; i++) {
if (msg_type == PGM_UINT8(&_structures[i].msg_type)) {
break;
}
}
if (i == num_types) {
if (i == _num_types) {
port->printf_P(PSTR("UNKN, %u\n"), (unsigned)msg_type);
return;
}
uint8_t msg_len = PGM_UINT8(&structure[i].msg_len) - 3;
uint8_t msg_len = PGM_UINT8(&_structures[i].msg_len) - 3;
uint8_t pkt[msg_len];
ReadBlock(pkt, msg_len);
port->printf_P(PSTR("%S, "), structure[i].name);
port->printf_P(PSTR("%S, "), _structures[i].name);
for (uint8_t ofs=0, fmt_ofs=0; ofs<msg_len; fmt_ofs++) {
char fmt = PGM_UINT8(&structure[i].format[fmt_ofs]);
char fmt = PGM_UINT8(&_structures[i].format[fmt_ofs]);
switch (fmt) {
case 'b': {
port->printf_P(PSTR("%d"), (int)pkt[ofs]);
@ -416,12 +422,10 @@ void DataFlash_Class::_print_log_entry(uint8_t msg_type,
using the same log formats as the current formats, but it is better
than falling back to old defaults in the GCS
*/
void DataFlash_Block::_print_log_formats(uint8_t num_types,
const struct LogStructure *structure,
AP_HAL::BetterStream *port)
void DataFlash_Block::_print_log_formats(AP_HAL::BetterStream *port)
{
for (uint8_t i=0; i<num_types; i++) {
const struct LogStructure *s = &structure[i];
for (uint8_t i=0; i<_num_types; i++) {
const struct LogStructure *s = &_structures[i];
port->printf_P(PSTR("FMT, %u, %u, %S, %S, %S\n"),
(unsigned)PGM_UINT8(&s->msg_type),
(unsigned)PGM_UINT8(&s->msg_len),
@ -434,8 +438,6 @@ void DataFlash_Block::_print_log_formats(uint8_t num_types,
*/
void DataFlash_Block::LogReadProcess(uint16_t log_num,
uint16_t start_page, uint16_t end_page,
uint8_t num_types,
const struct LogStructure *structure,
void (*print_mode)(AP_HAL::BetterStream *port, uint8_t mode),
AP_HAL::BetterStream *port)
{
@ -473,10 +475,10 @@ void DataFlash_Block::LogReadProcess(uint16_t log_num,
case 2:
log_step = 0;
if (first_entry && data != LOG_FORMAT_MSG) {
_print_log_formats(num_types, structure, port);
_print_log_formats(port);
}
first_entry = false;
_print_log_entry(data, num_types, structure, print_mode, port);
_print_log_entry(data, print_mode, port);
break;
}
uint16_t new_page = GetPage();
@ -554,17 +556,19 @@ void DataFlash_Block::ListAvailableLogs(AP_HAL::BetterStream *port)
// This function starts a new log file in the DataFlash, and writes
// the format of supported messages in the log, plus all parameters
uint16_t DataFlash_Class::StartNewLog(uint8_t num_types, const struct LogStructure *structures)
uint16_t DataFlash_Class::StartNewLog(void)
{
uint16_t ret;
ret = start_new_log();
#if 0
// write log formats so the log is self-describing
for (uint8_t i=0; i<num_types; i++) {
Log_Write_Format(&structures[i]);
for (uint8_t i=0; i<_num_types; i++) {
Log_Write_Format(&_structures[i]);
// avoid corrupting the APM1/APM2 dataflash by writing too fast
hal.scheduler->delay(10);
}
#endif
// and all current parameters
Log_Write_Parameters();
@ -574,22 +578,29 @@ uint16_t DataFlash_Class::StartNewLog(uint8_t num_types, const struct LogStructu
/*
write a structure format to the log
*/
void DataFlash_Class::Log_Write_Format(const struct LogStructure *s)
void DataFlash_Class::Log_Fill_Format(const struct LogStructure *s, struct log_Format &pkt)
{
struct log_Format pkt = {
LOG_PACKET_HEADER_INIT(LOG_FORMAT_MSG),
type : PGM_UINT8(&s->msg_type),
length : PGM_UINT8(&s->msg_len),
name : {},
format : {},
labels : {}
};
pkt.head1 = HEAD_BYTE1;
pkt.head2 = HEAD_BYTE2;
pkt.msgid = LOG_FORMAT_MSG;
pkt.type = PGM_UINT8(&s->msg_type);
pkt.length = PGM_UINT8(&s->msg_len);
strncpy_P(pkt.name, s->name, sizeof(pkt.name));
strncpy_P(pkt.format, s->format, sizeof(pkt.format));
strncpy_P(pkt.labels, s->labels, sizeof(pkt.labels));
}
/*
write a structure format to the log
*/
void DataFlash_Class::Log_Write_Format(const struct LogStructure *s)
{
struct log_Format pkt;
Log_Fill_Format(s, pkt);
WriteBlock(&pkt, sizeof(pkt));
}
/*
write a parameter to the log
*/