AP_DAL: allow compilation with HAL_LOGGING_ENABLED false
This commit is contained in:
parent
4b30963d1d
commit
8828659b33
@ -38,11 +38,13 @@ void AP_DAL::start_frame(AP_DAL::FrameType frametype)
|
|||||||
_last_imu_time_us = imu_us;
|
_last_imu_time_us = imu_us;
|
||||||
|
|
||||||
// we force write all msgs when logging starts
|
// we force write all msgs when logging starts
|
||||||
|
#if HAL_LOGGING_ENABLED
|
||||||
bool logging = AP::logger().logging_started() && AP::logger().allow_start_ekf();
|
bool logging = AP::logger().logging_started() && AP::logger().allow_start_ekf();
|
||||||
if (logging && !logging_started) {
|
if (logging && !logging_started) {
|
||||||
force_write = true;
|
force_write = true;
|
||||||
}
|
}
|
||||||
logging_started = logging;
|
logging_started = logging;
|
||||||
|
#endif
|
||||||
|
|
||||||
end_frame();
|
end_frame();
|
||||||
|
|
||||||
@ -280,6 +282,7 @@ uint8_t AP_DAL::logging_core(uint8_t c) const
|
|||||||
#endif
|
#endif
|
||||||
}
|
}
|
||||||
|
|
||||||
|
#if HAL_LOGGING_ENABLED
|
||||||
// write out a DAL log message. If old_msg is non-null, then
|
// write out a DAL log message. If old_msg is non-null, then
|
||||||
// only write if the content has changed
|
// only write if the content has changed
|
||||||
void AP_DAL::WriteLogMessage(enum LogMessages msg_type, void *msg, const void *old_msg, uint8_t msg_size)
|
void AP_DAL::WriteLogMessage(enum LogMessages msg_type, void *msg, const void *old_msg, uint8_t msg_size)
|
||||||
@ -301,6 +304,7 @@ void AP_DAL::WriteLogMessage(enum LogMessages msg_type, void *msg, const void *o
|
|||||||
_end = 0;
|
_end = 0;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
#endif
|
||||||
|
|
||||||
/*
|
/*
|
||||||
check if we are low on CPU for this core. This needs to capture the
|
check if we are low on CPU for this core. This needs to capture the
|
||||||
|
@ -324,9 +324,11 @@ public:
|
|||||||
// map core number for replay
|
// map core number for replay
|
||||||
uint8_t logging_core(uint8_t c) const;
|
uint8_t logging_core(uint8_t c) const;
|
||||||
|
|
||||||
|
#if HAL_LOGGING_ENABLED
|
||||||
// write out a DAL log message. If old_msg is non-null, then
|
// write out a DAL log message. If old_msg is non-null, then
|
||||||
// only write if the content has changed
|
// only write if the content has changed
|
||||||
static void WriteLogMessage(enum LogMessages msg_type, void *msg, const void *old_msg, uint8_t msg_size);
|
static void WriteLogMessage(enum LogMessages msg_type, void *msg, const void *old_msg, uint8_t msg_size);
|
||||||
|
#endif
|
||||||
|
|
||||||
private:
|
private:
|
||||||
|
|
||||||
@ -376,10 +378,15 @@ private:
|
|||||||
bool init_done;
|
bool init_done;
|
||||||
};
|
};
|
||||||
|
|
||||||
|
#if HAL_LOGGING_ENABLED
|
||||||
#define WRITE_REPLAY_BLOCK(sname,v) AP_DAL::WriteLogMessage(LOG_## sname ##_MSG, &v, nullptr, offsetof(log_ ##sname, _end))
|
#define WRITE_REPLAY_BLOCK(sname,v) AP_DAL::WriteLogMessage(LOG_## sname ##_MSG, &v, nullptr, offsetof(log_ ##sname, _end))
|
||||||
#define WRITE_REPLAY_BLOCK_IFCHANGED(sname,v,old) do { static_assert(sizeof(v) == sizeof(old), "types must match"); \
|
#define WRITE_REPLAY_BLOCK_IFCHANGED(sname,v,old) do { static_assert(sizeof(v) == sizeof(old), "types must match"); \
|
||||||
AP_DAL::WriteLogMessage(LOG_## sname ##_MSG, &v, &old, offsetof(log_ ##sname, _end)); } \
|
AP_DAL::WriteLogMessage(LOG_## sname ##_MSG, &v, &old, offsetof(log_ ##sname, _end)); } \
|
||||||
while (0)
|
while (0)
|
||||||
|
#else
|
||||||
|
#define WRITE_REPLAY_BLOCK(sname,v) do { (void)v; } while (false)
|
||||||
|
#define WRITE_REPLAY_BLOCK_IFCHANGED(sname,v,old) do { (void)old; } while (false)
|
||||||
|
#endif
|
||||||
|
|
||||||
namespace AP {
|
namespace AP {
|
||||||
AP_DAL &dal();
|
AP_DAL &dal();
|
||||||
|
Loading…
Reference in New Issue
Block a user