From aa8e5b0aefe29aad90cc4971a5e73029c121f664 Mon Sep 17 00:00:00 2001
From: Randy Mackay <rmackay9@yahoo.com>
Date: Mon, 14 Jan 2013 14:26:26 +0900
Subject: [PATCH] Copter: constrain auto roll and pitch to 45 degrees

---
 ArduCopter/navigation.pde | 4 ++++
 1 file changed, 4 insertions(+)

diff --git a/ArduCopter/navigation.pde b/ArduCopter/navigation.pde
index 396643dce..229c5e8f9 100644
--- a/ArduCopter/navigation.pde
+++ b/ArduCopter/navigation.pde
@@ -592,6 +592,10 @@ static void calc_nav_pitch_roll()
 
     // flip pitch because forward is negative
     auto_pitch = -auto_pitch;
+
+    // constrain maximum roll and pitch angles to 45 degrees
+    auto_roll = constrain(auto_roll, -4500, 4500);
+    auto_pitch = constrain(auto_pitch, -4500, 4500);
 }
 
 static int16_t get_desired_speed(int16_t max_speed)
-- 
GitLab