GCS_MAVLink: Send GPS logging as part of the logging status bits
This commit is contained in:
parent
f8808022b8
commit
7582a5b4a4
@ -7,6 +7,7 @@
|
||||
#include <AP_Scheduler/AP_Scheduler.h>
|
||||
#include <AP_Baro/AP_Baro.h>
|
||||
#include <AP_AHRS/AP_AHRS.h>
|
||||
#include <AP_GPS/AP_GPS.h>
|
||||
|
||||
extern const AP_HAL::HAL& hal;
|
||||
|
||||
@ -155,13 +156,14 @@ void GCS::update_sensor_status_flags()
|
||||
}
|
||||
|
||||
const AP_Logger &logger = AP::logger();
|
||||
if (logger.logging_present()) { // primary logging only (usually File)
|
||||
const AP_GPS &gps = AP::gps();
|
||||
if (logger.logging_present() || gps.logging_present()) { // primary logging only (usually File)
|
||||
control_sensors_present |= MAV_SYS_STATUS_LOGGING;
|
||||
}
|
||||
if (logger.logging_enabled()) {
|
||||
if (logger.logging_enabled() || gps.logging_enabled()) {
|
||||
control_sensors_enabled |= MAV_SYS_STATUS_LOGGING;
|
||||
}
|
||||
if (!logger.logging_failed()) {
|
||||
if (!logger.logging_failed() && !gps.logging_failed()) {
|
||||
control_sensors_health |= MAV_SYS_STATUS_LOGGING;
|
||||
}
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user