AP_Logger: make logging_started const

This commit is contained in:
Peter Barker 2024-10-09 11:26:57 +11:00 committed by Randy Mackay
parent e4859599cf
commit 70c277b759
2 changed files with 2 additions and 2 deletions

View File

@ -833,7 +833,7 @@ uint16_t AP_Logger::get_max_num_logs() {
}
/* we're started if any of the backends are started */
bool AP_Logger::logging_started(void) {
bool AP_Logger::logging_started(void) const {
for (uint8_t i=0; i< _next_backend; i++) {
if (backends[i]->logging_started()) {
return true;

View File

@ -301,7 +301,7 @@ public:
// returns true if logging of a message should be attempted
bool should_log(uint32_t mask) const;
bool logging_started(void);
bool logging_started(void) const;
#if CONFIG_HAL_BOARD == HAL_BOARD_SITL || CONFIG_HAL_BOARD == HAL_BOARD_LINUX
// currently only AP_Logger_File support this: