AP_GPS: changed fake GPS fix to have a latitude/longitude

Pair-Programmed-With: Randy Mackay <rmackay9@yahoo.com>
This commit is contained in:
Andrew Tridgell 2013-10-10 19:15:07 +11:00
parent dcb01d193d
commit 25d3e5b7e9
1 changed files with 6 additions and 0 deletions

View File

@ -281,6 +281,11 @@ AP_GPS_UBLOX::_parse_gps(void)
altitude_cm = _buffer.posllh.altitude_msl / 10; altitude_cm = _buffer.posllh.altitude_msl / 10;
fix = next_fix; fix = next_fix;
_new_position = true; _new_position = true;
#if UBLOX_FAKE_3DLOCK
longitude = 1491652300L;
latitude = -353632610L;
altitude_cm = 58400;
#endif
break; break;
case MSG_STATUS: case MSG_STATUS:
Debug("MSG_STATUS fix_status=%u fix_type=%u", Debug("MSG_STATUS fix_status=%u fix_type=%u",
@ -326,6 +331,7 @@ AP_GPS_UBLOX::_parse_gps(void)
#if UBLOX_FAKE_3DLOCK #if UBLOX_FAKE_3DLOCK
next_fix = fix; next_fix = fix;
num_sats = 10; num_sats = 10;
hdop = 200;
#endif #endif
break; break;
case MSG_VELNED: case MSG_VELNED: