From 123ce533bbacbd4bcbb0301f98933bc6655e6e16 Mon Sep 17 00:00:00 2001 From: Jason Short Date: Tue, 3 Jan 2012 22:50:33 -0800 Subject: [PATCH] Added precalc for wind compensation when entering Stabilze mode --- ArduCopter/system.pde | 8 ++++++-- 1 file changed, 6 insertions(+), 2 deletions(-) diff --git a/ArduCopter/system.pde b/ArduCopter/system.pde index 4e6874ec98..3d1cb57cad 100644 --- a/ArduCopter/system.pde +++ b/ArduCopter/system.pde @@ -525,8 +525,9 @@ static void set_mode(byte mode) // reset all of the throttle iterms g.pi_alt_hold.reset_I(); g.pi_throttle.reset_I(); - }else { // an automatic throttle + }else { + // an automatic throttle // todo: replace with a throttle cruise estimator init_throttle_cruise(); } @@ -537,7 +538,10 @@ static void set_mode(byte mode) reset_nav(); // removes the navigation from roll and pitch commands, but leaves the wind compensation - calc_wind_compensation(); + if(GPS_enabled) + wp_control = NO_NAV_MODE; + update_nav_wp(); + } Log_Write_Mode(control_mode);