From eba7d6da9ac6f39d315ae3274b7c643e3669156f Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Tue, 28 May 2013 11:19:28 +1000 Subject: [PATCH] Plane: removed the old crash_timer code This code is less relevent with the new L1 navigation, and could cause issues with the pilot not having control after a long dive. Thanks to Soren for pointing out the issues See issue #305 --- ArduPlane/ArduPlane.pde | 5 ----- ArduPlane/Attitude.pde | 14 -------------- ArduPlane/commands_logic.pde | 1 - ArduPlane/system.pde | 1 - 4 files changed, 21 deletions(-) diff --git a/ArduPlane/ArduPlane.pde b/ArduPlane/ArduPlane.pde index c3ae5a12a3..cac816ee0b 100644 --- a/ArduPlane/ArduPlane.pde +++ b/ArduPlane/ArduPlane.pde @@ -323,9 +323,6 @@ static int16_t failsafe; // Used to track if the value on channel 3 (throtttle) has fallen below the failsafe threshold // RC receiver should be set up to output a low throttle value when signal is lost static bool ch3_failsafe; -// A timer used to help recovery from unusual attitudes. If we enter an unusual attitude -// while in autonomous flight this variable is used to hold roll at 0 for a recovery period -static uint8_t crash_timer; // the time when the last HEARTBEAT message arrived from a GCS static uint32_t last_heartbeat_ms; @@ -1025,7 +1022,6 @@ static void update_GPS(void) static void update_current_flight_mode(void) { if(control_mode == AUTO) { - crash_checker(); switch(nav_command_ID) { case MAV_CMD_NAV_TAKEOFF: @@ -1111,7 +1107,6 @@ static void update_current_flight_mode(void) case RTL: case LOITER: case GUIDED: - crash_checker(); calc_nav_roll(); calc_nav_pitch(); calc_throttle(); diff --git a/ArduPlane/Attitude.pde b/ArduPlane/Attitude.pde index 80c31d5ead..ed3063cf4c 100644 --- a/ArduPlane/Attitude.pde +++ b/ArduPlane/Attitude.pde @@ -63,10 +63,6 @@ static bool stick_mixing_enabled(void) */ static void stabilize_roll(float speed_scaler) { - if (crash_timer > 0) { - nav_roll_cd = 0; - } - if (inverted_flight) { // we want to fly upside down. We need to cope with wrap of // the roll_sensor interfering with wrap of nav_roll, which @@ -279,16 +275,6 @@ static void stabilize() } -static void crash_checker() -{ - if(ahrs.pitch_sensor < -4500) { - crash_timer = 255; - } - if(crash_timer > 0) - crash_timer--; -} - - static void calc_throttle() { if (g.throttle_cruise <= 1) { diff --git a/ArduPlane/commands_logic.pde b/ArduPlane/commands_logic.pde index 3a21db137e..66b28263cf 100644 --- a/ArduPlane/commands_logic.pde +++ b/ArduPlane/commands_logic.pde @@ -232,7 +232,6 @@ static bool verify_condition_command() // Returns true if command compl static void do_RTL(void) { control_mode = RTL; - crash_timer = 0; next_WP = home; if (g.loiter_radius < 0) { diff --git a/ArduPlane/system.pde b/ArduPlane/system.pde index 1613e50cf7..9e6283cafe 100644 --- a/ArduPlane/system.pde +++ b/ArduPlane/system.pde @@ -324,7 +324,6 @@ static void set_mode(enum FlightMode mode) trim_control_surfaces(); control_mode = mode; - crash_timer = 0; switch(control_mode) {