From b34664ea07708e0e4cf283f7ca2ef99c3e44d200 Mon Sep 17 00:00:00 2001 From: Randy Mackay Date: Fri, 10 Jan 2014 16:21:10 +0900 Subject: [PATCH] Copter: remove unused altitude error --- ArduCopter/ArduCopter.pde | 10 ---------- ArduCopter/Attitude.pde | 3 --- 2 files changed, 13 deletions(-) diff --git a/ArduCopter/ArduCopter.pde b/ArduCopter/ArduCopter.pde index 064527df92..d701c02177 100644 --- a/ArduCopter/ArduCopter.pde +++ b/ArduCopter/ArduCopter.pde @@ -641,8 +641,6 @@ static AP_BattMonitor battery; //////////////////////////////////////////////////////////////////////////////// // The (throttle) controller desired altitude in cm static float controller_desired_alt; -// The cm we are off in altitude from next_WP.alt – Positive value means we are below the WP -static int32_t altitude_error; // The cm/s we are moving up or down based on filtered data - Positive = UP static int16_t climb_rate; // The altitude as reported by Sonar in cm – Values are 20 to 700 generally. @@ -1915,7 +1913,6 @@ bool set_throttle_mode( uint8_t new_throttle_mode ) case THROTTLE_MANUAL: case THROTTLE_MANUAL_TILT_COMPENSATED: throttle_accel_deactivate(); // this controller does not use accel based throttle controller - altitude_error = 0; // clear altitude error reported to GCS throttle_initialised = true; break; @@ -1939,7 +1936,6 @@ bool set_throttle_mode( uint8_t new_throttle_mode ) #if FRAME_CONFIG == HELI_FRAME case THROTTLE_MANUAL_HELI: throttle_accel_deactivate(); // this controller does not use accel based throttle controller - altitude_error = 0; // clear altitude error reported to GCS throttle_initialised = true; break; #endif @@ -2117,12 +2113,6 @@ static void set_target_alt_for_reporting(float alt_cm) target_alt_for_reporting = alt_cm; } -// get_target_alt_for_reporting - returns target altitude in cm for reporting purposes (logs and gcs) -static float get_target_alt_for_reporting() -{ - return target_alt_for_reporting; -} - static void read_AHRS(void) { // Perform IMU calculations and get attitude info diff --git a/ArduCopter/Attitude.pde b/ArduCopter/Attitude.pde index 6bac62eea2..8b481c0115 100644 --- a/ArduCopter/Attitude.pde +++ b/ArduCopter/Attitude.pde @@ -1026,9 +1026,6 @@ get_throttle_althold(int32_t target_alt, int16_t min_climb_rate, int16_t max_cli // call rate based throttle controller which will update accel based throttle controller targets get_throttle_rate(desired_rate); - // update altitude error reported to GCS - altitude_error = alt_error; - // TO-DO: enabled PID logging for this controller }