AP_Airspeed: move from HAL_NO_GCS to HAL_GCS_ENABLED

This commit is contained in:
Peter Barker 2021-08-18 21:42:16 +10:00 committed by Peter Barker
parent 8f6bed23cf
commit 22e9ad4818
2 changed files with 2 additions and 2 deletions

View File

@ -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));

View File

@ -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: