GCS_MAVLink: make logging dependent on HAL_LOGGING_ENABLED not HAL_BUILD_AP_PERIPH

This commit is contained in:
Peter Barker 2021-11-23 18:52:01 +11:00 committed by Andrew Tridgell
parent 8973dfa8e0
commit f461605d88

View File

@ -210,18 +210,27 @@ void GCS::update_sensor_status_flags()
}
#endif
#if !defined(HAL_BUILD_AP_PERIPH) || (defined(HAL_LOGGING_ENABLED) && (HAL_LOGGING_ENABLED == 1) && defined(HAL_PERIPH_ENABLE_GPS))
#if HAL_LOGGING_ENABLED
const AP_Logger &logger = AP::logger();
if (logger.logging_present() || gps.logging_present()) { // primary logging only (usually File)
bool logging_present = logger.logging_present();
bool logging_enabled = logger.logging_enabled();
bool logging_healthy = !logger.logging_failed();
#if !defined(HAL_BUILD_AP_PERIPH) || defined(HAL_PERIPH_ENABLE_GPS)
// some GPS units do logging, so they have to be healthy too:
logging_present |= gps.logging_present();
logging_enabled |= gps.logging_enabled();
logging_healthy &= !gps.logging_failed();
#endif
if (logging_present) {
control_sensors_present |= MAV_SYS_STATUS_LOGGING;
}
if (logger.logging_enabled() || gps.logging_enabled()) {
if (logging_enabled) {
control_sensors_enabled |= MAV_SYS_STATUS_LOGGING;
}
if (!logger.logging_failed() && !gps.logging_failed()) {
if (logging_healthy) {
control_sensors_health |= MAV_SYS_STATUS_LOGGING;
}
#endif
#endif // HAL_LOGGING_ENABLED
// set motors outputs as enabled if safety switch is not disarmed (i.e. either NONE or ARMED)
#if !defined(HAL_BUILD_AP_PERIPH)