diff --git a/ArduCopter/AP_Arming.cpp b/ArduCopter/AP_Arming.cpp index b39c460f91..4f19e6b4d1 100644 --- a/ArduCopter/AP_Arming.cpp +++ b/ArduCopter/AP_Arming.cpp @@ -494,7 +494,7 @@ bool AP_Arming_Copter::proximity_checks(bool display_failure) const // display error if something is within 60cm const float tolerance = 0.6f; if (distance <= tolerance) { - check_failed(ARMING_CHECK_PARAMETERS, display_failure, "Proximity %d deg, %4.2fm (want <= %0.2fm)", (int)angle_deg, (double)distance, (double)tolerance); + check_failed(ARMING_CHECK_PARAMETERS, display_failure, "Proximity %d deg, %4.2fm (want > %0.1fm)", (int)angle_deg, (double)distance, (double)tolerance); return false; } }