Copter: remove unused gps_fix_count

This commit is contained in:
Randy Mackay 2013-11-22 11:53:50 +09:00
parent fe6ad3579c
commit 4e6d41bc8e
1 changed files with 0 additions and 6 deletions

View File

@ -782,8 +782,6 @@ static AC_WPNav wp_nav(&inertial_nav, &ahrs, &g.pi_loiter_lat, &g.pi_loiter_lon,
////////////////////////////////////////////////////////////////////////////////
// Performance monitoring
////////////////////////////////////////////////////////////////////////////////
// The number of GPS fixes we have had
static uint8_t gps_fix_count;
static int16_t pmTest1;
// System Timers
@ -981,7 +979,6 @@ static void perf_update(void)
(unsigned long)perf_info_get_max_time());
}
perf_info_reset();
gps_fix_count = 0;
pmTest1 = 0;
}
@ -1313,9 +1310,6 @@ static void update_GPS(void)
// clear new data flag
g_gps->new_data = false;
// for performance monitoring
gps_fix_count++;
// check if we can initialise home yet
if (!ap.home_is_set) {
// if we have a 3d lock and valid location