mirror of https://github.com/ArduPilot/ardupilot
Replay: print some statistics on exit
This commit is contained in:
parent
97b6ca218b
commit
b5e206f72f
|
@ -5,6 +5,26 @@
|
|||
#include <sys/types.h>
|
||||
#include <stdio.h>
|
||||
#include <unistd.h>
|
||||
#include <time.h>
|
||||
|
||||
// flogged from AP_Hal_Linux/system.cpp; we don't want to use stopped clock here
|
||||
uint64_t now() {
|
||||
struct timespec ts;
|
||||
clock_gettime(CLOCK_MONOTONIC, &ts);
|
||||
return 1.0e6*((ts.tv_sec + (ts.tv_nsec*1.0e-9)));
|
||||
}
|
||||
|
||||
DataFlashFileReader::DataFlashFileReader() :
|
||||
start_micros(now())
|
||||
{}
|
||||
|
||||
DataFlashFileReader::~DataFlashFileReader()
|
||||
{
|
||||
const uint64_t micros = now();
|
||||
const uint64_t delta = micros - start_micros;
|
||||
::printf("Replay counts: %ld bytes %u entries\n", bytes_read, message_count);
|
||||
::printf("Replay rates: %ld bytes/second %ld messages/second\n", bytes_read*1000000/delta, message_count*1000000/delta);
|
||||
}
|
||||
|
||||
bool DataFlashFileReader::open_log(const char *logfile)
|
||||
{
|
||||
|
@ -15,10 +35,17 @@ bool DataFlashFileReader::open_log(const char *logfile)
|
|||
return true;
|
||||
}
|
||||
|
||||
ssize_t DataFlashFileReader::read_input(void *buffer, const size_t count)
|
||||
{
|
||||
uint64_t ret = ::read(fd, buffer, count);
|
||||
bytes_read += ret;
|
||||
return ret;
|
||||
}
|
||||
|
||||
bool DataFlashFileReader::update(char type[5])
|
||||
{
|
||||
uint8_t hdr[3];
|
||||
if (::read(fd, hdr, 3) != 3) {
|
||||
if (read_input(hdr, 3) != 3) {
|
||||
return false;
|
||||
}
|
||||
if (hdr[0] != HEAD_BYTE1 || hdr[1] != HEAD_BYTE2) {
|
||||
|
@ -29,13 +56,14 @@ bool DataFlashFileReader::update(char type[5])
|
|||
if (hdr[2] == LOG_FORMAT_MSG) {
|
||||
struct log_Format f;
|
||||
memcpy(&f, hdr, 3);
|
||||
if (::read(fd, &f.type, sizeof(f)-3) != sizeof(f)-3) {
|
||||
if (read_input(&f.type, sizeof(f)-3) != sizeof(f)-3) {
|
||||
return false;
|
||||
}
|
||||
memcpy(&formats[f.type], &f, sizeof(formats[f.type]));
|
||||
strncpy(type, "FMT", 3);
|
||||
type[3] = 0;
|
||||
|
||||
message_count++;
|
||||
return handle_log_format_msg(f);
|
||||
}
|
||||
|
||||
|
@ -55,12 +83,13 @@ bool DataFlashFileReader::update(char type[5])
|
|||
uint8_t msg[f.length];
|
||||
|
||||
memcpy(msg, hdr, 3);
|
||||
if (::read(fd, &msg[3], f.length-3) != f.length-3) {
|
||||
if (read_input(&msg[3], f.length-3) != f.length-3) {
|
||||
return false;
|
||||
}
|
||||
|
||||
strncpy(type, f.name, 4);
|
||||
type[4] = 0;
|
||||
|
||||
message_count++;
|
||||
return handle_msg(f,msg);
|
||||
}
|
||||
|
|
|
@ -5,6 +5,10 @@
|
|||
class DataFlashFileReader
|
||||
{
|
||||
public:
|
||||
|
||||
DataFlashFileReader();
|
||||
~DataFlashFileReader();
|
||||
|
||||
bool open_log(const char *logfile);
|
||||
bool update(char type[5]);
|
||||
|
||||
|
@ -18,4 +22,12 @@ protected:
|
|||
|
||||
#define LOGREADER_MAX_FORMATS 255 // must be >= highest MESSAGE
|
||||
struct log_Format formats[LOGREADER_MAX_FORMATS] {};
|
||||
|
||||
private:
|
||||
ssize_t read_input(void *buf, size_t count);
|
||||
|
||||
uint64_t bytes_read = 0;
|
||||
uint32_t message_count = 0;
|
||||
uint64_t start_micros;
|
||||
|
||||
};
|
||||
|
|
|
@ -37,6 +37,7 @@ const struct LogStructure log_structure[] = {
|
|||
|
||||
LogReader::LogReader(AP_AHRS &_ahrs, AP_InertialSensor &_ins, AP_Baro &_baro, Compass &_compass, AP_GPS &_gps,
|
||||
AP_Airspeed &_airspeed, DataFlash_Class &_dataflash, const char **&_nottypes):
|
||||
DataFlashFileReader(),
|
||||
vehicle(VehicleType::VEHICLE_UNKNOWN),
|
||||
ahrs(_ahrs),
|
||||
ins(_ins),
|
||||
|
|
Loading…
Reference in New Issue