diff --git a/ArduCopter/motors.pde b/ArduCopter/motors.pde index a3d50b5811..e7bf738bb9 100644 --- a/ArduCopter/motors.pde +++ b/ArduCopter/motors.pde @@ -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")); }