AP_Logger: correct logging when rally disabled

This commit is contained in:
Peter Barker 2023-09-04 20:05:11 +10:00 committed by Peter Barker
parent d27bb9d606
commit 34524d3475
2 changed files with 13 additions and 4 deletions

View File

@ -45,4 +45,7 @@
#define REPLAY_LOG_NEW_MSG_MIN 220 #define REPLAY_LOG_NEW_MSG_MIN 220
#include <AC_Fence/AC_Fence_config.h> #include <AC_Fence/AC_Fence_config.h>
#define HAL_LOGGER_FENCE_ENABLED AP_FENCE_ENABLED #define HAL_LOGGER_FENCE_ENABLED HAL_LOGGING_ENABLED && AP_FENCE_ENABLED
#include <AP_Rally/AP_Rally_config.h>
#define HAL_LOGGER_RALLY_ENABLED HAL_LOGGING_ENABLED && HAL_RALLY_ENABLED

View File

@ -7,6 +7,10 @@
#include <AC_Fence/AC_Fence.h> #include <AC_Fence/AC_Fence.h>
#endif #endif
#if HAL_LOGGER_RALLY_ENABLED
#include <AP_Rally/AP_Rally.h>
#endif
#define FORCE_VERSION_H_INCLUDE #define FORCE_VERSION_H_INCLUDE
#include "ap_version.h" #include "ap_version.h"
#undef FORCE_VERSION_H_INCLUDE #undef FORCE_VERSION_H_INCLUDE
@ -46,7 +50,7 @@ void LoggerMessageWriter_DFLogStart::reset()
#if AP_MISSION_ENABLED #if AP_MISSION_ENABLED
_writeentiremission.reset(); _writeentiremission.reset();
#endif #endif
#if HAL_RALLY_ENABLED #if HAL_LOGGER_RALLY_ENABLED
_writeallrallypoints.reset(); _writeallrallypoints.reset();
#endif #endif
#if HAL_LOGGER_FENCE_ENABLED #if HAL_LOGGER_FENCE_ENABLED
@ -183,7 +187,7 @@ void LoggerMessageWriter_DFLogStart::process()
} }
} }
#endif #endif
#if HAL_RALLY_ENABLED #if HAL_LOGGER_RALLY_ENABLED
if (!_writeallrallypoints.finished()) { if (!_writeallrallypoints.finished()) {
_writeallrallypoints.process(); _writeallrallypoints.process();
if (!_writeallrallypoints.finished()) { if (!_writeallrallypoints.finished()) {
@ -235,7 +239,7 @@ bool LoggerMessageWriter_DFLogStart::writeentiremission()
} }
#endif #endif
#if HAL_RALLY_ENABLED #if HAL_LOGGER_RALLY_ENABLED
bool LoggerMessageWriter_DFLogStart::writeallrallypoints() bool LoggerMessageWriter_DFLogStart::writeallrallypoints()
{ {
if (stage != Stage::DONE) { if (stage != Stage::DONE) {
@ -356,6 +360,7 @@ void LoggerMessageWriter_WriteSysInfo::process() {
_finished = true; // all done! _finished = true; // all done!
} }
#if HAL_LOGGER_RALLY_ENABLED
void LoggerMessageWriter_WriteAllRallyPoints::process() void LoggerMessageWriter_WriteAllRallyPoints::process()
{ {
const AP_Rally *_rally = AP::rally(); const AP_Rally *_rally = AP::rally();
@ -405,6 +410,7 @@ void LoggerMessageWriter_WriteAllRallyPoints::reset()
stage = Stage::WRITE_NEW_RALLY_MESSAGE; stage = Stage::WRITE_NEW_RALLY_MESSAGE;
_rally_number_to_send = 0; _rally_number_to_send = 0;
} }
#endif // HAL_LOGGER_RALLY_ENABLED
void LoggerMessageWriter_WriteEntireMission::process() { void LoggerMessageWriter_WriteEntireMission::process() {
const AP_Mission *_mission = AP::mission(); const AP_Mission *_mission = AP::mission();