From c238645e538dfc72523cc039fe5f527f605de99f Mon Sep 17 00:00:00 2001 From: Tom Pittenger Date: Tue, 12 Apr 2016 11:54:08 -0700 Subject: [PATCH] Plane: limit roll before calculating load factor --- ArduPlane/Attitude.cpp | 3 +-- 1 file changed, 1 insertion(+), 2 deletions(-) diff --git a/ArduPlane/Attitude.cpp b/ArduPlane/Attitude.cpp index 7b0f0a5189..779c835367 100644 --- a/ArduPlane/Attitude.cpp +++ b/ArduPlane/Attitude.cpp @@ -513,9 +513,8 @@ void Plane::calc_nav_pitch() */ void Plane::calc_nav_roll() { - nav_roll_cd = nav_controller->nav_roll_cd(); + nav_roll_cd = constrain_int32(nav_controller->nav_roll_cd(), -roll_limit_cd, roll_limit_cd); update_load_factor(); - nav_roll_cd = constrain_int32(nav_roll_cd, -roll_limit_cd, roll_limit_cd); }