AP_GPS: added ability to disable GPS

this is used for GPS loss testing in real vehicles, by linking it to a
RCn_OPTION value. GPS position is still logged, but is not used
This commit is contained in:
Andrew Tridgell 2018-09-05 12:37:18 +10:00
parent a8fa17e7fd
commit 2512b73106
1 changed files with 11 additions and 0 deletions

View File

@ -188,6 +188,9 @@ public:
/// Query GPS status
GPS_Status status(uint8_t instance) const {
if (_force_disable_gps && state[instance].status > NO_FIX) {
return NO_FIX;
}
return state[instance].status;
}
GPS_Status status(void) const {
@ -417,6 +420,11 @@ public:
// returns true if all GPS instances have passed all final arming checks/state changes
bool prepare_for_arming(void);
// used to disable GPS for GPS failure testing in flight
void force_disable(bool disable) {
_force_disable_gps = disable;
}
protected:
// configuration parameters
@ -555,6 +563,9 @@ private:
GPS_AUTO_CONFIG_DISABLE = 0,
GPS_AUTO_CONFIG_ENABLE = 1
};
// used for flight testing with GPS loss
bool _force_disable_gps;
};
namespace AP {