ArduCopter: remove some variables no longer required with introduction of AP_state

This commit is contained in:
rmackay9 2012-11-12 12:41:25 +09:00
parent ac5dcc8d49
commit dcd98eee78
3 changed files with 0 additions and 24 deletions

View File

@ -438,12 +438,6 @@ static byte oldSwitchPosition;
////////////////////////////////////////////////////////////////////////////////
// Motor Output
////////////////////////////////////////////////////////////////////////////////
// This is the array of PWM values being sent to the motors
//static int16_t motor_out[11];
// This is the array of PWM values being sent to the motors that has been lightly filtered with a simple LPF
// This was added to try and deal with biger motors
//static int16_t motor_filtered[11];
#if FRAME_CONFIG == QUAD_FRAME
#define MOTOR_CLASS AP_MotorsQuad
#endif
@ -698,12 +692,6 @@ static byte throttle_mode;
////////////////////////////////////////////////////////////////////////////////
// flight specific
////////////////////////////////////////////////////////////////////////////////
// Flag for monitoring the status of flight
// We must be in the air with throttle for 5 seconds before this flag is true
// This flag is reset when we are in a manual throttle mode with 0 throttle or disarmed
//static bool takeoff_complete;
// Used to see if we have landed and if we should shut our engines - not fully implemented
//static bool land_complete = true;
// An additional throttle added to keep the copter at the same altitude when banking
static int16_t angle_boost;
// Push copter down for clean landing
@ -711,8 +699,6 @@ static int16_t landing_boost;
// for controlling the landing throttle curve
//verifies landings
static int16_t ground_detector;
// have we reached our desired altitude brefore heading home?
//static bool rtl_reached_alt;
////////////////////////////////////////////////////////////////////////////////
@ -732,8 +718,6 @@ int32_t wp_distance;
// home location is stored when we have a good GPS lock and arm the copter
// Can be reset each the copter is re-armed
static struct Location home;
// Flag for if we have g_gps lock and have set the home location
//static bool home_is_set;
// Current location of the copter
static struct Location current_loc;
// Next WP is the desired location of the copter - the next waypoint or loiter location

View File

@ -527,10 +527,7 @@ static void reset_desired_speed()
static int16_t get_desired_climb_rate()
{
//static int16_t climb_old = 0;
if(alt_change_flag == REACHED_ALT) {
//climb_old = 0;
return 0;
}
@ -547,7 +544,6 @@ static int16_t get_desired_climb_rate()
}else{
// Descending
climb = constrain(climb, MIN_CLIMB_RATE, MAX_CLIMB_RATE_DOWN);
//climb = min(climb, MAX_CLIMB_RATE_DOWN); // don't go to fast
}
}else{
@ -558,9 +554,6 @@ static int16_t get_desired_climb_rate()
}
}
//climb = min(climb, climb_old + (100 * .02));// limit acceleration
//climb_old = climb;
if(alt_change_flag == DESCENDING){
climb = -climb;
}

View File

@ -2,7 +2,6 @@
// Toy Mode - THOR
////////////////////////////////////////////////////////////////////////////////
static boolean CH7_toy_flag;
//static boolean CH6_toy_flag;
#if TOY_MIXER == TOY_LOOKUP_TABLE
static const int16_t toy_lookup[] = {