GPS: Use appropiate GPS_ENGINE settings in APM, ACM and rover

This commit is contained in:
Andrew Tridgell 2012-06-10 16:36:18 +10:00
parent f9c5b135bc
commit 8f1121c980
3 changed files with 6 additions and 3 deletions

View File

@ -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

View File

@ -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)

View File

@ -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