Add hDOP for ublox gps driver

git-svn-id: https://arducopter.googlecode.com/svn/trunk@2241 f9c3cf11-9bcb-44bc-f272-b75c42450872
This commit is contained in:
deweibel@gmail.com 2011-05-11 02:54:43 +00:00
parent 8e50fbcb42
commit 20cdf7c698
1 changed files with 1 additions and 0 deletions

View File

@ -179,6 +179,7 @@ AP_GPS_UBLOX::_parse_gps(void)
case MSG_SOL:
fix = (_buffer.solution.fix_status & NAV_STATUS_FIX_VALID) && (_buffer.solution.fix_type == FIX_3D);
num_sats = _buffer.solution.satellites;
hdop = _buffer.solution.position_DOP;
break;
case MSG_VELNED:
speed_3d = _buffer.velned.speed_3d; // cm/s