diff --git a/ArduCopter/motors.pde b/ArduCopter/motors.pde
index e55b16b1ce94d8d3c26568d415e2ecce7578dfdc..725c9e857ebbef037f73218ed67ff9b1a97a5d44 100644
--- a/ArduCopter/motors.pde
+++ b/ArduCopter/motors.pde
@@ -471,6 +471,16 @@ 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 (display_failure) {
+                gcs_send_text_P(SEVERITY_HIGH,PSTR("Arm: Leaning"));
+            }
+            return false;
+        }
+    }
+
     // check if safety switch has been pushed
     if (hal.util->safety_switch_state() == AP_HAL::Util::SAFETY_DISARMED) {
         if (display_failure) {