mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-02 05:58:30 -04:00
AP_Arming: correct proximity pre-arm check msg
This commit is contained in:
parent
63a21c6c12
commit
1858fbe951
@ -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;
|
||||
}
|
||||
}
|
||||
|
Loading…
Reference in New Issue
Block a user