mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 14:38:30 -04:00
DataFlash: method to flush ringbuffer to fd
This commit is contained in:
parent
686b1137fa
commit
c5c39a77a3
@ -66,5 +66,11 @@ void DataFlash_Class::EnableWrites(bool enable) {
|
|||||||
backend->EnableWrites(enable);
|
backend->EnableWrites(enable);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL || CONFIG_HAL_BOARD == HAL_BOARD_LINUX
|
||||||
|
// currently only DataFlash_File support this:
|
||||||
|
void DataFlash_Class::flush(void) {
|
||||||
|
backend->flush();
|
||||||
|
}
|
||||||
|
#endif
|
||||||
|
|
||||||
// end functions pass straight through to backend
|
// end functions pass straight through to backend
|
||||||
|
@ -104,6 +104,11 @@ public:
|
|||||||
|
|
||||||
bool logging_started(void);
|
bool logging_started(void);
|
||||||
|
|
||||||
|
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL || CONFIG_HAL_BOARD == HAL_BOARD_LINUX
|
||||||
|
// currently only DataFlash_File support this:
|
||||||
|
void flush(void);
|
||||||
|
#endif
|
||||||
|
|
||||||
protected:
|
protected:
|
||||||
void Log_Fill_Format(const struct LogStructure *structure, struct log_Format &pkt);
|
void Log_Fill_Format(const struct LogStructure *structure, struct log_Format &pkt);
|
||||||
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,
|
||||||
|
@ -68,6 +68,11 @@ public:
|
|||||||
|
|
||||||
void Log_Fill_Format(const struct LogStructure *structure, struct log_Format &pkt);
|
void Log_Fill_Format(const struct LogStructure *structure, struct log_Format &pkt);
|
||||||
|
|
||||||
|
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL || CONFIG_HAL_BOARD == HAL_BOARD_LINUX
|
||||||
|
// currently only DataFlash_File support this:
|
||||||
|
virtual void flush(void) { }
|
||||||
|
#endif
|
||||||
|
|
||||||
protected:
|
protected:
|
||||||
DataFlash_Class &_front;
|
DataFlash_Class &_front;
|
||||||
|
|
||||||
|
@ -608,6 +608,25 @@ void DataFlash_File::ListAvailableLogs(AP_HAL::BetterStream *port)
|
|||||||
port->println();
|
port->println();
|
||||||
}
|
}
|
||||||
|
|
||||||
|
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL || CONFIG_HAL_BOARD == HAL_BOARD_LINUX
|
||||||
|
void DataFlash_File::flush(void)
|
||||||
|
{
|
||||||
|
uint16_t _tail;
|
||||||
|
uint32_t tnow = hal.scheduler->micros();
|
||||||
|
hal.scheduler->suspend_timer_procs();
|
||||||
|
while (_write_fd != -1 && _initialised && !_open_error &&
|
||||||
|
BUF_AVAILABLE(_writebuf)) {
|
||||||
|
// convince the IO timer that it really is OK to write out
|
||||||
|
// less than _writebuf_chunk bytes:
|
||||||
|
_last_write_time = tnow - 2000000;
|
||||||
|
_io_timer();
|
||||||
|
}
|
||||||
|
hal.scheduler->resume_timer_procs();
|
||||||
|
if (_write_fd != -1) {
|
||||||
|
::fsync(_write_fd);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
#endif
|
||||||
|
|
||||||
void DataFlash_File::_io_timer(void)
|
void DataFlash_File::_io_timer(void)
|
||||||
{
|
{
|
||||||
|
@ -53,6 +53,10 @@ public:
|
|||||||
void ShowDeviceInfo(AP_HAL::BetterStream *port);
|
void ShowDeviceInfo(AP_HAL::BetterStream *port);
|
||||||
void ListAvailableLogs(AP_HAL::BetterStream *port);
|
void ListAvailableLogs(AP_HAL::BetterStream *port);
|
||||||
|
|
||||||
|
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL || CONFIG_HAL_BOARD == HAL_BOARD_LINUX
|
||||||
|
void flush(void);
|
||||||
|
#endif
|
||||||
|
|
||||||
private:
|
private:
|
||||||
int _write_fd;
|
int _write_fd;
|
||||||
int _read_fd;
|
int _read_fd;
|
||||||
|
Loading…
Reference in New Issue
Block a user