Copter: use circular limit on tilt angle for arm check

This commit is contained in:
Jonathan Challinger 2015-04-22 17:06:23 -07:00 committed by Randy Mackay
parent b55367ccc7
commit e5b6cf9966

View File

@ -625,7 +625,7 @@ static bool arm_checks(bool display_failure, bool arming_from_gcs)
// 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 (labs(ahrs.roll_sensor) > aparm.angle_max || labs(ahrs.pitch_sensor) > aparm.angle_max) { if (degrees(acosf(ahrs.cos_roll()*ahrs.cos_pitch()))*100.0f > aparm.angle_max) {
if (display_failure) { if (display_failure) {
gcs_send_text_P(SEVERITY_HIGH,PSTR("Arm: Leaning")); gcs_send_text_P(SEVERITY_HIGH,PSTR("Arm: Leaning"));
} }