GPS: Use appropiate GPS_ENGINE settings in APM, ACM and rover
This commit is contained in:
parent
f9c5b135bc
commit
8f1121c980
@ -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
|
||||
|
@ -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)
|
||||
|
@ -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…
Reference in New Issue
Block a user