Browse Source

Copter: use circular limit on tilt angle for arm check

master
Jonathan Challinger 10 years ago committed by Randy Mackay
parent
commit
e5b6cf9966
  1. 2
      ArduCopter/motors.pde

2
ArduCopter/motors.pde

@ -625,7 +625,7 @@ static bool arm_checks(bool display_failure, bool arming_from_gcs) @@ -625,7 +625,7 @@ static bool arm_checks(bool display_failure, bool arming_from_gcs)
// check lean angle
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) {
gcs_send_text_P(SEVERITY_HIGH,PSTR("Arm: Leaning"));
}

Loading…
Cancel
Save