From 9b7a8375537930550daf7acc5a1bd34d6988fc69 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Mon, 13 Jan 2014 10:20:40 +1100 Subject: [PATCH] Rover: try changing GPS setting to AIRBORNE_4G this may reduce the GPS latency and improve chicane performance --- APMrover2/system.pde | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/APMrover2/system.pde b/APMrover2/system.pde index 4498e6d7db..e6d11c116a 100644 --- a/APMrover2/system.pde +++ b/APMrover2/system.pde @@ -173,7 +173,7 @@ static void init_ardupilot() // Do GPS init g_gps = &g_gps_driver; // GPS initialisation - g_gps->init(hal.uartB, GPS::GPS_ENGINE_AUTOMOTIVE); + g_gps->init(hal.uartB, GPS::GPS_ENGINE_AIRBORNE_4G); //mavlink_system.sysid = MAV_SYSTEM_ID; // Using g.sysid_this_mav mavlink_system.compid = 1; //MAV_COMP_ID_IMU; // We do not check for comp id