diff --git a/ArduCopter/motors.pde b/ArduCopter/motors.pde index d58e64a150..584aa43d5e 100644 --- a/ArduCopter/motors.pde +++ b/ArduCopter/motors.pde @@ -469,7 +469,7 @@ static bool arm_checks(bool display_failure) // check lean angle if ((g.arming_check == ARMING_CHECK_ALL) || (g.arming_check & ARMING_CHECK_INS)) { - if (labs(ahrs.roll_sensor) > g.angle_max || labs(ahrs.pitch_sensor) > g.angle_max) { + if (labs(ahrs.roll_sensor) > aparm.angle_max || labs(ahrs.pitch_sensor) > aparm.angle_max) { if (display_failure) { gcs_send_text_P(SEVERITY_HIGH,PSTR("Arm: Leaning")); }