Copter: fixed GPS init

This commit is contained in:
Andrew Tridgell 2012-12-18 13:36:57 +11:00
parent 975506c840
commit 08b1c2d590
2 changed files with 8 additions and 8 deletions

View File

@ -219,25 +219,25 @@ AP_OpticalFlow optflow;
// real GPS selection
#if GPS_PROTOCOL == GPS_PROTOCOL_AUTO
AP_GPS_Auto g_gps_driver(hal.uartB, &g_gps);
AP_GPS_Auto g_gps_driver(&g_gps);
#elif GPS_PROTOCOL == GPS_PROTOCOL_NMEA
AP_GPS_NMEA g_gps_driver(hal.uartB);
AP_GPS_NMEA g_gps_driver();
#elif GPS_PROTOCOL == GPS_PROTOCOL_SIRF
AP_GPS_SIRF g_gps_driver(hal.uartB);
AP_GPS_SIRF g_gps_driver();
#elif GPS_PROTOCOL == GPS_PROTOCOL_UBLOX
AP_GPS_UBLOX g_gps_driver(hal.uartB);
AP_GPS_UBLOX g_gps_driver();
#elif GPS_PROTOCOL == GPS_PROTOCOL_MTK
AP_GPS_MTK g_gps_driver(hal.uartB);
AP_GPS_MTK g_gps_driver();
#elif GPS_PROTOCOL == GPS_PROTOCOL_MTK16
AP_GPS_MTK16 g_gps_driver(hal.uartB);
AP_GPS_MTK16 g_gps_driver();
#elif GPS_PROTOCOL == GPS_PROTOCOL_NONE
AP_GPS_None g_gps_driver(NULL);
AP_GPS_None g_gps_driver();
#else
#error Unrecognised GPS_PROTOCOL setting.

View File

@ -210,7 +210,7 @@ static void init_ardupilot()
// Do GPS init
g_gps = &g_gps_driver;
// GPS Initialization
g_gps->init(GPS::GPS_ENGINE_AIRBORNE_1G);
g_gps->init(hal.uartB, GPS::GPS_ENGINE_AIRBORNE_1G);
if(g.compass_enabled)
init_compass();