diff --git a/libraries/AP_Airspeed/AP_Airspeed_MS5525.cpp b/libraries/AP_Airspeed/AP_Airspeed_MS5525.cpp index a646714a5a..21af06e2f5 100644 --- a/libraries/AP_Airspeed/AP_Airspeed_MS5525.cpp +++ b/libraries/AP_Airspeed/AP_Airspeed_MS5525.cpp @@ -27,6 +27,7 @@ #include #include #include +#include extern const AP_HAL::HAL &hal; @@ -79,13 +80,13 @@ bool AP_Airspeed_MS5525::init() found = read_prom(); if (found) { - printf("MS5525: Found sensor on bus %u address 0x%02x\n", get_bus(), addresses[i]); + GCS_SEND_TEXT(MAV_SEVERITY_INFO, "MS5525[%u]: Found on bus %u addr 0x%02x", get_instance(), get_bus(), addresses[i]); break; } dev->get_semaphore()->give(); } if (!found) { - printf("MS5525: no sensor found\n"); + GCS_SEND_TEXT(MAV_SEVERITY_INFO, "MS5525[%u]: no sensor found", get_instance()); return false; } diff --git a/libraries/AP_Airspeed/AP_Airspeed_SDP3X.cpp b/libraries/AP_Airspeed/AP_Airspeed_SDP3X.cpp index b68ef886fa..94739acf1f 100644 --- a/libraries/AP_Airspeed/AP_Airspeed_SDP3X.cpp +++ b/libraries/AP_Airspeed/AP_Airspeed_SDP3X.cpp @@ -127,8 +127,9 @@ bool AP_Airspeed_SDP3X::init() c = '3'; break; } - hal.console->printf("SDP3%c: Found on bus %u address 0x%02x scale=%u\n", - c, get_bus(), addresses[i], _scale); + 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); } if (!found) {