Browse Source

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

mission-4.1.18
Andrew Tridgell 13 years ago
parent
commit
940d994efb
  1. 3
      APMrover2/system.pde
  2. 3
      ArduCopter/system.pde
  3. 3
      ArduPlane/system.pde

3
APMrover2/system.pde

@ -203,7 +203,8 @@ static void init_ardupilot() @@ -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

3
ArduCopter/system.pde

@ -218,7 +218,8 @@ static void init_ardupilot() @@ -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)

3
ArduPlane/system.pde

@ -180,7 +180,8 @@ static void init_ardupilot() @@ -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

Loading…
Cancel
Save