Browse Source

Rover: updates for GPS changes

mission-4.1.18
Andrew Tridgell 11 years ago
parent
commit
d1a650a527
  1. 2
      APMrover2/Log.pde
  2. 4
      APMrover2/system.pde

2
APMrover2/Log.pde

@ -515,7 +515,7 @@ static const struct LogStructure log_structure[] PROGMEM = { @@ -515,7 +515,7 @@ static const struct LogStructure log_structure[] PROGMEM = {
{ LOG_CAMERA_MSG, sizeof(log_Camera),
"CAM", "IIHLLeccC", "TimeMS,GPSTime,GPSWeek,Lat,Lng,Alt,Roll,Pitch,Yaw" },
{ LOG_STARTUP_MSG, sizeof(log_Startup),
"STRT", "IBB", "TimeMS,SType,CTot" },
"STRT", "IBH", "TimeMS,SType,CTot" },
{ LOG_CTUN_MSG, sizeof(log_Control_Tuning),
"CTUN", "Ihcchf", "TimeMS,Steer,Roll,Pitch,ThrOut,AccY" },
{ LOG_NTUN_MSG, sizeof(log_Nav_Tuning),

4
APMrover2/system.pde

@ -189,12 +189,12 @@ static void init_ardupilot() @@ -189,12 +189,12 @@ static void init_ardupilot()
// Do GPS init
g_gps = &g_gps_driver;
// GPS initialisation
g_gps->init(hal.uartB, GPS::GPS_ENGINE_AIRBORNE_4G);
g_gps->init(hal.uartB, GPS::GPS_ENGINE_AIRBORNE_4G, &DataFlash);
#if GPS2_ENABLE
if (hal.uartE != NULL) {
g_gps2 = &g_gps2_driver;
g_gps2->init(hal.uartE, GPS::GPS_ENGINE_AIRBORNE_4G);
g_gps2->init(hal.uartE, GPS::GPS_ENGINE_AIRBORNE_4G, &DataFlash);
g_gps2->set_secondary();
}
#endif

Loading…
Cancel
Save