mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-23 00:58:37 -04:00
Copter: pre-arm check includes adsb failsafe
This commit is contained in:
parent
68899ed921
commit
df55704875
@ -337,6 +337,14 @@ bool Copter::pre_arm_checks(bool display_failure)
|
|||||||
if (!pre_arm_terrain_check(display_failure)) {
|
if (!pre_arm_terrain_check(display_failure)) {
|
||||||
return false;
|
return false;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
// check adsb avoidance failsafe
|
||||||
|
if (failsafe.adsb) {
|
||||||
|
if (display_failure) {
|
||||||
|
gcs_send_text(MAV_SEVERITY_CRITICAL,"Arm: ADSB threat detected");
|
||||||
|
}
|
||||||
|
return false;
|
||||||
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
// check throttle is above failsafe throttle
|
// check throttle is above failsafe throttle
|
||||||
@ -677,6 +685,16 @@ bool Copter::arm_checks(bool display_failure, bool arming_from_gcs)
|
|||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
// check adsb
|
||||||
|
if ((g.arming_check == ARMING_CHECK_ALL) || (g.arming_check & ARMING_CHECK_PARAMETERS)) {
|
||||||
|
if (failsafe.adsb) {
|
||||||
|
if (display_failure) {
|
||||||
|
gcs_send_text(MAV_SEVERITY_CRITICAL,"PreArm: ADSB threat detected");
|
||||||
|
}
|
||||||
|
return false;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
// check throttle
|
// check throttle
|
||||||
if ((g.arming_check == ARMING_CHECK_ALL) || (g.arming_check & ARMING_CHECK_RC)) {
|
if ((g.arming_check == ARMING_CHECK_ALL) || (g.arming_check & ARMING_CHECK_RC)) {
|
||||||
// check throttle is not too low - must be above failsafe throttle
|
// check throttle is not too low - must be above failsafe throttle
|
||||||
|
Loading…
Reference in New Issue
Block a user