mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-22 00:28:30 -04:00
DataFlash: use new scheduler API
This commit is contained in:
parent
f53afaa5ac
commit
19e9c95983
@ -28,21 +28,19 @@ extern const AP_HAL::HAL& hal;
|
|||||||
#define MAX_LOG_FILES 500U
|
#define MAX_LOG_FILES 500U
|
||||||
#define DATAFLASH_PAGE_SIZE 1024UL
|
#define DATAFLASH_PAGE_SIZE 1024UL
|
||||||
|
|
||||||
int DataFlash_File::_write_fd = -1;
|
|
||||||
volatile bool DataFlash_File::_initialised = false;
|
|
||||||
|
|
||||||
uint8_t *DataFlash_File::_writebuf = NULL;
|
|
||||||
const uint16_t DataFlash_File::_writebuf_size = 4096;
|
|
||||||
volatile uint16_t DataFlash_File::_writebuf_head = 0;
|
|
||||||
volatile uint16_t DataFlash_File::_writebuf_tail = 0;
|
|
||||||
uint32_t DataFlash_File::_last_write_time = 0;
|
|
||||||
|
|
||||||
/*
|
/*
|
||||||
constructor
|
constructor
|
||||||
*/
|
*/
|
||||||
DataFlash_File::DataFlash_File(const char *log_directory) :
|
DataFlash_File::DataFlash_File(const char *log_directory) :
|
||||||
|
_write_fd(-1),
|
||||||
_read_fd(-1),
|
_read_fd(-1),
|
||||||
_log_directory(log_directory)
|
_initialised(false),
|
||||||
|
_log_directory(log_directory),
|
||||||
|
_writebuf(NULL),
|
||||||
|
_writebuf_size(4096),
|
||||||
|
_writebuf_head(0),
|
||||||
|
_writebuf_tail(0),
|
||||||
|
_last_write_time(0)
|
||||||
{}
|
{}
|
||||||
|
|
||||||
|
|
||||||
@ -65,7 +63,7 @@ void DataFlash_File::Init(void)
|
|||||||
}
|
}
|
||||||
_writebuf_head = _writebuf_tail = 0;
|
_writebuf_head = _writebuf_tail = 0;
|
||||||
_initialised = true;
|
_initialised = true;
|
||||||
hal.scheduler->register_io_process(_io_timer);
|
hal.scheduler->register_io_process(reinterpret_cast<AP_HAL::TimedProc>(&DataFlash_File::_io_timer), this);
|
||||||
}
|
}
|
||||||
|
|
||||||
// return true for CardInserted() if we successfully initialised
|
// return true for CardInserted() if we successfully initialised
|
||||||
@ -409,7 +407,7 @@ void DataFlash_File::ListAvailableLogs(AP_HAL::BetterStream *port)
|
|||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
void DataFlash_File::_io_timer(uint32_t tnow)
|
void DataFlash_File::_io_timer(void)
|
||||||
{
|
{
|
||||||
uint16_t _tail;
|
uint16_t _tail;
|
||||||
if (_write_fd == -1 || !_initialised) {
|
if (_write_fd == -1 || !_initialised) {
|
||||||
@ -419,6 +417,7 @@ void DataFlash_File::_io_timer(uint32_t tnow)
|
|||||||
if (nbytes == 0) {
|
if (nbytes == 0) {
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
|
uint32_t tnow = hal.scheduler->micros();
|
||||||
if (nbytes < 512 &&
|
if (nbytes < 512 &&
|
||||||
tnow - _last_write_time < 2000000UL) {
|
tnow - _last_write_time < 2000000UL) {
|
||||||
// write in 512 byte chunks, but always write at least once
|
// write in 512 byte chunks, but always write at least once
|
||||||
|
@ -43,10 +43,10 @@ public:
|
|||||||
void ListAvailableLogs(AP_HAL::BetterStream *port);
|
void ListAvailableLogs(AP_HAL::BetterStream *port);
|
||||||
|
|
||||||
private:
|
private:
|
||||||
static int _write_fd;
|
int _write_fd;
|
||||||
int _read_fd;
|
int _read_fd;
|
||||||
uint32_t _read_offset;
|
uint32_t _read_offset;
|
||||||
static volatile bool _initialised;
|
volatile bool _initialised;
|
||||||
const char *_log_directory;
|
const char *_log_directory;
|
||||||
|
|
||||||
/*
|
/*
|
||||||
@ -55,18 +55,18 @@ private:
|
|||||||
void ReadBlock(void *pkt, uint16_t size);
|
void ReadBlock(void *pkt, uint16_t size);
|
||||||
|
|
||||||
// write buffer
|
// write buffer
|
||||||
static uint8_t *_writebuf;
|
uint8_t *_writebuf;
|
||||||
static const uint16_t _writebuf_size;
|
const uint16_t _writebuf_size;
|
||||||
static volatile uint16_t _writebuf_head;
|
volatile uint16_t _writebuf_head;
|
||||||
static volatile uint16_t _writebuf_tail;
|
volatile uint16_t _writebuf_tail;
|
||||||
static uint32_t _last_write_time;
|
uint32_t _last_write_time;
|
||||||
|
|
||||||
/* construct a file name given a log number. Caller must free. */
|
/* construct a file name given a log number. Caller must free. */
|
||||||
char *_log_file_name(uint16_t log_num);
|
char *_log_file_name(uint16_t log_num);
|
||||||
char *_lastlog_file_name(void);
|
char *_lastlog_file_name(void);
|
||||||
uint32_t _get_log_size(uint16_t log_num);
|
uint32_t _get_log_size(uint16_t log_num);
|
||||||
|
|
||||||
static void _io_timer(uint32_t now);
|
void _io_timer(void);
|
||||||
};
|
};
|
||||||
|
|
||||||
|
|
||||||
|
Loading…
Reference in New Issue
Block a user