mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
Copter: move common proximity pre-arm checks up
It will not be possible to arm if a proximity sensor has been configured but is not working after this patch. The can't-arm-when-within-60cm-of-something check can still be disabled with the PARAMETER arming check bit.
This commit is contained in:
parent
df3a7d32ea
commit
3e098df65a
@ -204,11 +204,6 @@ bool AP_Arming_Copter::parameter_checks(bool display_failure)
|
||||
}
|
||||
#endif
|
||||
|
||||
// check for something close to vehicle
|
||||
if (!pre_arm_proximity_check(display_failure)) {
|
||||
return false;
|
||||
}
|
||||
|
||||
// ensure controllers are OK with us arming:
|
||||
char failure_msg[50];
|
||||
if (!copter.pos_control->pre_arm_checks("PSC", failure_msg, ARRAY_SIZE(failure_msg))) {
|
||||
@ -404,19 +399,17 @@ bool AP_Arming_Copter::pre_arm_terrain_check(bool display_failure)
|
||||
}
|
||||
|
||||
// check nothing is too close to vehicle
|
||||
bool AP_Arming_Copter::pre_arm_proximity_check(bool display_failure)
|
||||
bool AP_Arming_Copter::proximity_checks(bool display_failure) const
|
||||
{
|
||||
#if PROXIMITY_ENABLED == ENABLED
|
||||
|
||||
// return true immediately if no sensor present
|
||||
if (copter.g2.proximity.get_status() == AP_Proximity::Proximity_NotConnected) {
|
||||
return true;
|
||||
if (!AP_Arming::proximity_checks(display_failure)) {
|
||||
return false;
|
||||
}
|
||||
|
||||
// return false if proximity sensor unhealthy
|
||||
if (copter.g2.proximity.get_status() < AP_Proximity::Proximity_Good) {
|
||||
check_failed(ARMING_CHECK_PARAMETERS, display_failure, "check proximity sensor");
|
||||
return false;
|
||||
if (!((checks_to_perform == ARMING_CHECK_ALL) || (checks_to_perform & ARMING_CHECK_PARAMETERS))) {
|
||||
// check is disabled
|
||||
return true;
|
||||
}
|
||||
|
||||
// get closest object if we might use it for avoidance
|
||||
|
@ -31,7 +31,7 @@ protected:
|
||||
bool pre_arm_checks(bool display_failure) override;
|
||||
bool pre_arm_ekf_attitude_check();
|
||||
bool pre_arm_terrain_check(bool display_failure);
|
||||
bool pre_arm_proximity_check(bool display_failure);
|
||||
bool proximity_checks(bool display_failure) const override;
|
||||
bool arm_checks(AP_Arming::Method method) override;
|
||||
|
||||
// NOTE! the following check functions *DO* call into AP_Arming:
|
||||
|
Loading…
Reference in New Issue
Block a user