mirror of https://github.com/ArduPilot/ardupilot
Rover: try changing GPS setting to AIRBORNE_4G
this may reduce the GPS latency and improve chicane performance
This commit is contained in:
parent
986417067e
commit
9b7a837553
|
@ -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
|
||||
|
|
Loading…
Reference in New Issue