diff --git a/libraries/AP_Airspeed/AP_Airspeed.cpp b/libraries/AP_Airspeed/AP_Airspeed.cpp index 127185b897..1615c59dd0 100644 --- a/libraries/AP_Airspeed/AP_Airspeed.cpp +++ b/libraries/AP_Airspeed/AP_Airspeed.cpp @@ -308,7 +308,7 @@ bool AP_Airspeed::add_backend(AP_Airspeed_Backend *backend) const uint8_t i = num_sensors; sensor[num_sensors++] = backend; if (!sensor[i]->init()) { - GCS_SEND_TEXT(MAV_SEVERITY_INFO, "Airspeed %u init failed", i+1); + GCS_SEND_TEXT(MAV_SEVERITY_ERROR, "Airspeed %u init failed", i+1); delete sensor[i]; sensor[i] = nullptr; } @@ -431,7 +431,7 @@ void AP_Airspeed::init() break; } if (sensor[i] && !sensor[i]->init()) { - GCS_SEND_TEXT(MAV_SEVERITY_INFO, "Airspeed %u init failed", i + 1); + GCS_SEND_TEXT(MAV_SEVERITY_ERROR, "Airspeed %u init failed", i + 1); delete sensor[i]; sensor[i] = nullptr; } @@ -487,7 +487,7 @@ void AP_Airspeed::calibrate(bool in_startup) continue; } if (sensor[i] == nullptr) { - GCS_SEND_TEXT(MAV_SEVERITY_INFO,"Airspeed %u not initalized, cannot cal", i+1); + GCS_SEND_TEXT(MAV_SEVERITY_ERROR, "Airspeed %u not initalized, cannot cal", i+1); continue; } state[i].cal.start_ms = AP_HAL::millis(); @@ -512,7 +512,7 @@ void AP_Airspeed::update_calibration(uint8_t i, float raw_pressure) if (AP_HAL::millis() - state[i].cal.start_ms >= 1000 && state[i].cal.read_count > 15) { if (state[i].cal.count == 0) { - GCS_SEND_TEXT(MAV_SEVERITY_INFO, "Airspeed %u unhealthy", i + 1); + GCS_SEND_TEXT(MAV_SEVERITY_WARNING, "Airspeed %u unhealthy", i + 1); } else { GCS_SEND_TEXT(MAV_SEVERITY_INFO, "Airspeed %u calibrated", i + 1); param[i].offset.set_and_save(state[i].cal.sum / state[i].cal.count); diff --git a/libraries/AP_Airspeed/AP_Airspeed_MS4525.cpp b/libraries/AP_Airspeed/AP_Airspeed_MS4525.cpp index 7eb9ef15e5..7524103110 100644 --- a/libraries/AP_Airspeed/AP_Airspeed_MS4525.cpp +++ b/libraries/AP_Airspeed/AP_Airspeed_MS4525.cpp @@ -86,7 +86,7 @@ bool AP_Airspeed_MS4525::init() } } - GCS_SEND_TEXT(MAV_SEVERITY_INFO, "MS4525[%u]: no sensor found", get_instance()); + GCS_SEND_TEXT(MAV_SEVERITY_ERROR, "MS4525[%u]: no sensor found", get_instance()); return false; found_sensor: diff --git a/libraries/AP_Airspeed/AP_Airspeed_MS5525.cpp b/libraries/AP_Airspeed/AP_Airspeed_MS5525.cpp index f22117c940..a23c2a8cdd 100644 --- a/libraries/AP_Airspeed/AP_Airspeed_MS5525.cpp +++ b/libraries/AP_Airspeed/AP_Airspeed_MS5525.cpp @@ -85,7 +85,7 @@ bool AP_Airspeed_MS5525::init() } } if (!found) { - GCS_SEND_TEXT(MAV_SEVERITY_INFO, "MS5525[%u]: no sensor found", get_instance()); + GCS_SEND_TEXT(MAV_SEVERITY_ERROR, "MS5525[%u]: no sensor found", get_instance()); return false; }