AP_Airspeed: fixed AP_Periph build

This commit is contained in:
Andrew Tridgell 2021-06-30 12:55:10 +10:00
parent 0bdd8231cf
commit 70bb470eb0

View File

@ -115,6 +115,7 @@ bool AP_Airspeed_SDP3X::init()
found = true;
#ifndef HAL_NO_GCS
char c = 'X';
switch (_scale) {
case SDP3X_SCALE_PRESSURE_SDP31:
@ -130,6 +131,7 @@ bool AP_Airspeed_SDP3X::init()
GCS_SEND_TEXT(MAV_SEVERITY_INFO, "SDP3%c[%u]: Found bus %u addr 0x%02x scale=%u",
get_instance(),
c, get_bus(), addresses[i], _scale);
#endif
}
if (!found) {