mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-12 02:44:00 -04:00
AP_Logger: Change the type of a method
This commit is contained in:
parent
d82b29b23d
commit
f6595a41ae
@ -49,7 +49,7 @@ public:
|
|||||||
|
|
||||||
virtual void PrepForArming() { }
|
virtual void PrepForArming() { }
|
||||||
|
|
||||||
virtual uint16_t start_new_log(void) = 0;
|
virtual void start_new_log() { };
|
||||||
|
|
||||||
/* stop logging - close output files etc etc.
|
/* stop logging - close output files etc etc.
|
||||||
*
|
*
|
||||||
|
@ -414,7 +414,7 @@ uint16_t AP_Logger_Block::get_num_logs(void)
|
|||||||
|
|
||||||
|
|
||||||
// This function starts a new log file in the AP_Logger
|
// This function starts a new log file in the AP_Logger
|
||||||
uint16_t AP_Logger_Block::start_new_log(void)
|
void AP_Logger_Block::start_new_log(void)
|
||||||
{
|
{
|
||||||
WITH_SEMAPHORE(sem);
|
WITH_SEMAPHORE(sem);
|
||||||
uint32_t last_page = find_last_page();
|
uint32_t last_page = find_last_page();
|
||||||
@ -424,7 +424,7 @@ uint16_t AP_Logger_Block::start_new_log(void)
|
|||||||
if (find_last_log() == 0 || GetFileNumber() == 0xFFFF) {
|
if (find_last_log() == 0 || GetFileNumber() == 0xFFFF) {
|
||||||
SetFileNumber(1);
|
SetFileNumber(1);
|
||||||
StartWrite(1);
|
StartWrite(1);
|
||||||
return 1;
|
return;
|
||||||
}
|
}
|
||||||
|
|
||||||
uint16_t new_log_num;
|
uint16_t new_log_num;
|
||||||
@ -444,7 +444,7 @@ uint16_t AP_Logger_Block::start_new_log(void)
|
|||||||
SetFileNumber(new_log_num);
|
SetFileNumber(new_log_num);
|
||||||
StartWrite(last_page + 1);
|
StartWrite(last_page + 1);
|
||||||
}
|
}
|
||||||
return new_log_num;
|
return;
|
||||||
}
|
}
|
||||||
|
|
||||||
// This function finds the first and last pages of a log file
|
// This function finds the first and last pages of a log file
|
||||||
|
@ -25,7 +25,7 @@ public:
|
|||||||
void get_log_info(uint16_t log_num, uint32_t &size, uint32_t &time_utc) override;
|
void get_log_info(uint16_t log_num, uint32_t &size, uint32_t &time_utc) override;
|
||||||
int16_t get_log_data(uint16_t log_num, uint16_t page, uint32_t offset, uint16_t len, uint8_t *data) override WARN_IF_UNUSED;
|
int16_t get_log_data(uint16_t log_num, uint16_t page, uint32_t offset, uint16_t len, uint8_t *data) override WARN_IF_UNUSED;
|
||||||
uint16_t get_num_logs() override;
|
uint16_t get_num_logs() override;
|
||||||
uint16_t start_new_log(void) override;
|
void start_new_log(void) override;
|
||||||
uint32_t bufferspace_available() override;
|
uint32_t bufferspace_available() override;
|
||||||
void stop_logging(void) override { log_write_started = false; }
|
void stop_logging(void) override { log_write_started = false; }
|
||||||
bool logging_enabled() const override { return true; }
|
bool logging_enabled() const override { return true; }
|
||||||
|
@ -776,7 +776,7 @@ void AP_Logger_File::PrepForArming()
|
|||||||
/*
|
/*
|
||||||
start writing to a new log file
|
start writing to a new log file
|
||||||
*/
|
*/
|
||||||
uint16_t AP_Logger_File::start_new_log(void)
|
void AP_Logger_File::start_new_log(void)
|
||||||
{
|
{
|
||||||
stop_logging();
|
stop_logging();
|
||||||
|
|
||||||
@ -785,7 +785,7 @@ uint16_t AP_Logger_File::start_new_log(void)
|
|||||||
if (_open_error) {
|
if (_open_error) {
|
||||||
// we have previously failed to open a file - don't try again
|
// we have previously failed to open a file - don't try again
|
||||||
// to prevent us trying to open files while in flight
|
// to prevent us trying to open files while in flight
|
||||||
return 0xFFFF;
|
return;
|
||||||
}
|
}
|
||||||
|
|
||||||
if (_read_fd != -1) {
|
if (_read_fd != -1) {
|
||||||
@ -796,7 +796,7 @@ uint16_t AP_Logger_File::start_new_log(void)
|
|||||||
if (disk_space_avail() < _free_space_min_avail && disk_space() > 0) {
|
if (disk_space_avail() < _free_space_min_avail && disk_space() > 0) {
|
||||||
hal.console->printf("Out of space for logging\n");
|
hal.console->printf("Out of space for logging\n");
|
||||||
_open_error = true;
|
_open_error = true;
|
||||||
return 0xffff;
|
return;
|
||||||
}
|
}
|
||||||
|
|
||||||
uint16_t log_num = find_last_log();
|
uint16_t log_num = find_last_log();
|
||||||
@ -809,7 +809,7 @@ uint16_t AP_Logger_File::start_new_log(void)
|
|||||||
}
|
}
|
||||||
if (!write_fd_semaphore.take(1)) {
|
if (!write_fd_semaphore.take(1)) {
|
||||||
_open_error = true;
|
_open_error = true;
|
||||||
return 0xFFFF;
|
return;
|
||||||
}
|
}
|
||||||
if (_write_filename) {
|
if (_write_filename) {
|
||||||
free(_write_filename);
|
free(_write_filename);
|
||||||
@ -819,7 +819,7 @@ uint16_t AP_Logger_File::start_new_log(void)
|
|||||||
if (_write_filename == nullptr) {
|
if (_write_filename == nullptr) {
|
||||||
_open_error = true;
|
_open_error = true;
|
||||||
write_fd_semaphore.give();
|
write_fd_semaphore.give();
|
||||||
return 0xFFFF;
|
return;
|
||||||
}
|
}
|
||||||
|
|
||||||
#if CONFIG_HAL_BOARD == HAL_BOARD_CHIBIOS
|
#if CONFIG_HAL_BOARD == HAL_BOARD_CHIBIOS
|
||||||
@ -841,7 +841,7 @@ uint16_t AP_Logger_File::start_new_log(void)
|
|||||||
_write_filename, strerror(saved_errno));
|
_write_filename, strerror(saved_errno));
|
||||||
hal.console->printf("Log open fail for %s - %s\n",
|
hal.console->printf("Log open fail for %s - %s\n",
|
||||||
_write_filename, strerror(saved_errno));
|
_write_filename, strerror(saved_errno));
|
||||||
return 0xFFFF;
|
return;
|
||||||
}
|
}
|
||||||
_last_write_ms = AP_HAL::millis();
|
_last_write_ms = AP_HAL::millis();
|
||||||
_write_offset = 0;
|
_write_offset = 0;
|
||||||
@ -858,7 +858,7 @@ uint16_t AP_Logger_File::start_new_log(void)
|
|||||||
free(fname);
|
free(fname);
|
||||||
if (fd == -1) {
|
if (fd == -1) {
|
||||||
_open_error = true;
|
_open_error = true;
|
||||||
return 0xFFFF;
|
return;
|
||||||
}
|
}
|
||||||
|
|
||||||
char buf[30];
|
char buf[30];
|
||||||
@ -869,10 +869,10 @@ uint16_t AP_Logger_File::start_new_log(void)
|
|||||||
|
|
||||||
if (written < to_write) {
|
if (written < to_write) {
|
||||||
_open_error = true;
|
_open_error = true;
|
||||||
return 0xFFFF;
|
return;
|
||||||
}
|
}
|
||||||
|
|
||||||
return log_num;
|
return;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
|
@ -42,7 +42,7 @@ public:
|
|||||||
void get_log_info(uint16_t log_num, uint32_t &size, uint32_t &time_utc) override;
|
void get_log_info(uint16_t log_num, uint32_t &size, uint32_t &time_utc) override;
|
||||||
int16_t get_log_data(uint16_t log_num, uint16_t page, uint32_t offset, uint16_t len, uint8_t *data) override;
|
int16_t get_log_data(uint16_t log_num, uint16_t page, uint32_t offset, uint16_t len, uint8_t *data) override;
|
||||||
uint16_t get_num_logs() override;
|
uint16_t get_num_logs() override;
|
||||||
uint16_t start_new_log(void) override;
|
void start_new_log(void) override;
|
||||||
|
|
||||||
#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) override;
|
void flush(void) override;
|
||||||
|
@ -170,8 +170,8 @@ private:
|
|||||||
/* we currently ignore requests to start a new log. Notionally we
|
/* we currently ignore requests to start a new log. Notionally we
|
||||||
* could close the currently logging session and hope the client
|
* could close the currently logging session and hope the client
|
||||||
* re-opens one */
|
* re-opens one */
|
||||||
uint16_t start_new_log(void) override {
|
void start_new_log(void) override {
|
||||||
return 0;
|
return;
|
||||||
}
|
}
|
||||||
// performance counters
|
// performance counters
|
||||||
AP_HAL::Util::perf_counter_t _perf_errors;
|
AP_HAL::Util::perf_counter_t _perf_errors;
|
||||||
|
Loading…
Reference in New Issue
Block a user