AP_AirSpeed: eliminate GCS_MAVLINK::send_statustext_all
This commit is contained in:
parent
ad7cb6ef32
commit
3214b48f8c
@ -162,7 +162,7 @@ void AP_Airspeed::init()
|
||||
break;
|
||||
}
|
||||
if (sensor && !sensor->init()) {
|
||||
GCS_MAVLINK::send_statustext_all(MAV_SEVERITY_INFO, "Airspeed init failed");
|
||||
gcs().send_text(MAV_SEVERITY_INFO, "Airspeed init failed");
|
||||
delete sensor;
|
||||
sensor = nullptr;
|
||||
}
|
||||
@ -223,9 +223,9 @@ void AP_Airspeed::update_calibration(float raw_pressure)
|
||||
if (AP_HAL::millis() - _cal.start_ms >= 1000 &&
|
||||
_cal.read_count > 15) {
|
||||
if (_cal.count == 0) {
|
||||
GCS_MAVLINK::send_statustext_all(MAV_SEVERITY_INFO, "Airspeed sensor unhealthy");
|
||||
gcs().send_text(MAV_SEVERITY_INFO, "Airspeed sensor unhealthy");
|
||||
} else {
|
||||
GCS_MAVLINK::send_statustext_all(MAV_SEVERITY_INFO, "Airspeed sensor calibrated");
|
||||
gcs().send_text(MAV_SEVERITY_INFO, "Airspeed sensor calibrated");
|
||||
_offset.set_and_save(_cal.sum / _cal.count);
|
||||
}
|
||||
_cal.start_ms = 0;
|
||||
|
Loading…
Reference in New Issue
Block a user