diff --git a/ArduCopter/AP_State.pde b/ArduCopter/AP_State.pde index 4395965ff6..63ccaa975e 100644 --- a/ArduCopter/AP_State.pde +++ b/ArduCopter/AP_State.pde @@ -93,19 +93,6 @@ static void set_failsafe_gcs(bool b) failsafe.gcs = b; } -// --------------------------------------------- -void set_takeoff_complete(bool b) -{ - // if no change, exit immediately - if( ap.takeoff_complete == b ) - return; - - if(b){ - Log_Write_Event(DATA_TAKEOFF); - } - ap.takeoff_complete = b; -} - // --------------------------------------------- void set_land_complete(bool b) { diff --git a/ArduCopter/ArduCopter.pde b/ArduCopter/ArduCopter.pde index bab728fc4b..ab5abb4977 100644 --- a/ArduCopter/ArduCopter.pde +++ b/ArduCopter/ArduCopter.pde @@ -409,14 +409,13 @@ static union { uint8_t logging_started : 1; // 6 // true if dataflash logging has started uint8_t do_flip : 1; // 7 // Used to enable flip code - uint8_t takeoff_complete : 1; // 8 - uint8_t land_complete : 1; // 9 // true if we have detected a landing + uint8_t land_complete : 1; // 8 // true if we have detected a landing - uint8_t new_radio_frame : 1; // 10 // Set true if we have new PWM data to act on from the Radio - uint8_t CH7_flag : 2; // 11,12 // ch7 aux switch : 0 is low or false, 1 is center or true, 2 is high - uint8_t CH8_flag : 2; // 13,14 // ch8 aux switch : 0 is low or false, 1 is center or true, 2 is high - uint8_t usb_connected : 1; // 15 // true if APM is powered from USB connection - uint8_t yaw_stopped : 1; // 16 // Used to manage the Yaw hold capabilities + uint8_t new_radio_frame : 1; // 9 // Set true if we have new PWM data to act on from the Radio + uint8_t CH7_flag : 2; // 10,11 // ch7 aux switch : 0 is low or false, 1 is center or true, 2 is high + uint8_t CH8_flag : 2; // 12,13 // ch8 aux switch : 0 is low or false, 1 is center or true, 2 is high + uint8_t usb_connected : 1; // 14 // true if APM is powered from USB connection + uint8_t yaw_stopped : 1; // 15 // Used to manage the Yaw hold capabilities uint8_t disable_stab_rate_limit : 1; // 17 // disables limits rate request from the stability controller @@ -1772,14 +1771,6 @@ void update_throttle_mode(void) #else update_throttle_cruise(pilot_throttle_scaled); #endif //HELI_FRAME - - // check if we've taken off yet - if (!ap.takeoff_complete && motors.armed()) { - if (pilot_throttle_scaled > g.throttle_cruise) { - // we must be in the air by now - set_takeoff_complete(true); - } - } } set_target_alt_for_reporting(0); break; @@ -1798,13 +1789,6 @@ void update_throttle_mode(void) #else update_throttle_cruise(pilot_throttle_scaled); #endif //HELI_FRAME - - if (!ap.takeoff_complete && motors.armed()) { - if (pilot_throttle_scaled > g.throttle_cruise) { - // we must be in the air by now - set_takeoff_complete(true); - } - } } set_target_alt_for_reporting(0); break; diff --git a/ArduCopter/commands_logic.pde b/ArduCopter/commands_logic.pde index fc49787908..ca493e1137 100644 --- a/ArduCopter/commands_logic.pde +++ b/ArduCopter/commands_logic.pde @@ -376,7 +376,6 @@ static void do_loiter_time() static bool verify_takeoff() { // have we reached our target altitude? - set_takeoff_complete(wp_nav.reached_wp_destination()); return wp_nav.reached_wp_destination(); } diff --git a/ArduCopter/control_modes.pde b/ArduCopter/control_modes.pde index 60f702089d..a772d4097d 100644 --- a/ArduCopter/control_modes.pde +++ b/ArduCopter/control_modes.pde @@ -146,7 +146,7 @@ static void do_aux_switch_function(int8_t ch_function, uint8_t ch_flag) switch(tmp_function) { case AUX_SWITCH_FLIP: // flip if switch is on, positive throttle and we're actually flying - if((ch_flag == AUX_SWITCH_HIGH) && (g.rc_3.control_in >= 0) && ap.takeoff_complete) { + if((ch_flag == AUX_SWITCH_HIGH) && (g.rc_3.control_in >= 0) && !ap.land_complete) { init_flip(); } break; diff --git a/ArduCopter/motors.pde b/ArduCopter/motors.pde index 583f4dc6d3..e723b1368f 100644 --- a/ArduCopter/motors.pde +++ b/ArduCopter/motors.pde @@ -520,7 +520,7 @@ static void init_disarm_motors() #endif // we are not in the air - set_takeoff_complete(false); + set_land_complete(true); // setup fast AHRS gains to get right attitude ahrs.set_fast_gains(true);