mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-23 00:04:02 -04:00
AHRS: add support for GPS fix type 2D
This commit is contained in:
parent
d7454bb09e
commit
24044dc0c4
@ -103,7 +103,7 @@ bool AP_AHRS::airspeed_estimate(float *airspeed_ret)
|
||||
{
|
||||
if (_airspeed && _airspeed->use()) {
|
||||
*airspeed_ret = _airspeed->get_airspeed();
|
||||
if (_wind_max > 0 && _gps && _gps->status() == GPS::GPS_OK) {
|
||||
if (_wind_max > 0 && _gps && _gps->status() >= GPS::GPS_OK_FIX_2D) {
|
||||
// constrain the airspeed by the ground speed
|
||||
// and AHRS_WIND_MAX
|
||||
*airspeed_ret = constrain(*airspeed_ret,
|
||||
|
@ -120,7 +120,7 @@ public:
|
||||
// otherwise false. This only updates the lat and lng fields
|
||||
// of the Location
|
||||
bool get_position(struct Location *loc) {
|
||||
if (!_gps || _gps->status() != GPS::GPS_OK) {
|
||||
if (!_gps || _gps->status() <= GPS::NO_FIX) {
|
||||
return false;
|
||||
}
|
||||
loc->lat = _gps->latitude;
|
||||
|
@ -281,7 +281,7 @@ AP_AHRS_DCM::_P_gain(float spin_rate)
|
||||
// return true if we have and should use GPS
|
||||
bool AP_AHRS_DCM::have_gps(void)
|
||||
{
|
||||
if (!_gps || _gps->status() != GPS::GPS_OK || !_gps_use) {
|
||||
if (!_gps || _gps->status() <= GPS::NO_FIX || !_gps_use) {
|
||||
return false;
|
||||
}
|
||||
return true;
|
||||
@ -730,7 +730,7 @@ bool AP_AHRS_DCM::airspeed_estimate(float *airspeed_ret)
|
||||
ret = true;
|
||||
}
|
||||
|
||||
if (ret && _wind_max > 0 && _gps && _gps->status() == GPS::GPS_OK) {
|
||||
if (ret && _wind_max > 0 && _gps && _gps->status() >= GPS::GPS_OK_FIX_2D) {
|
||||
// constrain the airspeed by the ground speed
|
||||
// and AHRS_WIND_MAX
|
||||
*airspeed_ret = constrain(*airspeed_ret,
|
||||
|
Loading…
Reference in New Issue
Block a user