mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-25 10:08:28 -04:00
Copter: add arming check of fence
This commit is contained in:
parent
f4a9f9876f
commit
fbe0e5dfb3
@ -727,6 +727,16 @@ bool Copter::arm_checks(bool display_failure, bool arming_from_gcs)
|
|||||||
return false;
|
return false;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
#if AC_FENCE == ENABLED
|
||||||
|
// check vehicle is within fence
|
||||||
|
if(!fence.pre_arm_check()) {
|
||||||
|
if (display_failure) {
|
||||||
|
gcs_send_text_P(SEVERITY_HIGH,PSTR("Arm: check fence"));
|
||||||
|
}
|
||||||
|
return false;
|
||||||
|
}
|
||||||
|
#endif
|
||||||
|
|
||||||
// check lean angle
|
// check lean angle
|
||||||
if ((g.arming_check == ARMING_CHECK_ALL) || (g.arming_check & ARMING_CHECK_INS)) {
|
if ((g.arming_check == ARMING_CHECK_ALL) || (g.arming_check & ARMING_CHECK_INS)) {
|
||||||
if (degrees(acosf(ahrs.cos_roll()*ahrs.cos_pitch()))*100.0f > aparm.angle_max) {
|
if (degrees(acosf(ahrs.cos_roll()*ahrs.cos_pitch()))*100.0f > aparm.angle_max) {
|
||||||
|
Loading…
Reference in New Issue
Block a user