From 400d080d124eff3f6ec7023920ada983cbd6866e Mon Sep 17 00:00:00 2001 From: Jason Short Date: Thu, 12 Jan 2012 22:25:29 -0800 Subject: [PATCH] added notes --- ArduCopter/system.pde | 16 +++------------- 1 file changed, 3 insertions(+), 13 deletions(-) diff --git a/ArduCopter/system.pde b/ArduCopter/system.pde index b518400297..e1f3537781 100644 --- a/ArduCopter/system.pde +++ b/ArduCopter/system.pde @@ -428,12 +428,6 @@ static void startup_ground(void) static void set_mode(byte mode) { - //if(control_mode == mode){ - // don't switch modes if we are already in the correct mode. - // Serial.print("Double mode\n"); - //return; - //} - // if we don't have GPS lock if(home_is_set == false){ // our max mode should be @@ -458,6 +452,9 @@ static void set_mode(byte mode) // clearing value used in interactive alt hold manual_boost = 0; + // clearing value used to force the copter down in landing mode + landing_boost = 0; + // do not auto_land if we are leaving RTL auto_land_timer = 0; @@ -574,13 +571,6 @@ static void set_mode(byte mode) // We are under manual attitude control // removes the navigation from roll and pitch commands, but leaves the wind compensation reset_nav(); - - #if WIND_COMP_STAB == 1 - if(GPS_enabled){ - wp_control = NO_NAV_MODE; - update_nav_wp(); - } - #endif } Log_Write_Mode(control_mode);