diff --git a/libraries/AP_ADSB/AP_ADSB.cpp b/libraries/AP_ADSB/AP_ADSB.cpp index 9d82e541a4f92..9c3e9dcee58bb 100644 --- a/libraries/AP_ADSB/AP_ADSB.cpp +++ b/libraries/AP_ADSB/AP_ADSB.cpp @@ -828,17 +828,17 @@ bool AP_ADSB::get_vehicle_by_ICAO(const uint32_t icao, adsb_vehicle_t &vehicle) */ void AP_ADSB::write_log(const adsb_vehicle_t &vehicle) const { - switch (_log) { - case logging::SPECIAL_ONLY: + switch ((Logging)_log) { + case Logging::SPECIAL_ONLY: if (!is_special_vehicle(vehicle.info.ICAO_address)) { return; } break; - case logging::ALL: + case Logging::ALL: break; - case logging::NONE: + case Logging::NONE: default: return; } diff --git a/libraries/AP_ADSB/AP_ADSB.h b/libraries/AP_ADSB/AP_ADSB.h index f9210a559a6b6..91ecee728c109 100644 --- a/libraries/AP_ADSB/AP_ADSB.h +++ b/libraries/AP_ADSB/AP_ADSB.h @@ -288,13 +288,13 @@ class AP_ADSB { void push_sample(const adsb_vehicle_t &vehicle); // logging - AP_Int8 _log; void write_log(const adsb_vehicle_t &vehicle) const; - enum logging { + enum class Logging { NONE = 0, SPECIAL_ONLY = 1, ALL = 2 }; + AP_Enum _log; // reference to backend AP_ADSB_Backend *_backend[ADSB_MAX_INSTANCES];