Browse Source

GPS_Glitch: remove unused recovered flag

master
Randy Mackay 12 years ago
parent
commit
78124f2fca
  1. 9
      libraries/AP_GPS/AP_GPS_Glitch.cpp
  2. 6
      libraries/AP_GPS/AP_GPS_Glitch.h

9
libraries/AP_GPS/AP_GPS_Glitch.cpp

@ -31,7 +31,6 @@ void GPS_Glitch::check_position() @@ -31,7 +31,6 @@ void GPS_Glitch::check_position()
// exit immediately if we don't have gps lock
if (_gps == NULL || _gps->status() != GPS::GPS_OK_FIX_3D) {
_flags.glitching = true;
_flags.recovered = false;
return;
}
@ -44,7 +43,6 @@ void GPS_Glitch::check_position() @@ -44,7 +43,6 @@ void GPS_Glitch::check_position()
_last_good_vel.y = _gps->velocity_east();
_flags.initialised = true;
_flags.glitching = false;
_flags.recovered = false;
return;
}
@ -78,14 +76,7 @@ void GPS_Glitch::check_position() @@ -78,14 +76,7 @@ void GPS_Glitch::check_position()
_last_good_lon = _gps->longitude;
_last_good_vel.x = _gps->velocity_north();
_last_good_vel.y = _gps->velocity_east();
// if we were glitching, we have now recovered
_flags.recovered = _flags.glitching;
}else{
_flags.recovered = false;
}
// To-Do: we need to stop consumer from seeing 'recovered' flag multiple times because GPS updates
// are much slower than inertial updates
// update glitching flag
_flags.glitching = !all_ok;

6
libraries/AP_GPS/AP_GPS_Glitch.h

@ -24,7 +24,7 @@ public: @@ -24,7 +24,7 @@ public:
// constructor
GPS_Glitch(GPS*& gps);
// check_position - checks latest gps position against last know position, velocity and maximum acceleration and updates glitching and recovered flags
// check_position - checks latest gps position against last know position, velocity and maximum acceleration and updates glitching flag
void check_position();
// enable - enable or disable gps sanity checking
@ -36,9 +36,6 @@ public: @@ -36,9 +36,6 @@ public:
// glitching - returns true if we are experiencing a glitch
bool glitching() { return _flags.glitching; }
// recovered - returns true if we have just recovered from a glitch
bool recovered() { return _flags.recovered; }
// last_good_update - returns system time of the last good update
uint32_t last_good_update() { return _last_good_update; }
@ -52,7 +49,6 @@ private: @@ -52,7 +49,6 @@ private:
uint8_t initialised : 1; // 1 if we have received at least one good gps lock
uint8_t enabled : 1; // 1 if we are enabled
uint8_t glitching : 1; // 1 if we are experiencing a gps glitch
uint8_t recovered : 1; // 1 if we have just recovered from a glitch
} _flags;
// gps sanity check variables

Loading…
Cancel
Save