Browse Source

Rover: remove proximity check from arming checks

it is OK for rovers to be armed very close to objects especially when they are beside the rover
master
Randy Mackay 6 years ago
parent
commit
b64bdcdfda
  1. 12
      APMrover2/AP_Arming.cpp

12
APMrover2/AP_Arming.cpp

@ -88,17 +88,5 @@ bool AP_Arming_Rover::proximity_check(bool report) @@ -88,17 +88,5 @@ bool AP_Arming_Rover::proximity_check(bool report)
return false;
}
// get closest object if we might use it for avoidance
float angle_deg, distance;
if (rover.g2.avoid.proximity_avoidance_enabled() && rover.g2.proximity.get_closest_object(angle_deg, distance)) {
// display error if something is within 60cm
if (distance <= 0.6f) {
if (report) {
gcs().send_text(MAV_SEVERITY_CRITICAL, "PreArm: Proximity %d deg, %4.2fm", static_cast<int32_t>(angle_deg), static_cast<double>(distance));
}
return false;
}
}
return true;
}

Loading…
Cancel
Save