From d3b087d2c1959ec70178d7d8b73df2277854d9ee Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Fri, 14 Nov 2014 14:44:15 +1100 Subject: [PATCH] AP_GPS: fixed build on non-PX4 platforms --- libraries/AP_GPS/AP_GPS.cpp | 10 +++++++--- libraries/AP_GPS/AP_GPS_PX4.cpp | 6 +++++- libraries/AP_GPS/AP_GPS_PX4.h | 4 +++- 3 files changed, 15 insertions(+), 5 deletions(-) diff --git a/libraries/AP_GPS/AP_GPS.cpp b/libraries/AP_GPS/AP_GPS.cpp index ffc8fb2f25..00ccd2b6ac 100644 --- a/libraries/AP_GPS/AP_GPS.cpp +++ b/libraries/AP_GPS/AP_GPS.cpp @@ -145,20 +145,23 @@ AP_GPS::detect_instance(uint8_t instance) AP_GPS_Backend *new_gps = NULL; AP_HAL::UARTDriver *port = instance==0?hal.uartB:hal.uartE; struct detect_state *dstate = &detect_state[instance]; + uint32_t now = hal.scheduler->millis(); +#if CONFIG_HAL_BOARD == HAL_BOARD_PX4 if (_type[instance] == GPS_TYPE_PX4) { // check for explicitely chosen PX4 GPS beforehand // it is not possible to autodetect it, nor does it require a real UART hal.console->print_P(PSTR(" PX4 ")); new_gps = new AP_GPS_PX4(*this, state[instance], port); + goto found_gps; } - else if (port == NULL) { +#endif + + if (port == NULL) { // UART not available return; } - uint32_t now = hal.scheduler->millis(); - state[instance].instance = instance; state[instance].status = NO_GPS; @@ -233,6 +236,7 @@ AP_GPS::detect_instance(uint8_t instance) #endif } +found_gps: if (new_gps != NULL) { state[instance].status = NO_FIX; drivers[instance] = new_gps; diff --git a/libraries/AP_GPS/AP_GPS_PX4.cpp b/libraries/AP_GPS/AP_GPS_PX4.cpp index add1c92016..d72f88ff33 100644 --- a/libraries/AP_GPS/AP_GPS_PX4.cpp +++ b/libraries/AP_GPS/AP_GPS_PX4.cpp @@ -22,7 +22,10 @@ // // Code by Holger Steinhaus +#include +#if CONFIG_HAL_BOARD == HAL_BOARD_PX4 #include "AP_GPS_PX4.h" + #include #include @@ -75,4 +78,5 @@ AP_GPS_PX4::read(void) } return updated; -} \ No newline at end of file +} +#endif diff --git a/libraries/AP_GPS/AP_GPS_PX4.h b/libraries/AP_GPS/AP_GPS_PX4.h index 6f5222cebd..837fc991cc 100644 --- a/libraries/AP_GPS/AP_GPS_PX4.h +++ b/libraries/AP_GPS/AP_GPS_PX4.h @@ -23,6 +23,7 @@ #include #include +#if CONFIG_HAL_BOARD == HAL_BOARD_PX4 #include class AP_GPS_PX4 : public AP_GPS_Backend { @@ -35,5 +36,6 @@ private: int _gps_sub; struct vehicle_gps_position_s _gps_pos; }; +#endif // CONFIG_HAL_BOARD +#endif // AP_GPS_PX4_H -#endif // AP_GPS_SIRF_h