DataFlash: remove vestiges of CLI functions

This commit is contained in:
Peter Barker 2017-08-12 15:42:08 +10:00 committed by Randy Mackay
parent d777da970b
commit 8027883734
13 changed files with 3 additions and 629 deletions

View File

@ -522,38 +522,6 @@ uint16_t DataFlash_Class::get_num_logs(void) {
return backends[0]->get_num_logs();
}
void DataFlash_Class::LogReadProcess(uint16_t log_num,
uint16_t start_page, uint16_t end_page,
print_mode_fn printMode,
AP_HAL::BetterStream *port) {
if (_next_backend == 0) {
// how were we called?!
return;
}
backends[0]->LogReadProcess(log_num, start_page, end_page, printMode, port);
}
void DataFlash_Class::DumpPageInfo(AP_HAL::BetterStream *port) {
if (_next_backend == 0) {
// how were we called?!
return;
}
backends[0]->DumpPageInfo(port);
}
void DataFlash_Class::ShowDeviceInfo(AP_HAL::BetterStream *port) {
if (_next_backend == 0) {
// how were we called?!
return;
}
backends[0]->ShowDeviceInfo(port);
}
void DataFlash_Class::ListAvailableLogs(AP_HAL::BetterStream *port) {
if (_next_backend == 0) {
// how were we called?!
return;
}
backends[0]->ListAvailableLogs(port);
}
/* we're started if any of the backends are started */
bool DataFlash_Class::logging_started(void) {
for (uint8_t i=0; i< _next_backend; i++) {

View File

@ -50,7 +50,6 @@ class DataFlash_Class
friend class DataFlash_Backend; // for _num_types
public:
FUNCTOR_TYPEDEF(print_mode_fn, void, AP_HAL::BetterStream*, uint8_t);
FUNCTOR_TYPEDEF(vehicle_startup_message_Log_Writer, void);
DataFlash_Class(const char *firmware_string, const AP_Int32 &log_bitmask);
@ -83,13 +82,6 @@ public:
uint16_t find_last_log() const;
void get_log_boundaries(uint16_t log_num, uint16_t & start_page, uint16_t & end_page);
uint16_t get_num_logs(void);
void LogReadProcess(uint16_t log_num,
uint16_t start_page, uint16_t end_page,
print_mode_fn printMode,
AP_HAL::BetterStream *port);
void DumpPageInfo(AP_HAL::BetterStream *port);
void ShowDeviceInfo(AP_HAL::BetterStream *port);
void ListAvailableLogs(AP_HAL::BetterStream *port);
void setVehicle_Startup_Log_Writer(vehicle_startup_message_Log_Writer writer);

View File

@ -8,7 +8,6 @@ class DataFlash_Backend
{
public:
FUNCTOR_TYPEDEF(print_mode_fn, void, AP_HAL::BetterStream*, uint8_t);
FUNCTOR_TYPEDEF(vehicle_startup_message_Log_Writer, void);
DataFlash_Backend(DataFlash_Class &front,
@ -43,13 +42,6 @@ public:
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() = 0;
virtual void LogReadProcess(const uint16_t list_entry,
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;
virtual bool logging_started(void) const = 0;
@ -141,13 +133,6 @@ protected:
virtual void periodic_1Hz(const uint32_t now);
virtual void periodic_fullrate(const uint32_t now);
/*
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);
bool ShouldLog(bool is_critical);
virtual bool WritesOK() const = 0;
virtual bool StartNewLogOK() const;

View File

@ -978,153 +978,6 @@ uint16_t DataFlash_File::start_new_log(void)
return log_num;
}
/*
Read the log and print it on port
*/
void DataFlash_File::LogReadProcess(const uint16_t list_entry,
uint16_t start_page, uint16_t end_page,
print_mode_fn print_mode,
AP_HAL::BetterStream *port)
{
uint8_t log_step = 0;
if (!_initialised || _open_error) {
return;
}
const uint16_t log_num = _log_num_from_list_entry(list_entry);
if (log_num == 0) {
return;
}
if (_read_fd != -1) {
::close(_read_fd);
_read_fd = -1;
}
char *fname = _log_file_name(log_num);
if (fname == nullptr) {
return;
}
_read_fd = ::open(fname, O_RDONLY|O_CLOEXEC);
free(fname);
if (_read_fd == -1) {
return;
}
_read_fd_log_num = log_num;
_read_offset = 0;
if (start_page != 0) {
if (::lseek(_read_fd, start_page * DATAFLASH_PAGE_SIZE, SEEK_SET) == (off_t)-1) {
close(_read_fd);
_read_fd = -1;
return;
}
_read_offset = start_page * DATAFLASH_PAGE_SIZE;
}
uint8_t log_counter = 0;
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;
_print_log_entry(data, print_mode, port);
log_counter++;
// work around NuttX bug (see above for explanation)
if (log_counter == 10) {
log_counter = 0;
if (::lseek(_read_fd, 0, SEEK_CUR) == (off_t)-1) {
close(_read_fd);
_read_fd = -1;
return;
}
}
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
of logs a page at a time isn't so useful. Just pull the SD card out
and look at it on your PC
*/
void DataFlash_File::DumpPageInfo(AP_HAL::BetterStream *port)
{
port->printf("DataFlash: num_logs=%u\n",
(unsigned)get_num_logs());
}
void DataFlash_File::ShowDeviceInfo(AP_HAL::BetterStream *port)
{
port->printf("DataFlash logs stored in %s\n",
_log_directory);
}
/*
list available log numbers
*/
void DataFlash_File::ListAvailableLogs(AP_HAL::BetterStream *port)
{
uint16_t num_logs = get_num_logs();
if (num_logs == 0) {
port->printf("\nNo logs\n\n");
return;
}
port->printf("\n%u logs\n", (unsigned)num_logs);
#if !DATAFLASH_FILE_MINIMAL
for (uint16_t i=1; i<=num_logs; i++) {
uint16_t log_num = _log_num_from_list_entry(i);
char *filename = _log_file_name(log_num);
if (filename != nullptr) {
struct stat st;
if (stat(filename, &st) == 0) {
struct tm *tm = gmtime(&st.st_mtime);
port->printf("Log %u in %s of size %u %u/%u/%u %u:%u\n",
(unsigned)i,
filename,
(unsigned)st.st_size,
(unsigned)tm->tm_year+1900,
(unsigned)tm->tm_mon+1,
(unsigned)tm->tm_mday,
(unsigned)tm->tm_hour,
(unsigned)tm->tm_min);
}
free(filename);
}
}
#endif
port->printf("\n");
}
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL || CONFIG_HAL_BOARD == HAL_BOARD_LINUX
void DataFlash_File::flush(void)

View File

@ -53,13 +53,6 @@ public:
int16_t get_log_data(uint16_t log_num, uint16_t page, uint32_t offset, uint16_t len, uint8_t *data) override;
uint16_t get_num_logs() override;
uint16_t start_new_log(void) override;
void LogReadProcess(const uint16_t log_num,
uint16_t start_page, uint16_t end_page,
print_mode_fn print_mode,
AP_HAL::BetterStream *port) override;
void DumpPageInfo(AP_HAL::BetterStream *port) override;
void ShowDeviceInfo(AP_HAL::BetterStream *port) override;
void ListAvailableLogs(AP_HAL::BetterStream *port) override;
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL || CONFIG_HAL_BOARD == HAL_BOARD_LINUX
void flush(void) override;

View File

@ -852,142 +852,6 @@ uint16_t DataFlash_File::start_new_log(void)
return log_num;
}
/*
Read the log and print it on port
*/
void DataFlash_File::LogReadProcess(const uint16_t list_entry,
uint16_t start_page, uint16_t end_page,
print_mode_fn print_mode,
AP_HAL::BetterStream *port)
{
uint8_t log_step = 0;
if (!_initialised || _open_error) {
return;
}
const uint16_t log_num = _log_num_from_list_entry(list_entry);
if (log_num == 0) {
return;
}
if (_read_fd) {
_read_fd.close();
}
char *fname = _log_file_name(log_num);
if (fname == nullptr) {
return;
}
_read_fd = SD.open(fname, O_RDONLY);
free(fname);
if (!(_read_fd)) {
return;
}
_read_fd_log_num = log_num;
_read_offset = 0;
if (start_page != 0) {
if (!_read_fd.seek(start_page * DATAFLASH_PAGE_SIZE)) {
_read_fd.close();
return;
}
_read_offset = start_page * DATAFLASH_PAGE_SIZE;
}
uint8_t log_counter = 0;
while (true) {
uint8_t data;
if (_read_fd.read(&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;
_print_log_entry(data, print_mode, port);
log_counter++;
break;
}
if (_read_offset >= (end_page+1) * DATAFLASH_PAGE_SIZE) {
break;
}
}
_read_fd.close();
}
/*
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 or mount FC as massStorage
and look at it on your PC
*/
void DataFlash_File::DumpPageInfo(AP_HAL::BetterStream *port)
{
port->printf("DataFlash: num_logs=%u\n", (unsigned)get_num_logs());
}
void DataFlash_File::ShowDeviceInfo(AP_HAL::BetterStream *port)
{
port->printf("DataFlash logs stored in %s\n", _log_directory);
}
/*
list available log numbers
*/
void DataFlash_File::ListAvailableLogs(AP_HAL::BetterStream *port)
{
uint16_t num_logs = get_num_logs();
if (num_logs == 0) {
port->printf("\nNo logs\n\n");
return;
}
port->printf("\n%u logs\n", (unsigned)num_logs);
for (uint16_t i=1; i<=num_logs; i++) {
uint16_t log_num = _log_num_from_list_entry(i);
char *filename = _log_file_name(log_num);
if (filename != nullptr) {
if(file_exists(filename)) {
uint32_t time=_get_log_time(log_num);
struct tm *tm = gmtime((const time_t*)&time);
port->printf("Log %u in %s of size %u %u/%u/%u %u:%u\n",
(unsigned)i,
filename,
(unsigned)_get_log_size(log_num),
(unsigned)tm->tm_year+1900,
(unsigned)tm->tm_mon+1,
(unsigned)tm->tm_mday,
(unsigned)tm->tm_hour,
(unsigned)tm->tm_min);
}
free(filename);
}
}
port->println();
}
void DataFlash_File::_io_timer(void)
{
uint32_t tnow = AP_HAL::millis();

View File

@ -45,13 +45,6 @@ public:
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) override;
void LogReadProcess(const uint16_t log_num,
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);
void periodic_1Hz(const uint32_t now) override;
void periodic_fullrate(const uint32_t now);
@ -152,4 +145,4 @@ private:
bool _busy;
};
#endif
#endif

View File

@ -54,14 +54,6 @@ public:
void get_log_info(uint16_t log_num, uint32_t &size, uint32_t &time_utc) override {}
int16_t get_log_data(uint16_t log_num, uint16_t page, uint32_t offset, uint16_t len, uint8_t *data) override { return 0; }
uint16_t get_num_logs(void) override { return 0; }
void LogReadProcess(uint16_t log_num,
uint16_t start_page, uint16_t end_page,
print_mode_fn printMode,
AP_HAL::BetterStream *port) override {}
void DumpPageInfo(AP_HAL::BetterStream *port) override {}
void ShowDeviceInfo(AP_HAL::BetterStream *port) override {}
void ListAvailableLogs(AP_HAL::BetterStream *port) override {}
void push_log_blocks() override;

View File

@ -1022,71 +1022,4 @@ void DataFlash_Revo::ListAvailableLogs(AP_HAL::BetterStream *port)
port->println();
}
/*
Read the log and print it on port
*/
void DataFlash_Revo::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;
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;
// 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;
}
}
}
void DataFlash_Revo::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;
}
#endif

View File

@ -180,15 +180,6 @@ public:
uint16_t start_new_log(void);
void get_log_boundaries(uint16_t log_num, uint16_t & start_page, uint16_t & end_page);
uint16_t find_last_log() override;
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 get_log_info(uint16_t log_num, uint32_t &size, uint32_t &time_utc);
void DumpPageInfo(AP_HAL::BetterStream *port);
void ShowDeviceInfo(AP_HAL::BetterStream *port);
void ListAvailableLogs(AP_HAL::BetterStream *port);
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);

View File

@ -23,177 +23,6 @@
extern const AP_HAL::HAL& hal;
/*
read and print a log entry using the format strings from the given structure
*/
void DataFlash_Backend::_print_log_entry(uint8_t msg_type,
print_mode_fn print_mode,
AP_HAL::BetterStream *port)
{
uint8_t i;
for (i=0; i<num_types(); i++) {
if (msg_type == structure(i)->msg_type) {
break;
}
}
if (i == num_types()) {
port->printf("UNKN, %u\n", (unsigned)msg_type);
return;
}
const struct LogStructure *log_structure = structure(i);
uint8_t msg_len = log_structure->msg_len - 3;
uint8_t pkt[msg_len];
if (!ReadBlock(pkt, msg_len)) {
return;
}
port->printf("%s, ", log_structure->name);
for (uint8_t ofs=0, fmt_ofs=0; ofs<msg_len; fmt_ofs++) {
char fmt = log_structure->format[fmt_ofs];
switch (fmt) {
case 'b': {
port->printf("%d", (int)pkt[ofs]);
ofs += 1;
break;
}
case 'B': {
port->printf("%u", (unsigned)pkt[ofs]);
ofs += 1;
break;
}
case 'h': {
int16_t v;
memcpy(&v, &pkt[ofs], sizeof(v));
port->printf("%d", (int)v);
ofs += sizeof(v);
break;
}
case 'H': {
uint16_t v;
memcpy(&v, &pkt[ofs], sizeof(v));
port->printf("%u", (unsigned)v);
ofs += sizeof(v);
break;
}
case 'i': {
int32_t v;
memcpy(&v, &pkt[ofs], sizeof(v));
port->printf("%ld", (long)v);
ofs += sizeof(v);
break;
}
case 'I': {
uint32_t v;
memcpy(&v, &pkt[ofs], sizeof(v));
port->printf("%lu", (unsigned long)v);
ofs += sizeof(v);
break;
}
case 'q': {
int64_t v;
memcpy(&v, &pkt[ofs], sizeof(v));
port->printf("%lld", (long long)v);
ofs += sizeof(v);
break;
}
case 'Q': {
uint64_t v;
memcpy(&v, &pkt[ofs], sizeof(v));
port->printf("%llu", (unsigned long long)v);
ofs += sizeof(v);
break;
}
case 'f': {
float v;
memcpy(&v, &pkt[ofs], sizeof(v));
port->printf("%f", (double)v);
ofs += sizeof(v);
break;
}
case 'd': {
double v;
memcpy(&v, &pkt[ofs], sizeof(v));
// note that %f here *really* means a single-precision
// float, so we lose precision printing this double out
// dtoa_engine needed....
port->printf("%f", (double)v);
ofs += sizeof(v);
break;
}
case 'c': {
int16_t v;
memcpy(&v, &pkt[ofs], sizeof(v));
port->printf("%.2f", (double)(0.01f*v));
ofs += sizeof(v);
break;
}
case 'C': {
uint16_t v;
memcpy(&v, &pkt[ofs], sizeof(v));
port->printf("%.2f", (double)(0.01f*v));
ofs += sizeof(v);
break;
}
case 'e': {
int32_t v;
memcpy(&v, &pkt[ofs], sizeof(v));
port->printf("%.2f", (double)(0.01f*v));
ofs += sizeof(v);
break;
}
case 'E': {
uint32_t v;
memcpy(&v, &pkt[ofs], sizeof(v));
port->printf("%.2f", (double)(0.01f*v));
ofs += sizeof(v);
break;
}
case 'L': {
int32_t v;
memcpy(&v, &pkt[ofs], sizeof(v));
print_latlon(port, v);
ofs += sizeof(v);
break;
}
case 'n': {
char v[5];
memcpy(&v, &pkt[ofs], sizeof(v));
v[sizeof(v)-1] = 0;
port->printf("%s", v);
ofs += sizeof(v)-1;
break;
}
case 'N': {
char v[17];
memcpy(&v, &pkt[ofs], sizeof(v));
v[sizeof(v)-1] = 0;
port->printf("%s", v);
ofs += sizeof(v)-1;
break;
}
case 'Z': {
char v[65];
memcpy(&v, &pkt[ofs], sizeof(v));
v[sizeof(v)-1] = 0;
port->printf("%s", v);
ofs += sizeof(v)-1;
break;
}
case 'M': {
print_mode(port, pkt[ofs]);
ofs += 1;
break;
}
default:
ofs = msg_len;
break;
}
if (ofs < msg_len) {
port->printf(", ");
}
}
port->printf("\n");
}
/*
write a structure format to the log - should be in frontend
*/

View File

@ -214,7 +214,6 @@ void DataFlashTest_AllTypes::setup(void)
// Test
hal.scheduler->delay(20);
dataflash.ShowDeviceInfo(hal.console);
Log_Write_TypeMessages();
Log_Write_TypeMessages_Log_Write();

View File

@ -11,7 +11,6 @@
const AP_HAL::HAL& hal = AP_HAL::get_HAL();
#define LOG_TEST_MSG 1
struct PACKED log_Test {
LOG_PACKET_HEADER;
uint16_t v1, v2, v3, v4;
@ -42,7 +41,7 @@ private:
AP_Int32 log_bitmask;
DataFlash_Class dataflash{"DF Test 0.1", log_bitmask};
void print_mode(AP_HAL::BetterStream *port, uint8_t mode);
};
static DataFlashTest dataflashtest;
@ -58,14 +57,11 @@ void DataFlashTest::setup(void)
// Test
hal.scheduler->delay(20);
dataflash.ShowDeviceInfo(hal.console);
// We start to write some info (sequentialy) starting from page 1
// This is similar to what we will do...
log_num = dataflash.find_last_log();
hal.console->printf("Using log number %u\n", log_num);
hal.console->printf("After testing perform erase before using DataFlash for logging!\n");
hal.console->printf("\n");
hal.console->printf("Writing to flash... wait...\n");
uint32_t total_micros = 0;
@ -101,23 +97,10 @@ void DataFlashTest::setup(void)
void DataFlashTest::loop(void)
{
uint16_t start, end;
hal.console->printf("Start read of log %u\n", log_num);
dataflash.get_log_boundaries(log_num, start, end);
dataflash.LogReadProcess(log_num, start, end,
FUNCTOR_BIND_MEMBER(&DataFlashTest::print_mode, void, AP_HAL::BetterStream *, uint8_t),//print_mode,
hal.console);
hal.console->printf("\nTest complete. Test will repeat in 20 seconds\n");
hal.console->printf("\nTest complete.\n");
hal.scheduler->delay(20000);
}
void DataFlashTest::print_mode(AP_HAL::BetterStream *port, uint8_t mode)
{
port->printf("Mode(%u)", (unsigned)mode);
}
/*
compatibility with old pde style build
*/
@ -129,7 +112,6 @@ void setup()
dataflashtest.setup();
}
void loop()
{
dataflashtest.loop();