AP_Airspeed: use GCS_SEND_TEXT instead of printf for sensor probe messages
This commit is contained in:
parent
e6c7970a19
commit
7f85b413f2
@ -27,6 +27,7 @@
|
||||
#include <AP_HAL/utility/sparse-endian.h>
|
||||
#include <AP_Math/AP_Math.h>
|
||||
#include <AP_Math/crc.h>
|
||||
#include <GCS_MAVLink/GCS.h>
|
||||
|
||||
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;
|
||||
}
|
||||
|
||||
|
@ -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) {
|
||||
|
Loading…
Reference in New Issue
Block a user