diff --git a/APMrover2/GCS_Mavlink.cpp b/APMrover2/GCS_Mavlink.cpp index 92f28fd2ba..ed79e85b8f 100644 --- a/APMrover2/GCS_Mavlink.cpp +++ b/APMrover2/GCS_Mavlink.cpp @@ -1307,7 +1307,7 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg) gps.setHIL(0, AP_GPS::GPS_OK_FIX_3D, packet.time_usec/1000, - loc, vel, 10, 0, true); + loc, vel, 10, 0); // rad/sec Vector3f gyros;