mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
Copter: arming check ignores proximity if avoidance disabled
This commit is contained in:
parent
e7f2c9870a
commit
dbbf6cae5c
@ -620,9 +620,9 @@ bool Copter::pre_arm_proximity_check(bool display_failure)
|
|||||||
return false;
|
return false;
|
||||||
}
|
}
|
||||||
|
|
||||||
// get closest object
|
// get closest object if we might use it for avoidance
|
||||||
float angle_deg, distance;
|
float angle_deg, distance;
|
||||||
if (g2.proximity.get_closest_object(angle_deg, distance)) {
|
if (avoid.proximity_avoidance_enabled() && g2.proximity.get_closest_object(angle_deg, distance)) {
|
||||||
// display error if something is within 60cm
|
// display error if something is within 60cm
|
||||||
if (distance <= 0.6f) {
|
if (distance <= 0.6f) {
|
||||||
if (display_failure) {
|
if (display_failure) {
|
||||||
|
Loading…
Reference in New Issue
Block a user