AP_Logger: use HAL_LOGGING_ENABLED defines

This commit is contained in:
Peter Barker 2023-09-05 23:08:30 +10:00 committed by Peter Barker
parent 2e84e273ea
commit 198268e03c
5 changed files with 31 additions and 3 deletions

View File

@ -1,3 +1,7 @@
#include "AP_Logger_config.h"
#if HAL_LOGGING_ENABLED
#include "AP_Logger_Backend.h"
#include "LoggerMessageWriter.h"
@ -752,3 +756,5 @@ bool AP_Logger_RateLimiter::should_log(uint8_t msgid, bool writev_streaming)
}
return ret;
}
#endif // HAL_LOGGING_ENABLED

View File

@ -1,5 +1,9 @@
#pragma once
#include "AP_Logger_config.h"
#if HAL_LOGGING_ENABLED
#include "AP_Logger.h"
#include <AP_Common/Bitmask.h>
@ -259,3 +263,5 @@ private:
void Write_AP_Logger_Stats_File(const struct df_stats &_stats);
void validate_WritePrioritisedBlock(const void *pBuffer, uint16_t size);
};
#endif // HAL_LOGGING_ENABLED

View File

@ -7,17 +7,21 @@
#define HAL_LOGGING_ENABLED 1
#endif
#ifndef HAL_LOGGING_BACKEND_DEFAULT_ENABLED
#define HAL_LOGGING_BACKEND_DEFAULT_ENABLED HAL_LOGGING_ENABLED
#endif
// set default for HAL_LOGGING_DATAFLASH_ENABLED
#ifndef HAL_LOGGING_DATAFLASH_ENABLED
#define HAL_LOGGING_DATAFLASH_ENABLED (CONFIG_HAL_BOARD == HAL_BOARD_SITL)
#define HAL_LOGGING_DATAFLASH_ENABLED HAL_LOGGING_BACKEND_DEFAULT_ENABLED && (CONFIG_HAL_BOARD == HAL_BOARD_SITL)
#endif
#ifndef HAL_LOGGING_MAVLINK_ENABLED
#define HAL_LOGGING_MAVLINK_ENABLED HAL_LOGGING_ENABLED
#define HAL_LOGGING_MAVLINK_ENABLED HAL_LOGGING_BACKEND_DEFAULT_ENABLED
#endif
#ifndef HAL_LOGGING_FILESYSTEM_ENABLED
#define HAL_LOGGING_FILESYSTEM_ENABLED HAL_LOGGING_ENABLED && AP_FILESYSTEM_FILE_WRITING_ENABLED
#define HAL_LOGGING_FILESYSTEM_ENABLED HAL_LOGGING_BACKEND_DEFAULT_ENABLED && AP_FILESYSTEM_FILE_WRITING_ENABLED
#endif
#if HAL_LOGGING_DATAFLASH_ENABLED

View File

@ -1,3 +1,7 @@
#include "AP_Logger_config.h"
#if HAL_LOGGING_ENABLED
#include <stdlib.h>
#include <AP_AHRS/AP_AHRS.h>
@ -561,3 +565,5 @@ void AP_Logger::Write_PSCD(float pos_target, float pos, float vel_desired, float
{
Write_PSCx(LOG_PSCD_MSG, pos_target, pos, vel_desired, vel_target, vel, accel_desired, accel_target, accel);
}
#endif // HAL_LOGGING_ENABLED

View File

@ -1,3 +1,7 @@
#include "AP_Logger_config.h"
#if HAL_LOGGING_ENABLED
#include "AP_Common/AP_FWVersion.h"
#include "LoggerMessageWriter.h"
#include <AP_Scheduler/AP_Scheduler.h>
@ -519,3 +523,5 @@ void LoggerMessageWriter_Write_Polyfence::reset()
}
#endif // !APM_BUILD_TYPE(APM_BUILD_Replay)
#endif // AP_FENCE_ENABLED
#endif // HAL_LOGGING_ENABLED