DataFlash: remove DataFlash_Block and DataFlash_SITL

This commit is contained in:
Peter Barker 2017-06-15 11:01:42 +10:00 committed by Francisco Ferreira
parent 6a01c65197
commit 244365767d
5 changed files with 0 additions and 1036 deletions

View File

@ -1,311 +0,0 @@
/*
* DataFlash.cpp - DataFlash log library generic code
*/
#include "DataFlash_Block.h"
#include <AP_HAL/AP_HAL.h>
extern AP_HAL::HAL& hal;
// the last page holds the log format in first 4 bytes. Please change
// this if (and only if!) the low level format changes
#define DF_LOGGING_FORMAT 0x28122013
uint32_t DataFlash_Block::bufferspace_available()
{
// because DataFlash_Block devices are ring buffers, we *always*
// have room...
return df_NumPages * df_PageSize;
}
// *** DATAFLASH PUBLIC FUNCTIONS ***
void DataFlash_Block::StartWrite(uint16_t PageAdr)
{
df_BufferIdx = 0;
df_BufferNum = 0;
df_PageAdr = PageAdr;
WaitReady();
}
void DataFlash_Block::FinishWrite(void)
{
// Write Buffer to flash, NO WAIT
BufferToPage(df_BufferNum, df_PageAdr, 0);
df_PageAdr++;
// If we reach the end of the memory, start from the beginning
if (df_PageAdr > df_NumPages)
df_PageAdr = 1;
// switch buffer
df_BufferNum ^= 1;
df_BufferIdx = 0;
}
bool DataFlash_Block::WritesOK() const
{
if (!DataFlash_Backend::WritesOK()) {
return false;
}
if (!CardInserted()) {
return false;
}
if (!log_write_started) {
return false;
}
return true;
}
bool DataFlash_Block::WritePrioritisedBlock(const void *pBuffer, uint16_t size,
bool is_critical)
{
// is_critical is ignored - we're a ring buffer and never run out
// of space. possibly if we do more complicated bandwidth
// limiting we can reservice bandwidth based on is_critical
if (!WritesOK()) {
return false;
}
if (! WriteBlockCheckStartupMessages()) {
return false;
}
while (size > 0) {
uint16_t n = df_PageSize - df_BufferIdx;
if (n > size) {
n = size;
}
if (df_BufferIdx == 0) {
// if we are at the start of a page we need to insert a
// page header
if (n > df_PageSize - sizeof(struct PageHeader)) {
n = df_PageSize - sizeof(struct PageHeader);
}
struct PageHeader ph = { df_FileNumber, df_FilePage };
BlockWrite(df_BufferNum, df_BufferIdx, &ph, sizeof(ph), pBuffer, n);
df_BufferIdx += n + sizeof(ph);
} else {
BlockWrite(df_BufferNum, df_BufferIdx, nullptr, 0, pBuffer, n);
df_BufferIdx += n;
}
size -= n;
pBuffer = (const void *)(n + (uintptr_t)pBuffer);
if (df_BufferIdx == df_PageSize) {
FinishWrite();
df_FilePage++;
}
}
return true;
}
// Get the last page written to
uint16_t DataFlash_Block::GetWritePage()
{
return df_PageAdr;
}
// Get the last page read
uint16_t DataFlash_Block::GetPage()
{
return df_Read_PageAdr;
}
void DataFlash_Block::StartRead(uint16_t PageAdr)
{
df_Read_BufferNum = 0;
df_Read_PageAdr = PageAdr;
// disable writing while reading
log_write_started = false;
WaitReady();
// copy flash page to buffer
PageToBuffer(df_Read_BufferNum, df_Read_PageAdr);
// We are starting a new page - read FileNumber and FilePage
struct PageHeader ph;
BlockRead(df_Read_BufferNum, 0, &ph, sizeof(ph));
df_FileNumber = ph.FileNumber;
df_FilePage = ph.FilePage;
df_Read_BufferIdx = sizeof(ph);
}
bool DataFlash_Block::ReadBlock(void *pBuffer, uint16_t size)
{
while (size > 0) {
uint16_t n = df_PageSize - df_Read_BufferIdx;
if (n > size) {
n = size;
}
WaitReady();
if (!BlockRead(df_Read_BufferNum, df_Read_BufferIdx, pBuffer, n)) {
return false;
}
size -= n;
pBuffer = (void *)(n + (uintptr_t)pBuffer);
df_Read_BufferIdx += n;
if (df_Read_BufferIdx == df_PageSize) {
df_Read_PageAdr++;
if (df_Read_PageAdr > df_NumPages) {
df_Read_PageAdr = 1;
}
PageToBuffer(df_Read_BufferNum, df_Read_PageAdr);
// We are starting a new page - read FileNumber and FilePage
struct PageHeader ph;
if (!BlockRead(df_Read_BufferNum, 0, &ph, sizeof(ph))) {
return false;
}
df_FileNumber = ph.FileNumber;
df_FilePage = ph.FilePage;
df_Read_BufferIdx = sizeof(ph);
}
}
return true;
}
void DataFlash_Block::SetFileNumber(uint16_t FileNumber)
{
df_FileNumber = FileNumber;
df_FilePage = 1;
}
uint16_t DataFlash_Block::GetFileNumber()
{
return df_FileNumber;
}
uint16_t DataFlash_Block::GetFilePage()
{
return df_FilePage;
}
void DataFlash_Block::EraseAll()
{
log_write_started = false;
for (uint16_t j = 1; j <= (df_NumPages+1)/8; j++) {
BlockErase(j);
if (j%6 == 0) {
hal.scheduler->delay(6);
}
}
// write the logging format in the last page
hal.scheduler->delay(100);
StartWrite(df_NumPages+1);
uint32_t version = DF_LOGGING_FORMAT;
log_write_started = true;
_writes_enabled = true;
WriteBlock(&version, sizeof(version));
log_write_started = false;
FinishWrite();
hal.scheduler->delay(100);
}
bool DataFlash_Block::NeedPrep(void)
{
return NeedErase();
}
void DataFlash_Block::Prep()
{
if (hal.util->get_soft_armed()) {
// do not want to do any filesystem operations while we are e.g. flying
return;
}
if (NeedErase()) {
EraseAll();
}
}
/*
* we need to erase if the logging format has changed
*/
bool DataFlash_Block::NeedErase(void)
{
uint32_t version = 0;
StartRead(df_NumPages+1);
if (!ReadBlock(&version, sizeof(version))) {
return true;
}
StartRead(1);
return version != DF_LOGGING_FORMAT;
}
/**
get raw data from a log
*/
int16_t DataFlash_Block::get_log_data_raw(uint16_t log_num, uint16_t page, uint32_t offset, uint16_t len, uint8_t *data)
{
uint16_t data_page_size = df_PageSize - sizeof(struct PageHeader);
if (offset >= data_page_size) {
page += offset / data_page_size;
offset = offset % data_page_size;
if (page > df_NumPages) {
// pages are one based, not zero
page = 1 + page - df_NumPages;
}
}
if (log_write_started || df_Read_PageAdr != page) {
StartRead(page);
}
df_Read_BufferIdx = offset + sizeof(struct PageHeader);
if (!ReadBlock(data, len)) {
return -1;
}
return (int16_t)len;
}
/**
get data from a log, accounting for adding FMT headers
*/
int16_t DataFlash_Block::get_log_data(uint16_t log_num, uint16_t page, uint32_t offset, uint16_t len, uint8_t *data)
{
if (offset == 0) {
uint8_t header[3];
get_log_data_raw(log_num, page, 0, 3, header);
adding_fmt_headers = (header[0] != HEAD_BYTE1 || header[1] != HEAD_BYTE2 || header[2] != LOG_FORMAT_MSG);
}
uint16_t ret = 0;
if (adding_fmt_headers) {
// the log doesn't start with a FMT message, we need to add
// them
const uint16_t fmt_header_size = num_types() * sizeof(struct log_Format);
while (offset < fmt_header_size && len > 0) {
struct log_Format pkt;
uint8_t t = offset / sizeof(pkt);
uint8_t ofs = offset % sizeof(pkt);
Log_Fill_Format(structure(t), pkt);
uint8_t n = sizeof(pkt) - ofs;
if (n > len) {
n = len;
}
memcpy(data, ofs + (uint8_t *)&pkt, n);
data += n;
offset += n;
len -= n;
ret += n;
}
offset -= fmt_header_size;
}
if (len > 0) {
ret += get_log_data_raw(log_num, page, offset, len, data);
}
return ret;
}

View File

@ -1,123 +0,0 @@
/*
DataFlash logging - block oriented variant
*/
#pragma once
#include "DataFlash_Backend.h"
#include <stdint.h>
class DataFlash_Block : public DataFlash_Backend
{
public:
DataFlash_Block(DataFlash_Class &front, DFMessageWriter_DFLogStart *writer) :
DataFlash_Backend(front, writer) { }
virtual bool CardInserted(void) const = 0;
// erase handling
void EraseAll();
bool NeedPrep(void);
void Prep();
/* Write a block of data at current offset */
bool WritePrioritisedBlock(const void *pBuffer, uint16_t size, bool is_critical);
// high level interface
uint16_t find_last_log() override;
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() override;
uint16_t start_new_log(void);
void LogReadProcess(const uint16_t list_entry,
uint16_t start_page, uint16_t end_page,
print_mode_fn print_mode,
AP_HAL::BetterStream *port);
void DumpPageInfo(AP_HAL::BetterStream *port);
void ShowDeviceInfo(AP_HAL::BetterStream *port);
void ListAvailableLogs(AP_HAL::BetterStream *port);
uint32_t bufferspace_available();
private:
struct PageHeader {
uint16_t FileNumber;
uint16_t FilePage;
};
// DataFlash Log variables...
uint8_t df_BufferNum;
uint8_t df_Read_BufferNum;
uint16_t df_BufferIdx;
uint16_t df_Read_BufferIdx;
uint16_t df_PageAdr;
uint16_t df_Read_PageAdr;
uint16_t df_FileNumber;
uint16_t df_FilePage;
// offset from adding FMT messages to log data
bool adding_fmt_headers;
/*
functions implemented by the board specific backends
*/
virtual void WaitReady() = 0;
virtual void BufferToPage (uint8_t BufferNum, uint16_t PageAdr, uint8_t wait) = 0;
virtual void PageToBuffer(uint8_t BufferNum, uint16_t PageAdr) = 0;
virtual void PageErase(uint16_t PageAdr) = 0;
virtual void BlockErase(uint16_t BlockAdr) = 0;
virtual void ChipErase() = 0;
// write size bytes of data to a page. The caller must ensure that
// the data fits within the page, otherwise it will wrap to the
// start of the page
virtual void BlockWrite(uint8_t BufferNum, uint16_t IntPageAdr,
const void *pHeader, uint8_t hdr_size,
const void *pBuffer, uint16_t size) = 0;
// read size bytes of data to a page. The caller must ensure that
// the data fits within the page, otherwise it will wrap to the
// start of the page
virtual bool BlockRead(uint8_t BufferNum, uint16_t IntPageAdr, void *pBuffer, uint16_t size) = 0;
// erase handling
bool NeedErase(void);
// internal high level functions
void StartRead(uint16_t PageAdr);
uint16_t find_last_page(void);
uint16_t find_last_page_of_log(uint16_t log_number);
bool check_wrapped(void);
uint16_t GetPage(void);
uint16_t GetWritePage(void);
void StartWrite(uint16_t PageAdr);
void FinishWrite(void);
// Read methods
bool ReadBlock(void *pBuffer, uint16_t size);
// file numbers
void SetFileNumber(uint16_t FileNumber);
uint16_t GetFilePage();
uint16_t GetFileNumber();
void _print_log_formats(AP_HAL::BetterStream *port);
protected:
uint8_t df_manufacturer;
uint16_t df_device;
// page handling
uint16_t df_PageSize;
uint16_t df_NumPages;
virtual void ReadManufacturerID() = 0;
bool WritesOK() const override;
};
#include "DataFlash_SITL.h"

View File

@ -1,162 +0,0 @@
/*
hacked up DataFlash library for Desktop support
*/
#include "DataFlash_SITL.h"
#include <AP_HAL/AP_HAL.h>
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL
#include <unistd.h>
#include <stdlib.h>
#include <sys/types.h>
#include <sys/stat.h>
#include <fcntl.h>
#include <stdint.h>
#include <assert.h>
#pragma GCC diagnostic ignored "-Wunused-result"
#define DF_PAGE_SIZE 512
#define DF_NUM_PAGES 16384
extern const AP_HAL::HAL& hal;
static int flash_fd;
static uint8_t buffer[2][DF_PAGE_SIZE];
// Public Methods //////////////////////////////////////////////////////////////
void DataFlash_SITL::Init()
{
DataFlash_Backend::Init();
if (flash_fd == 0) {
flash_fd = open("dataflash.bin", O_RDWR|O_CLOEXEC, 0777);
if (flash_fd == -1) {
uint8_t *fill;
fill = (uint8_t *)malloc(DF_PAGE_SIZE*DF_NUM_PAGES);
flash_fd = open("dataflash.bin", O_RDWR | O_CREAT | O_CLOEXEC, 0777);
memset(fill, 0xFF, DF_PAGE_SIZE*DF_NUM_PAGES);
write(flash_fd, fill, DF_PAGE_SIZE*DF_NUM_PAGES);
free(fill);
}
ftruncate(flash_fd, DF_PAGE_SIZE*DF_NUM_PAGES);
}
df_PageSize = DF_PAGE_SIZE;
// reserve last page for config information
df_NumPages = DF_NUM_PAGES - 1;
}
// This function is mainly to test the device
void DataFlash_SITL::ReadManufacturerID()
{
df_manufacturer = 1;
df_device = 0x0203;
}
bool DataFlash_SITL::CardInserted(void) const
{
return true;
}
// Read the status register
uint8_t DataFlash_SITL::ReadStatusReg()
{
return 0;
}
// Read the status of the DataFlash
inline
uint8_t DataFlash_SITL::ReadStatus()
{
return 1;
}
inline
uint16_t DataFlash_SITL::PageSize()
{
return df_PageSize;
}
// Wait until DataFlash is in ready state...
void DataFlash_SITL::WaitReady()
{
while(!ReadStatus());
}
void DataFlash_SITL::PageToBuffer(unsigned char BufferNum, uint16_t PageAdr)
{
assert(PageAdr>=1);
pread(flash_fd, buffer[BufferNum], DF_PAGE_SIZE, (PageAdr-1)*DF_PAGE_SIZE);
}
void DataFlash_SITL::BufferToPage (unsigned char BufferNum, uint16_t PageAdr, unsigned char wait)
{
assert(PageAdr>=1);
pwrite(flash_fd, buffer[BufferNum], DF_PAGE_SIZE, (PageAdr-1)*(uint32_t)DF_PAGE_SIZE);
}
void DataFlash_SITL::BufferWrite (unsigned char BufferNum, uint16_t IntPageAdr, unsigned char Data)
{
buffer[BufferNum][IntPageAdr] = (uint8_t)Data;
}
void DataFlash_SITL::BlockWrite(uint8_t BufferNum, uint16_t IntPageAdr,
const void *pHeader, uint8_t hdr_size,
const void *pBuffer, uint16_t size)
{
if (!_writes_enabled) {
return;
}
if (hdr_size) {
memcpy(&buffer[BufferNum][IntPageAdr],
pHeader,
hdr_size);
}
memcpy(&buffer[BufferNum][IntPageAdr+hdr_size],
pBuffer,
size);
}
// read size bytes of data to a page. The caller must ensure that
// the data fits within the page, otherwise it will wrap to the
// start of the page
bool DataFlash_SITL::BlockRead(uint8_t BufferNum, uint16_t IntPageAdr, void *pBuffer, uint16_t size)
{
memcpy(pBuffer, &buffer[BufferNum][IntPageAdr], size);
return true;
}
// *** END OF INTERNAL FUNCTIONS ***
void DataFlash_SITL::PageErase (uint16_t PageAdr)
{
uint8_t fill[DF_PAGE_SIZE];
memset(fill, 0xFF, sizeof(fill));
assert(PageAdr>=1);
pwrite(flash_fd, fill, DF_PAGE_SIZE, (PageAdr-1)*DF_PAGE_SIZE);
}
void DataFlash_SITL::BlockErase (uint16_t BlockAdr)
{
uint8_t fill[DF_PAGE_SIZE*8];
memset(fill, 0xFF, sizeof(fill));
assert(BlockAdr>=1);
pwrite(flash_fd, fill, DF_PAGE_SIZE*8, (BlockAdr-1)*DF_PAGE_SIZE*8);
}
void DataFlash_SITL::ChipErase()
{
for (int i=0; i<DF_NUM_PAGES; i++) {
PageErase(i);
hal.scheduler->delay(1);
}
}
#endif

View File

@ -1,48 +0,0 @@
/* ************************************************************ */
/* DataFlash_SITL Log library */
/* ************************************************************ */
#pragma once
#include <AP_HAL/AP_HAL.h>
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL
#include "DataFlash_Block.h"
class DataFlash_SITL : public DataFlash_Block
{
private:
//Methods
void BufferWrite (uint8_t BufferNum, uint16_t IntPageAdr, uint8_t Data);
void BufferToPage (uint8_t BufferNum, uint16_t PageAdr, uint8_t wait);
void PageToBuffer(uint8_t BufferNum, uint16_t PageAdr);
void WaitReady();
uint8_t ReadStatusReg();
uint8_t ReadStatus();
uint16_t PageSize();
void PageErase (uint16_t PageAdr);
void BlockErase (uint16_t BlockAdr);
void ChipErase();
// write size bytes of data to a page. The caller must ensure that
// the data fits within the page, otherwise it will wrap to the
// start of the page
// If pHeader is not nullptr then write the header bytes before the data
void BlockWrite(uint8_t BufferNum, uint16_t IntPageAdr,
const void *pHeader, uint8_t hdr_size,
const void *pBuffer, uint16_t size);
// read size bytes of data to a page. The caller must ensure that
// the data fits within the page, otherwise it will wrap to the
// start of the page
bool BlockRead(uint8_t BufferNum, uint16_t IntPageAdr, void *pBuffer, uint16_t size);
public:
DataFlash_SITL(DataFlash_Class &front, DFMessageWriter_DFLogStart *writer) :
DataFlash_Block(front, writer) { }
void Init() override;
void ReadManufacturerID();
bool CardInserted() const;
};
#endif // CONFIG_HAL_BOARD == HAL_BOARD_SITL

View File

@ -12,266 +12,12 @@
#include <AC_AttitudeControl/AC_PosControl.h>
#include "DataFlash.h"
#include "DataFlash_SITL.h"
#include "DataFlash_Block.h"
#include "DataFlash_File.h"
#include "DataFlash_MAVLink.h"
#include "DFMessageWriter.h"
extern const AP_HAL::HAL& hal;
// 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)
{
uint16_t lastpage;
uint16_t last;
uint16_t first;
if (find_last_page() == 1) {
return 0;
}
StartRead(1);
if (GetFileNumber() == 0xFFFF) {
return 0;
}
lastpage = find_last_page();
StartRead(lastpage);
last = GetFileNumber();
StartRead(lastpage + 2);
first = GetFileNumber();
if(first > last) {
StartRead(1);
first = GetFileNumber();
}
if (last == first) {
return 1;
}
return (last - first + 1);
}
// This function starts a new log file in the DataFlash
uint16_t DataFlash_Block::start_new_log(void)
{
_startup_messagewriter->reset();
uint16_t last_page = find_last_page();
StartRead(last_page);
//Serial.printf("last page: "); Serial.printf("%u\n", last_page);
//Serial.printf("file #: "); Serial.printf("%u\n", GetFileNumber());
//Serial.printf("file page: "); Serial.printf("%u\n", GetFilePage());
if(find_last_log() == 0 || GetFileNumber() == 0xFFFF) {
SetFileNumber(1);
StartWrite(1);
//Serial.printf("start log from 0\n");
log_write_started = true;
return 1;
}
uint16_t new_log_num;
// Check for log of length 1 page and suppress
if(GetFilePage() <= 1) {
new_log_num = GetFileNumber();
// Last log too short, reuse its number
// and overwrite it
SetFileNumber(new_log_num);
StartWrite(last_page);
} else {
new_log_num = GetFileNumber()+1;
if (last_page == 0xFFFF) {
last_page=0;
}
SetFileNumber(new_log_num);
StartWrite(last_page + 1);
}
log_write_started = true;
return new_log_num;
}
// This function finds the first and last pages of a log file
// The first page may be greater than the last page if the DataFlash has been filled and partially overwritten.
void DataFlash_Block::get_log_boundaries(uint16_t log_num, uint16_t & start_page, uint16_t & end_page)
{
uint16_t num = get_num_logs();
uint16_t look;
if (df_BufferIdx != 0) {
FinishWrite();
hal.scheduler->delay(100);
}
if(num == 1)
{
StartRead(df_NumPages);
if (GetFileNumber() == 0xFFFF)
{
start_page = 1;
end_page = find_last_page_of_log((uint16_t)log_num);
} else {
end_page = find_last_page_of_log((uint16_t)log_num);
start_page = end_page + 1;
}
} else {
if(log_num==1) {
StartRead(df_NumPages);
if(GetFileNumber() == 0xFFFF) {
start_page = 1;
} else {
start_page = find_last_page() + 1;
}
} else {
if(log_num == find_last_log() - num + 1) {
start_page = find_last_page() + 1;
} else {
look = log_num-1;
do {
start_page = find_last_page_of_log(look) + 1;
look--;
} while (start_page <= 0 && look >=1);
}
}
}
if (start_page == df_NumPages+1 || start_page == 0) {
start_page = 1;
}
end_page = find_last_page_of_log(log_num);
if (end_page == 0) {
end_page = start_page;
}
}
// find log size and time
void DataFlash_Block::get_log_info(uint16_t log_num, uint32_t &size, uint32_t &time_utc)
{
uint16_t start, end;
get_log_boundaries(log_num, start, end);
if (end >= start) {
size = (end + 1 - start) * (uint32_t)df_PageSize;
} else {
size = (df_NumPages + end - start) * (uint32_t)df_PageSize;
}
time_utc = 0;
}
bool DataFlash_Block::check_wrapped(void)
{
StartRead(df_NumPages);
if(GetFileNumber() == 0xFFFF)
return 0;
else
return 1;
}
// This function finds the last log number
uint16_t DataFlash_Block::find_last_log(void)
{
uint16_t last_page = find_last_page();
StartRead(last_page);
return GetFileNumber();
}
// This function finds the last page of the last file
uint16_t DataFlash_Block::find_last_page(void)
{
uint16_t look;
uint16_t bottom = 1;
uint16_t top = df_NumPages;
uint32_t look_hash;
uint32_t bottom_hash;
uint32_t top_hash;
StartRead(bottom);
bottom_hash = ((int32_t)GetFileNumber()<<16) | GetFilePage();
while(top-bottom > 1) {
look = (top+bottom)/2;
StartRead(look);
look_hash = (int32_t)GetFileNumber()<<16 | GetFilePage();
if (look_hash >= 0xFFFF0000) look_hash = 0;
if(look_hash < bottom_hash) {
// move down
top = look;
} else {
// move up
bottom = look;
bottom_hash = look_hash;
}
}
StartRead(top);
top_hash = ((int32_t)GetFileNumber()<<16) | GetFilePage();
if (top_hash >= 0xFFFF0000) {
top_hash = 0;
}
if (top_hash > bottom_hash) {
return top;
}
return bottom;
}
// This function finds the last page of a particular log file
uint16_t DataFlash_Block::find_last_page_of_log(uint16_t log_number)
{
uint16_t look;
uint16_t bottom;
uint16_t top;
uint32_t look_hash;
uint32_t check_hash;
if(check_wrapped())
{
StartRead(1);
bottom = GetFileNumber();
if (bottom > log_number)
{
bottom = find_last_page();
top = df_NumPages;
} else {
bottom = 1;
top = find_last_page();
}
} else {
bottom = 1;
top = find_last_page();
}
check_hash = (int32_t)log_number<<16 | 0xFFFF;
while(top-bottom > 1)
{
look = (top+bottom)/2;
StartRead(look);
look_hash = (int32_t)GetFileNumber()<<16 | GetFilePage();
if (look_hash >= 0xFFFF0000) look_hash = 0;
if(look_hash > check_hash) {
// move down
top = look;
} else {
// move up
bottom = look;
}
}
StartRead(top);
if (GetFileNumber() == log_number) return top;
StartRead(bottom);
if (GetFileNumber() == log_number) return bottom;
return 0xFFFF;
}
/*
read and print a log entry using the format strings from the given structure
@ -444,144 +190,6 @@ void DataFlash_Backend::_print_log_entry(uint8_t msg_type,
port->printf("\n");
}
/*
print FMT specifiers for log dumps where we have wrapped in the
dataflash and so have no formats. This assumes the log being dumped
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(AP_HAL::BetterStream *port)
{
for (uint8_t i=0; i<num_types(); i++) {
const struct LogStructure *s = structure(i);
port->printf("FMT, %u, %u, %s, %s, %s\n", s->msg_type, s->msg_len,
s->name, s->format, s->labels);
}
}
/*
Read the log and print it on port
*/
void DataFlash_Block::LogReadProcess(uint16_t log_num,
uint16_t start_page, uint16_t end_page,
print_mode_fn print_mode,
AP_HAL::BetterStream *port)
{
uint8_t log_step = 0;
uint16_t page = start_page;
bool first_entry = true;
if (df_BufferIdx != 0) {
FinishWrite();
hal.scheduler->delay(100);
}
StartRead(start_page);
while (true) {
uint8_t data;
if (!ReadBlock(&data, 1)) {
break;
}
// 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;
if (first_entry && data != LOG_FORMAT_MSG) {
_print_log_formats(port);
}
first_entry = false;
_print_log_entry(data, print_mode, port);
break;
}
uint16_t new_page = GetPage();
if (new_page != page) {
if (new_page == end_page+1 || new_page == start_page) {
return;
}
page = new_page;
}
}
}
/*
dump header information from all log pages
*/
void DataFlash_Block::DumpPageInfo(AP_HAL::BetterStream *port)
{
for (uint16_t count=1; count<=df_NumPages; count++) {
StartRead(count);
port->printf("DF page, log file #, log page: %u,\t", (unsigned)count);
port->printf("%u,\t", (unsigned)GetFileNumber());
port->printf("%u\n", (unsigned)GetFilePage());
}
}
/*
show information about the device
*/
void DataFlash_Block::ShowDeviceInfo(AP_HAL::BetterStream *port)
{
if (!CardInserted()) {
port->printf("No dataflash inserted\n");
return;
}
ReadManufacturerID();
port->printf("Manufacturer: 0x%02x Device: 0x%04x\n",
(unsigned)df_manufacturer,
(unsigned)df_device);
port->printf("NumPages: %u PageSize: %u\n",
(unsigned)df_NumPages+1,
(unsigned)df_PageSize);
}
/*
list available log numbers
*/
void DataFlash_Block::ListAvailableLogs(AP_HAL::BetterStream *port)
{
uint16_t num_logs = get_num_logs();
int16_t last_log_num = find_last_log();
uint16_t log_start = 0;
uint16_t log_end = 0;
if (num_logs == 0) {
port->printf("\nNo logs\n\n");
return;
}
port->printf("\n%u logs\n", (unsigned)num_logs);
for (uint16_t i=num_logs; i>=1; i--) {
uint16_t last_log_start = log_start, last_log_end = log_end;
uint16_t temp = last_log_num - i + 1;
get_log_boundaries(temp, log_start, log_end);
port->printf("Log %u, start %u, end %u\n",
(unsigned)temp,
(unsigned)log_start,
(unsigned)log_end);
if (last_log_start == log_start && last_log_end == log_end) {
// we are printing bogus logs
break;
}
}
port->printf("\n");
}
/*
write a structure format to the log - should be in frontend
*/