Plane: pass fix type to gps->setHIL()

This commit is contained in:
Andrew Tridgell 2014-02-25 21:11:15 +11:00
parent 2fcbdc4056
commit 95dd252f29
1 changed files with 2 additions and 1 deletions

View File

@ -2123,7 +2123,8 @@ mission_failed:
if (g_gps != NULL) {
// set gps hil sensor
g_gps->setHIL(packet.time_usec/1000,
g_gps->setHIL(GPS::FIX_3D,
packet.time_usec/1000,
packet.lat*1.0e-7, packet.lon*1.0e-7, packet.alt*1.0e-3,
vel*1.0e-2, cog*1.0e-2, 0, 10);
}