diff --git a/ArduCopter/navigation.pde b/ArduCopter/navigation.pde index 396643dceb452b7e179417323ef4dc620e84ae06..229c5e8f9a809e51ed32bde2592d380739f7ef04 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)