mirror of https://github.com/ArduPilot/ardupilot
GPS_Glitch: make enable/disable a parameter
This commit is contained in:
parent
78124f2fca
commit
a2c0415ba9
|
@ -10,11 +10,24 @@
|
|||
|
||||
extern const AP_HAL::HAL& hal;
|
||||
|
||||
// table of user settable parameters
|
||||
const AP_Param::GroupInfo GPS_Glitch::var_info[] PROGMEM = {
|
||||
// @Param: ENABLE
|
||||
// @DisplayName: GPS Glitch protection enable/disable
|
||||
// @Description: Allows you to enable (1) or disable (0) gps glitch protection
|
||||
// @Values: 0:Disabled,1:Enabled
|
||||
// @User: Standard
|
||||
AP_GROUPINFO("ENABLE", 0, GPS_Glitch, _enabled, 1),
|
||||
|
||||
AP_GROUPEND
|
||||
};
|
||||
|
||||
// constuctor
|
||||
GPS_Glitch::GPS_Glitch(GPS*& gps) :
|
||||
_gps(gps)
|
||||
{
|
||||
_flags.enabled = true;
|
||||
AP_Param::setup_object_defaults(this, var_info);
|
||||
_enabled = true;
|
||||
}
|
||||
|
||||
// check_position - returns true if gps position is acceptable, false if not
|
||||
|
@ -35,7 +48,7 @@ void GPS_Glitch::check_position()
|
|||
}
|
||||
|
||||
// if not initialised or disabled update last good position and exit
|
||||
if (!_flags.initialised || !_flags.enabled) {
|
||||
if (!_flags.initialised || !_enabled) {
|
||||
_last_good_update = now;
|
||||
_last_good_lat = _gps->latitude;
|
||||
_last_good_lon = _gps->longitude;
|
||||
|
|
|
@ -28,10 +28,10 @@ public:
|
|||
void check_position();
|
||||
|
||||
// enable - enable or disable gps sanity checking
|
||||
void enable(bool true_or_false) { _flags.enabled = true_or_false; }
|
||||
void enable(bool true_or_false) { _enabled = true_or_false; }
|
||||
|
||||
// enabled - returns true if glitch detection is enabled
|
||||
bool enabled() { return _flags.enabled; }
|
||||
bool enabled() { return _enabled; }
|
||||
|
||||
// glitching - returns true if we are experiencing a glitch
|
||||
bool glitching() { return _flags.glitching; }
|
||||
|
@ -39,6 +39,9 @@ public:
|
|||
// last_good_update - returns system time of the last good update
|
||||
uint32_t last_good_update() { return _last_good_update; }
|
||||
|
||||
// class level parameters
|
||||
static const struct AP_Param::GroupInfo var_info[];
|
||||
|
||||
private:
|
||||
|
||||
/// external dependencies
|
||||
|
@ -47,10 +50,12 @@ private:
|
|||
/// structure for holding flags
|
||||
struct GPS_Glitch_flags {
|
||||
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
|
||||
} _flags;
|
||||
|
||||
// parameters
|
||||
AP_Int8 _enabled; // top level enable/disable control
|
||||
|
||||
// gps sanity check variables
|
||||
uint32_t _last_good_update; // system time of last gps update that passed checks
|
||||
int32_t _last_good_lat; // last good latitude reported by the gps
|
||||
|
|
Loading…
Reference in New Issue