From 2ac29effe971329efe4535222708b6219ecf23ec Mon Sep 17 00:00:00 2001 From: Jason Short Date: Sun, 11 Mar 2012 22:43:25 -0700 Subject: [PATCH] ACM: The I term in update_nav_wp with the no_nav condition was pulling from the wrong PID loop and was essentially 0 all the time. --- ArduCopter/ArduCopter.pde | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/ArduCopter/ArduCopter.pde b/ArduCopter/ArduCopter.pde index 7db27efdc6..c9f21fd94f 100644 --- a/ArduCopter/ArduCopter.pde +++ b/ArduCopter/ArduCopter.pde @@ -2202,8 +2202,8 @@ static void update_nav_wp() // or change Loiter position // We bring copy over our Iterms for wind control, but we don't navigate - nav_lon = g.pi_loiter_lon.get_integrator(); - nav_lat = g.pi_loiter_lat.get_integrator(); + nav_lon = g.pid_loiter_rate_lon.get_integrator(); + nav_lat = g.pid_loiter_rate_lon.get_integrator(); // rotate pitch and roll to the copter frame of reference calc_loiter_pitch_roll();