From 940d994efbddb4a6d5c5d233c223d6e445ed1d6d Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Sun, 10 Jun 2012 16:36:18 +1000 Subject: [PATCH] GPS: Use appropiate GPS_ENGINE settings in APM, ACM and rover --- APMrover2/system.pde | 3 ++- ArduCopter/system.pde | 3 ++- ArduPlane/system.pde | 3 ++- 3 files changed, 6 insertions(+), 3 deletions(-) diff --git a/APMrover2/system.pde b/APMrover2/system.pde index d19dbf0c52..46db3d7c03 100644 --- a/APMrover2/system.pde +++ b/APMrover2/system.pde @@ -203,7 +203,8 @@ static void init_ardupilot() #endif // Do GPS init g_gps = &g_gps_driver; - g_gps->init(); // GPS Initialization + // GPS initialisation + g_gps->init(GPS::GPS_ENGINE_AUTOMOTIVE); g_gps->callback = mavlink_delay; //mavlink_system.sysid = MAV_SYSTEM_ID; // Using g.sysid_this_mav diff --git a/ArduCopter/system.pde b/ArduCopter/system.pde index 14dad5a4c0..9af7209be1 100644 --- a/ArduCopter/system.pde +++ b/ArduCopter/system.pde @@ -218,7 +218,8 @@ static void init_ardupilot() // Do GPS init g_gps = &g_gps_driver; - g_gps->init(); // GPS Initialization + // GPS Initialization + g_gps->init(GPS::GPS_ENGINE_AIRBORNE_1G); g_gps->callback = mavlink_delay; if(g.compass_enabled) diff --git a/ArduPlane/system.pde b/ArduPlane/system.pde index ea6d30b5ad..a17f74667e 100644 --- a/ArduPlane/system.pde +++ b/ArduPlane/system.pde @@ -180,7 +180,8 @@ static void init_ardupilot() // Do GPS init g_gps = &g_gps_driver; - g_gps->init(); // GPS Initialization + // GPS Initialization + g_gps->init(GPS::GPS_ENGINE_AIRBORNE_4G); g_gps->callback = mavlink_delay; //mavlink_system.sysid = MAV_SYSTEM_ID; // Using g.sysid_this_mav