AP_GPS: Support fix types of DGPS and RTK

This commit is contained in:
Niels Joubert 2014-03-31 16:39:53 -07:00 committed by Andrew Tridgell
parent 64d4a1236f
commit 552f33b39e

View File

@ -73,7 +73,9 @@ public:
NO_GPS = 0, ///< No GPS connected/detected NO_GPS = 0, ///< No GPS connected/detected
NO_FIX = 1, ///< Receiving valid GPS messages but no lock NO_FIX = 1, ///< Receiving valid GPS messages but no lock
GPS_OK_FIX_2D = 2, ///< Receiving valid messages and 2D lock GPS_OK_FIX_2D = 2, ///< Receiving valid messages and 2D lock
GPS_OK_FIX_3D = 3 ///< Receiving valid messages and 3D lock GPS_OK_FIX_3D = 3, ///< Receiving valid messages and 3D lock
GPS_OK_FIX_3D_DGPS = 4, ///< Receiving valid messages and 3D lock with differential improvements
GPS_OK_FIX_3D_RTK = 5, ///< Receiving valid messages and 3D lock, with relative-positioning improvements
}; };
// GPS navigation engine settings. Not all GPS receivers support // GPS navigation engine settings. Not all GPS receivers support