mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-21 23:33:57 -04:00
AP_Airspeed: fixed AP_Periph build
This commit is contained in:
parent
0bdd8231cf
commit
70bb470eb0
@ -115,6 +115,7 @@ bool AP_Airspeed_SDP3X::init()
|
|||||||
|
|
||||||
found = true;
|
found = true;
|
||||||
|
|
||||||
|
#ifndef HAL_NO_GCS
|
||||||
char c = 'X';
|
char c = 'X';
|
||||||
switch (_scale) {
|
switch (_scale) {
|
||||||
case SDP3X_SCALE_PRESSURE_SDP31:
|
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",
|
GCS_SEND_TEXT(MAV_SEVERITY_INFO, "SDP3%c[%u]: Found bus %u addr 0x%02x scale=%u",
|
||||||
get_instance(),
|
get_instance(),
|
||||||
c, get_bus(), addresses[i], _scale);
|
c, get_bus(), addresses[i], _scale);
|
||||||
|
#endif
|
||||||
}
|
}
|
||||||
|
|
||||||
if (!found) {
|
if (!found) {
|
||||||
|
Loading…
Reference in New Issue
Block a user