From 27309a553fe296ddb4710ab78dc702b3f89b24b7 Mon Sep 17 00:00:00 2001 From: Randy Mackay Date: Mon, 25 Mar 2013 19:08:47 +0900 Subject: [PATCH] GPS: fixes after review Ensure 3D fix before returning velocity_down UBLOX: restore check of fix_status as part of determining 2D or 3D fix SIRF: add missing brackets on fix type check --- libraries/AP_GPS/AP_GPS_SIRF.cpp | 2 +- libraries/AP_GPS/AP_GPS_UBLOX.cpp | 26 ++++++++++++++++++-------- libraries/AP_GPS/GPS.h | 2 +- 3 files changed, 20 insertions(+), 10 deletions(-) diff --git a/libraries/AP_GPS/AP_GPS_SIRF.cpp b/libraries/AP_GPS/AP_GPS_SIRF.cpp index fe155b2509..acddc9f0d9 100644 --- a/libraries/AP_GPS/AP_GPS_SIRF.cpp +++ b/libraries/AP_GPS/AP_GPS_SIRF.cpp @@ -174,7 +174,7 @@ AP_GPS_SIRF::_parse_gps(void) // parse fix type if (_buffer.nav.fix_invalid) { fix = GPS::FIX_NONE; - }else if (_buffer.nav.fix_type & FIX_MASK == FIX_3D) { + }else if ((_buffer.nav.fix_type & FIX_MASK) == FIX_3D) { fix = GPS::FIX_3D; }else{ fix = GPS::FIX_2D; diff --git a/libraries/AP_GPS/AP_GPS_UBLOX.cpp b/libraries/AP_GPS/AP_GPS_UBLOX.cpp index 4f2eeadfa7..0109f27f0b 100644 --- a/libraries/AP_GPS/AP_GPS_UBLOX.cpp +++ b/libraries/AP_GPS/AP_GPS_UBLOX.cpp @@ -228,10 +228,15 @@ AP_GPS_UBLOX::_parse_gps(void) Debug("MSG_STATUS fix_status=%u fix_type=%u", _buffer.status.fix_status, _buffer.status.fix_type); - if (_buffer.status.fix_type == AP_GPS_UBLOX::FIX_3D) { - next_fix = GPS::FIX_3D; - }else if (_buffer.status.fix_type == AP_GPS_UBLOX::FIX_2D) { - next_fix = GPS::FIX_2D; + if (_buffer.status.fix_status & NAV_STATUS_FIX_VALID) { + if( _buffer.status.fix_type == AP_GPS_UBLOX::FIX_3D) { + next_fix = GPS::FIX_3D; + }else if (_buffer.status.fix_type == AP_GPS_UBLOX::FIX_2D) { + next_fix = GPS::FIX_2D; + }else{ + next_fix = GPS::FIX_NONE; + fix = GPS::FIX_NONE; + } }else{ next_fix = GPS::FIX_NONE; fix = GPS::FIX_NONE; @@ -241,10 +246,15 @@ AP_GPS_UBLOX::_parse_gps(void) Debug("MSG_SOL fix_status=%u fix_type=%u", _buffer.solution.fix_status, _buffer.solution.fix_type); - if (_buffer.status.fix_type == AP_GPS_UBLOX::FIX_3D) { - next_fix = GPS::FIX_3D; - }else if (_buffer.status.fix_type == AP_GPS_UBLOX::FIX_2D) { - next_fix = GPS::FIX_2D; + if (_buffer.status.fix_status & NAV_STATUS_FIX_VALID) { + if( _buffer.status.fix_type == AP_GPS_UBLOX::FIX_3D) { + next_fix = GPS::FIX_3D; + }else if (_buffer.status.fix_type == AP_GPS_UBLOX::FIX_2D) { + next_fix = GPS::FIX_2D; + }else{ + next_fix = GPS::FIX_NONE; + fix = GPS::FIX_NONE; + } }else{ next_fix = GPS::FIX_NONE; fix = GPS::FIX_NONE; diff --git a/libraries/AP_GPS/GPS.h b/libraries/AP_GPS/GPS.h index 3f7fdc8731..20f65fb21a 100644 --- a/libraries/AP_GPS/GPS.h +++ b/libraries/AP_GPS/GPS.h @@ -141,7 +141,7 @@ public: return _status >= GPS_OK_FIX_2D ? _velocity_east : 0; } float velocity_down(void) { - return _status >= GPS_OK_FIX_2D ? _velocity_down : 0; + return _status >= GPS_OK_FIX_3D ? _velocity_down : 0; } // last ground speed in m/s. This can be used when we have no GPS