mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-09 09:28:31 -04:00
DataFlash: simplify code now that copter is converted
no longer need as many public functions
This commit is contained in:
parent
a0708460a4
commit
62f190ed15
@ -34,19 +34,10 @@ public:
|
|||||||
/* 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;
|
virtual void WriteBlock(const void *pBuffer, uint16_t size) = 0;
|
||||||
|
|
||||||
/*
|
|
||||||
read a packet. The header byte have already been read.
|
|
||||||
*/
|
|
||||||
virtual void ReadPacket(void *pkt, uint16_t size) = 0;
|
|
||||||
|
|
||||||
// high level interface
|
// high level interface
|
||||||
virtual uint16_t find_last_log(void) = 0;
|
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_boundaries(uint16_t log_num, uint16_t & start_page, uint16_t & end_page) = 0;
|
||||||
virtual uint16_t get_num_logs(void) = 0;
|
virtual uint16_t get_num_logs(void) = 0;
|
||||||
virtual uint16_t start_new_log(void) = 0;
|
|
||||||
void log_read_process(uint16_t log_num,
|
|
||||||
uint16_t start_page, uint16_t end_page,
|
|
||||||
void (*callback)(uint8_t msgid));
|
|
||||||
virtual void LogReadProcess(uint16_t log_num,
|
virtual void LogReadProcess(uint16_t log_num,
|
||||||
uint16_t start_page, uint16_t end_page,
|
uint16_t start_page, uint16_t end_page,
|
||||||
uint8_t num_types,
|
uint8_t num_types,
|
||||||
@ -90,6 +81,13 @@ protected:
|
|||||||
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);
|
||||||
void Log_Write_Parameters(void);
|
void Log_Write_Parameters(void);
|
||||||
|
virtual uint16_t start_new_log(void) = 0;
|
||||||
|
|
||||||
|
/*
|
||||||
|
read a block
|
||||||
|
*/
|
||||||
|
virtual void ReadBlock(void *pkt, uint16_t size) = 0;
|
||||||
|
|
||||||
};
|
};
|
||||||
|
|
||||||
/*
|
/*
|
||||||
|
@ -131,11 +131,6 @@ void DataFlash_Block::ReadBlock(void *pBuffer, uint16_t size)
|
|||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
void DataFlash_Block::ReadPacket(void *pkt, uint16_t size)
|
|
||||||
{
|
|
||||||
ReadBlock((void *)(sizeof(struct log_Header)+(uintptr_t)pkt), size - sizeof(struct log_Header));
|
|
||||||
}
|
|
||||||
|
|
||||||
void DataFlash_Block::SetFileNumber(uint16_t FileNumber)
|
void DataFlash_Block::SetFileNumber(uint16_t FileNumber)
|
||||||
{
|
{
|
||||||
df_FileNumber = FileNumber;
|
df_FileNumber = FileNumber;
|
||||||
|
@ -30,19 +30,11 @@ public:
|
|||||||
/* Write a block of data at current offset */
|
/* Write a block of data at current offset */
|
||||||
void WriteBlock(const void *pBuffer, uint16_t size);
|
void WriteBlock(const void *pBuffer, uint16_t size);
|
||||||
|
|
||||||
/*
|
|
||||||
read a packet. The header byte have already been read.
|
|
||||||
*/
|
|
||||||
void ReadPacket(void *pkt, uint16_t size);
|
|
||||||
|
|
||||||
// high level interface
|
// high level interface
|
||||||
uint16_t find_last_log(void);
|
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_boundaries(uint16_t log_num, uint16_t & start_page, uint16_t & end_page);
|
||||||
uint16_t get_num_logs(void);
|
uint16_t get_num_logs(void);
|
||||||
uint16_t start_new_log(void);
|
uint16_t start_new_log(void);
|
||||||
void log_read_process(uint16_t log_num,
|
|
||||||
uint16_t start_page, uint16_t end_page,
|
|
||||||
void (*callback)(uint8_t msgid));
|
|
||||||
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,
|
||||||
uint8_t num_types,
|
uint8_t num_types,
|
||||||
|
@ -172,16 +172,12 @@ void DataFlash_File::WriteBlock(const void *pBuffer, uint16_t size)
|
|||||||
/*
|
/*
|
||||||
read a packet. The header bytes have already been read.
|
read a packet. The header bytes have already been read.
|
||||||
*/
|
*/
|
||||||
void DataFlash_File::ReadPacket(void *pkt, uint16_t size)
|
void DataFlash_File::ReadBlock(void *pkt, uint16_t size)
|
||||||
{
|
{
|
||||||
if (_read_fd == -1 || !_initialised || size <= 3) {
|
if (_read_fd == -1 || !_initialised || size <= 3) {
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
|
|
||||||
// we don't read the 3 header bytes. That happens in log_read_process()
|
|
||||||
pkt = (void *)(3+(char *)pkt);
|
|
||||||
size -= 3;
|
|
||||||
|
|
||||||
memset(pkt, 0, size);
|
memset(pkt, 0, size);
|
||||||
::read(_read_fd, pkt, size);
|
::read(_read_fd, pkt, size);
|
||||||
_read_offset += size;
|
_read_offset += size;
|
||||||
@ -362,72 +358,6 @@ void DataFlash_File::LogReadProcess(uint16_t log_num,
|
|||||||
_read_fd = -1;
|
_read_fd = -1;
|
||||||
}
|
}
|
||||||
|
|
||||||
/*
|
|
||||||
start processing a log, called by CLI to display logs
|
|
||||||
*/
|
|
||||||
void DataFlash_File::log_read_process(uint16_t log_num,
|
|
||||||
uint16_t start_page, uint16_t end_page,
|
|
||||||
void (*callback)(uint8_t msgid))
|
|
||||||
{
|
|
||||||
uint8_t log_step = 0;
|
|
||||||
if (!_initialised) {
|
|
||||||
return;
|
|
||||||
}
|
|
||||||
if (_read_fd != -1) {
|
|
||||||
::close(_read_fd);
|
|
||||||
}
|
|
||||||
char *fname = _log_file_name(log_num);
|
|
||||||
if (fname == NULL) {
|
|
||||||
return;
|
|
||||||
}
|
|
||||||
_read_fd = ::open(fname, O_RDONLY);
|
|
||||||
free(fname);
|
|
||||||
if (_read_fd == -1) {
|
|
||||||
return;
|
|
||||||
}
|
|
||||||
_read_offset = 0;
|
|
||||||
if (start_page != 0) {
|
|
||||||
::lseek(_read_fd, start_page * DATAFLASH_PAGE_SIZE, SEEK_SET);
|
|
||||||
}
|
|
||||||
|
|
||||||
while (true) {
|
|
||||||
uint8_t data;
|
|
||||||
if (::read(_read_fd, &data, 1) != 1) {
|
|
||||||
// reached end of file
|
|
||||||
break;
|
|
||||||
}
|
|
||||||
_read_offset++;
|
|
||||||
|
|
||||||
// This is a state machine to read the packets
|
|
||||||
switch(log_step) {
|
|
||||||
case 0:
|
|
||||||
if (data == HEAD_BYTE1) {
|
|
||||||
log_step++;
|
|
||||||
}
|
|
||||||
break;
|
|
||||||
|
|
||||||
case 1:
|
|
||||||
if (data == HEAD_BYTE2) {
|
|
||||||
log_step++;
|
|
||||||
} else {
|
|
||||||
log_step = 0;
|
|
||||||
}
|
|
||||||
break;
|
|
||||||
|
|
||||||
case 2:
|
|
||||||
log_step = 0;
|
|
||||||
callback(data);
|
|
||||||
break;
|
|
||||||
}
|
|
||||||
if (_read_offset >= (end_page+1) * DATAFLASH_PAGE_SIZE) {
|
|
||||||
break;
|
|
||||||
}
|
|
||||||
}
|
|
||||||
|
|
||||||
::close(_read_fd);
|
|
||||||
_read_fd = -1;
|
|
||||||
}
|
|
||||||
|
|
||||||
/*
|
/*
|
||||||
this is a lot less verbose than the block interface. Dumping 2Gbyte
|
this is a lot less verbose than the block interface. Dumping 2Gbyte
|
||||||
of logs a page at a time isn't so useful. Just pull the SD card out
|
of logs a page at a time isn't so useful. Just pull the SD card out
|
||||||
|
@ -27,19 +27,11 @@ public:
|
|||||||
/* Write a block of data at current offset */
|
/* Write a block of data at current offset */
|
||||||
void WriteBlock(const void *pBuffer, uint16_t size);
|
void WriteBlock(const void *pBuffer, uint16_t size);
|
||||||
|
|
||||||
/*
|
|
||||||
read a packet. The header byte have already been read.
|
|
||||||
*/
|
|
||||||
void ReadPacket(void *pkt, uint16_t size);
|
|
||||||
|
|
||||||
// high level interface
|
// high level interface
|
||||||
uint16_t find_last_log(void);
|
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_boundaries(uint16_t log_num, uint16_t & start_page, uint16_t & end_page);
|
||||||
uint16_t get_num_logs(void);
|
uint16_t get_num_logs(void);
|
||||||
uint16_t start_new_log(void);
|
uint16_t start_new_log(void);
|
||||||
void log_read_process(uint16_t log_num,
|
|
||||||
uint16_t start_page, uint16_t end_page,
|
|
||||||
void (*callback)(uint8_t msgid));
|
|
||||||
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,
|
||||||
uint8_t num_types,
|
uint8_t num_types,
|
||||||
@ -56,6 +48,11 @@ private:
|
|||||||
static volatile bool _initialised;
|
static volatile bool _initialised;
|
||||||
const char *_log_directory;
|
const char *_log_directory;
|
||||||
|
|
||||||
|
/*
|
||||||
|
read a block
|
||||||
|
*/
|
||||||
|
void ReadBlock(void *pkt, uint16_t size);
|
||||||
|
|
||||||
// write buffer
|
// write buffer
|
||||||
static uint8_t *_writebuf;
|
static uint8_t *_writebuf;
|
||||||
static const uint16_t _writebuf_size;
|
static const uint16_t _writebuf_size;
|
||||||
|
@ -282,11 +282,11 @@ void DataFlash_Class::_print_log_entry(uint8_t msg_type,
|
|||||||
port->printf_P(PSTR("UNKN, %u\n"), (unsigned)msg_type);
|
port->printf_P(PSTR("UNKN, %u\n"), (unsigned)msg_type);
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
uint8_t msg_len = PGM_UINT8(&structure[i].msg_len);
|
uint8_t msg_len = PGM_UINT8(&structure[i].msg_len) - 3;
|
||||||
uint8_t pkt[msg_len];
|
uint8_t pkt[msg_len];
|
||||||
ReadPacket(pkt, msg_len);
|
ReadBlock(pkt, msg_len);
|
||||||
port->printf_P(PSTR("%S, "), structure[i].name);
|
port->printf_P(PSTR("%S, "), structure[i].name);
|
||||||
for (uint8_t ofs=3, fmt_ofs=0; ofs<msg_len; fmt_ofs++) {
|
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(&structure[i].format[fmt_ofs]);
|
||||||
switch (fmt) {
|
switch (fmt) {
|
||||||
case 'b': {
|
case 'b': {
|
||||||
@ -451,59 +451,6 @@ void DataFlash_Block::LogReadProcess(uint16_t log_num,
|
|||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
/*
|
|
||||||
Read the DataFlash log memory
|
|
||||||
This is obsolete and will be removed when plane and copter are
|
|
||||||
converted to LogReadProcess()
|
|
||||||
*/
|
|
||||||
void DataFlash_Block::log_read_process(uint16_t log_num,
|
|
||||||
uint16_t start_page, uint16_t end_page,
|
|
||||||
void (*callback)(uint8_t msgid))
|
|
||||||
{
|
|
||||||
uint8_t log_step = 0;
|
|
||||||
uint16_t page = start_page;
|
|
||||||
|
|
||||||
if (df_BufferIdx != 0) {
|
|
||||||
FinishWrite();
|
|
||||||
}
|
|
||||||
|
|
||||||
StartRead(start_page);
|
|
||||||
|
|
||||||
while (true) {
|
|
||||||
uint8_t data;
|
|
||||||
ReadBlock(&data, 1);
|
|
||||||
|
|
||||||
// This is a state machine to read the packets
|
|
||||||
switch(log_step) {
|
|
||||||
case 0:
|
|
||||||
if (data == HEAD_BYTE1) {
|
|
||||||
log_step++;
|
|
||||||
}
|
|
||||||
break;
|
|
||||||
|
|
||||||
case 1:
|
|
||||||
if (data == HEAD_BYTE2) {
|
|
||||||
log_step++;
|
|
||||||
} else {
|
|
||||||
log_step = 0;
|
|
||||||
}
|
|
||||||
break;
|
|
||||||
|
|
||||||
case 2:
|
|
||||||
log_step = 0;
|
|
||||||
callback(data);
|
|
||||||
break;
|
|
||||||
}
|
|
||||||
uint16_t new_page = GetPage();
|
|
||||||
if (new_page != page) {
|
|
||||||
if (new_page == end_page || new_page == start_page) {
|
|
||||||
return;
|
|
||||||
}
|
|
||||||
page = new_page;
|
|
||||||
}
|
|
||||||
}
|
|
||||||
}
|
|
||||||
|
|
||||||
/*
|
/*
|
||||||
dump header information from all log pages
|
dump header information from all log pages
|
||||||
*/
|
*/
|
||||||
|
Loading…
Reference in New Issue
Block a user