diff --git a/libraries/AP_Airspeed/AP_Airspeed.cpp b/libraries/AP_Airspeed/AP_Airspeed.cpp index 3091e79fdb..195c656ab6 100644 --- a/libraries/AP_Airspeed/AP_Airspeed.cpp +++ b/libraries/AP_Airspeed/AP_Airspeed.cpp @@ -598,7 +598,7 @@ void AP_Airspeed::update(bool log) read(i); } -#ifndef HAL_NO_GCS +#if HAL_GCS_ENABLED // debugging until we get MAVLink support for 2nd airspeed sensor if (enabled(1)) { gcs().send_named_float("AS2", get_airspeed(1)); diff --git a/libraries/AP_Airspeed/AP_Airspeed_SDP3X.cpp b/libraries/AP_Airspeed/AP_Airspeed_SDP3X.cpp index 5c79c00082..2260ddff07 100644 --- a/libraries/AP_Airspeed/AP_Airspeed_SDP3X.cpp +++ b/libraries/AP_Airspeed/AP_Airspeed_SDP3X.cpp @@ -115,7 +115,7 @@ bool AP_Airspeed_SDP3X::init() found = true; -#ifndef HAL_NO_GCS +#if HAL_GCS_ENABLED char c = 'X'; switch (_scale) { case SDP3X_SCALE_PRESSURE_SDP31: