mirror of https://github.com/ArduPilot/ardupilot
DataFlash: stop write logging while reading
prevents nuttx getting confused
This commit is contained in:
parent
ff7004fcc5
commit
e1a86440bb
|
@ -269,7 +269,8 @@ int16_t DataFlash_File::get_log_data(uint16_t log_num, uint16_t page, uint32_t o
|
|||
if (fname == NULL) {
|
||||
return -1;
|
||||
}
|
||||
_read_fd = open(fname, O_RDONLY);
|
||||
stop_logging();
|
||||
_read_fd = ::open(fname, O_RDONLY);
|
||||
free(fname);
|
||||
if (_read_fd == -1) {
|
||||
return -1;
|
||||
|
@ -314,17 +315,26 @@ uint16_t DataFlash_File::get_num_logs(void)
|
|||
return ret;
|
||||
}
|
||||
|
||||
|
||||
/*
|
||||
start writing to a new log file
|
||||
stop logging
|
||||
*/
|
||||
uint16_t DataFlash_File::start_new_log(void)
|
||||
void DataFlash_File::stop_logging(void)
|
||||
{
|
||||
if (_write_fd != -1) {
|
||||
int fd = _write_fd;
|
||||
_write_fd = -1;
|
||||
::close(fd);
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
/*
|
||||
start writing to a new log file
|
||||
*/
|
||||
uint16_t DataFlash_File::start_new_log(void)
|
||||
{
|
||||
stop_logging();
|
||||
|
||||
if (_read_fd != -1) {
|
||||
::close(_read_fd);
|
||||
_read_fd = -1;
|
||||
|
@ -515,7 +525,7 @@ void DataFlash_File::_io_timer(void)
|
|||
assert(_writebuf_head+nbytes <= _writebuf_size);
|
||||
ssize_t nwritten = ::write(_write_fd, &_writebuf[_writebuf_head], nbytes);
|
||||
if (nwritten <= 0) {
|
||||
hal.console->printf("DataFlash write: %d %d\n", (int)nwritten, (int)errno);
|
||||
//hal.console->printf("DataFlash write: %d %d\n", (int)nwritten, (int)errno);
|
||||
close(_write_fd);
|
||||
_write_fd = -1;
|
||||
_initialised = false;
|
||||
|
|
|
@ -68,6 +68,8 @@ private:
|
|||
uint32_t _get_log_size(uint16_t log_num);
|
||||
uint32_t _get_log_time(uint16_t log_num);
|
||||
|
||||
void stop_logging(void);
|
||||
|
||||
void _io_timer(void);
|
||||
};
|
||||
|
||||
|
|
Loading…
Reference in New Issue