diff --git a/libraries/AP_GPS/AP_GPS.cpp b/libraries/AP_GPS/AP_GPS.cpp
index 7de3e0e0a04c50807271b800df4a6d35dc2b2aea..7857ca66a28ae1a8d707bb9baf1a3bb881fecaff 100644
--- a/libraries/AP_GPS/AP_GPS.cpp
+++ b/libraries/AP_GPS/AP_GPS.cpp
@@ -146,7 +146,13 @@ AP_GPS::detect_instance(uint8_t instance)
     AP_HAL::UARTDriver *port = instance==0?hal.uartB:hal.uartE;
     struct detect_state *dstate = &detect_state[instance];
 
-    if (port == NULL) {
+    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);
+    }
+    else if (port == NULL) {
         // UART not available
         return;
     }
diff --git a/libraries/AP_GPS/AP_GPS.h b/libraries/AP_GPS/AP_GPS.h
index 270351ae0b7d3c23a7f67fa463fdfde4bdffaed1..25ecc2b839937484d869be1b1af7b48c4e439469 100644
--- a/libraries/AP_GPS/AP_GPS.h
+++ b/libraries/AP_GPS/AP_GPS.h
@@ -91,7 +91,8 @@ public:
         GPS_TYPE_NMEA  = 5,
         GPS_TYPE_SIRF  = 6,
         GPS_TYPE_HIL   = 7,
-        GPS_TYPE_SBP   = 8
+        GPS_TYPE_SBP   = 8,
+        GPS_TYPE_PX4   = 9
     };
 
     /// GPS status codes
@@ -413,5 +414,6 @@ private:
 #include <AP_GPS_NMEA.h>
 #include <AP_GPS_SIRF.h>
 #include <AP_GPS_SBP.h>
+#include <AP_GPS_PX4.h>
 
 #endif // __AP_GPS_H__