mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 14:38:30 -04:00
DataFlash: add a heartbeat for the io thread in DataFlash_File
This commit is contained in:
parent
e11c276b35
commit
bc45ab5409
@ -29,6 +29,7 @@
|
|||||||
#include <stdio.h>
|
#include <stdio.h>
|
||||||
#include <time.h>
|
#include <time.h>
|
||||||
#include <dirent.h>
|
#include <dirent.h>
|
||||||
|
#include <GCS_MAVLink/GCS.h>
|
||||||
#if defined(__APPLE__) && defined(__MACH__)
|
#if defined(__APPLE__) && defined(__MACH__)
|
||||||
#include <sys/param.h>
|
#include <sys/param.h>
|
||||||
#include <sys/mount.h>
|
#include <sys/mount.h>
|
||||||
@ -182,6 +183,18 @@ bool DataFlash_File::log_exists(const uint16_t lognum) const
|
|||||||
return ret;
|
return ret;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
void DataFlash_File::periodic_1Hz(const uint32_t now)
|
||||||
|
{
|
||||||
|
if (!io_thread_alive()) {
|
||||||
|
GCS_MAVLINK::send_statustext_all(MAV_SEVERITY_CRITICAL, "No IO Thread Heartbeat");
|
||||||
|
// If you try to close the file here then it will almost
|
||||||
|
// certainly block. Since this is the main thread, this is
|
||||||
|
// likely to cause a crash.
|
||||||
|
_write_fd = -1;
|
||||||
|
_initialised = false;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
void DataFlash_File::periodic_fullrate(const uint32_t now)
|
void DataFlash_File::periodic_fullrate(const uint32_t now)
|
||||||
{
|
{
|
||||||
DataFlash_Backend::push_log_blocks();
|
DataFlash_Backend::push_log_blocks();
|
||||||
@ -1017,6 +1030,8 @@ void DataFlash_File::flush(void)
|
|||||||
|
|
||||||
void DataFlash_File::_io_timer(void)
|
void DataFlash_File::_io_timer(void)
|
||||||
{
|
{
|
||||||
|
uint32_t tnow = AP_HAL::millis();
|
||||||
|
_io_timer_heartbeat = tnow;
|
||||||
if (_write_fd == -1 || !_initialised || _open_error) {
|
if (_write_fd == -1 || !_initialised || _open_error) {
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
@ -1025,7 +1040,6 @@ void DataFlash_File::_io_timer(void)
|
|||||||
if (nbytes == 0) {
|
if (nbytes == 0) {
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
uint32_t tnow = AP_HAL::millis();
|
|
||||||
if (nbytes < _writebuf_chunk &&
|
if (nbytes < _writebuf_chunk &&
|
||||||
tnow - _last_write_time < 2000UL) {
|
tnow - _last_write_time < 2000UL) {
|
||||||
// write in _writebuf_chunk-sized chunks, but always write at
|
// write in _writebuf_chunk-sized chunks, but always write at
|
||||||
@ -1094,6 +1108,13 @@ bool DataFlash_File::logging_enabled() const
|
|||||||
return false;
|
return false;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
bool DataFlash_File::io_thread_alive() const
|
||||||
|
{
|
||||||
|
uint32_t tnow = AP_HAL::millis();
|
||||||
|
// if the io thread hasn't had a heartbeat in a full second then it is dead
|
||||||
|
return _io_timer_heartbeat + 1000 > tnow;
|
||||||
|
}
|
||||||
|
|
||||||
bool DataFlash_File::logging_failed() const
|
bool DataFlash_File::logging_failed() const
|
||||||
{
|
{
|
||||||
if (_write_fd == -1 &&
|
if (_write_fd == -1 &&
|
||||||
@ -1104,6 +1125,12 @@ bool DataFlash_File::logging_failed() const
|
|||||||
if (_open_error) {
|
if (_open_error) {
|
||||||
return true;
|
return true;
|
||||||
}
|
}
|
||||||
|
if (!io_thread_alive()) {
|
||||||
|
// No heartbeat in a second. IO thread is dead?! Very Not
|
||||||
|
// Good.
|
||||||
|
return true;
|
||||||
|
}
|
||||||
|
|
||||||
return false;
|
return false;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -64,6 +64,7 @@ public:
|
|||||||
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL || CONFIG_HAL_BOARD == HAL_BOARD_LINUX
|
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL || CONFIG_HAL_BOARD == HAL_BOARD_LINUX
|
||||||
void flush(void);
|
void flush(void);
|
||||||
#endif
|
#endif
|
||||||
|
void periodic_1Hz(const uint32_t now) override;
|
||||||
void periodic_fullrate(const uint32_t now);
|
void periodic_fullrate(const uint32_t now);
|
||||||
|
|
||||||
// this method is used when reporting system status over mavlink
|
// this method is used when reporting system status over mavlink
|
||||||
@ -82,6 +83,9 @@ private:
|
|||||||
volatile bool _open_error;
|
volatile bool _open_error;
|
||||||
const char *_log_directory;
|
const char *_log_directory;
|
||||||
|
|
||||||
|
uint32_t _io_timer_heartbeat;
|
||||||
|
bool io_thread_alive() const;
|
||||||
|
|
||||||
uint16_t _cached_oldest_log;
|
uint16_t _cached_oldest_log;
|
||||||
|
|
||||||
/*
|
/*
|
||||||
|
Loading…
Reference in New Issue
Block a user