mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-18 06:38:29 -04:00
AP_NavEKF3: allow compilation with HAL_LOGGING_ENABLED false
This commit is contained in:
parent
3a76ce3162
commit
0afed2f8c2
@ -1,3 +1,7 @@
|
||||
#include <AP_Logger/AP_Logger_config.h>
|
||||
|
||||
#if HAL_LOGGING_ENABLED
|
||||
|
||||
#include "AP_NavEKF3.h"
|
||||
#include "AP_NavEKF3_core.h"
|
||||
|
||||
@ -440,3 +444,5 @@ void NavEKF3_core::Log_Write_GSF(uint64_t time_us)
|
||||
}
|
||||
yawEstimator->Log_Write(time_us, LOG_XKY0_MSG, LOG_XKY1_MSG, DAL_CORE(core_index));
|
||||
}
|
||||
|
||||
#endif // HAL_LOGGING_ENABLED
|
||||
|
@ -1394,6 +1394,7 @@ void NavEKF3_core::updateMovementCheck(void)
|
||||
|
||||
if (logStatusChange || imuSampleTime_ms - lastMoveCheckLogTime_ms > 200) {
|
||||
lastMoveCheckLogTime_ms = imuSampleTime_ms;
|
||||
#if HAL_LOGGING_ENABLED
|
||||
const struct log_XKFM pkt{
|
||||
LOG_PACKET_HEADER_INIT(LOG_XKFM_MSG),
|
||||
time_us : dal.micros64(),
|
||||
@ -1405,6 +1406,7 @@ void NavEKF3_core::updateMovementCheck(void)
|
||||
accel_diff_ratio : float(accel_diff_ratio),
|
||||
};
|
||||
AP::logger().WriteBlock(&pkt, sizeof(pkt));
|
||||
#endif
|
||||
}
|
||||
}
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user