diff --git a/QGCExternalLibs.pri b/QGCExternalLibs.pri
index 13756cb9a044b6860c5558b3dee467468ad0511f..606ca5947fb9744c36d766c70c693bbb12cc7dd8 100644
--- a/QGCExternalLibs.pri
+++ b/QGCExternalLibs.pri
@@ -5,57 +5,6 @@ WindowsBuild {
     INCLUDEPATH += libs/lib/msinttypes
 }
 
-#
-# [OPTIONAL] QUpgrade support.
-#
-# Allow the user to override QUpgrade compilation through a DISABLE_QUPGRADE
-# define like: `qmake DEFINES=DISABLE_QUPGRADE`
-contains(DEFINES, DISABLE_QUPGRADE) {
-    message("Skipping support for QUpgrade (manual override from command line)")
-    DEFINES -= DISABLE_QUPGRADE
-}
-# Otherwise the user can still disable this feature in the user_config.pri file.
-else:exists(user_config.pri):infile(user_config.pri, DEFINES, DISABLE_QUPGRADE) {
-    message("Skipping support for QUpgrade (manual override from user_config.pri)")
-}
-# If the QUpgrade submodule has been initialized, build in support by default.
-# We look for the existence of qupgrade.pro for the check. We can't look for a .git file
-# because that breaks the TeamCity build process which does not use repositories.
-else:exists(qupgrade/qupgrade.pro) {
-    message("Including support for QUpgrade")
-
-    DEFINES += QGC_QUPGRADE_ENABLED
-
-    INCLUDEPATH += qupgrade/src/apps/qupgrade
-
-    FORMS += \
-        qupgrade/src/apps/qupgrade/dialog_bare.ui \
-        qupgrade/src/apps/qupgrade/boardwidget.ui
-
-    HEADERS += \
-        qupgrade/src/apps/qupgrade/qgcfirmwareupgradeworker.h \
-        qupgrade/src/apps/qupgrade/uploader.h \
-        qupgrade/src/apps/qupgrade/dialog_bare.h \
-        qupgrade/src/apps/qupgrade/boardwidget.h
-
-    SOURCES += \
-        qupgrade/src/apps/qupgrade/qgcfirmwareupgradeworker.cpp \
-        qupgrade/src/apps/qupgrade/uploader.cpp \
-        qupgrade/src/apps/qupgrade/dialog_bare.cpp \
-        qupgrade/src/apps/qupgrade/boardwidget.cpp
-
-    RESOURCES += \
-        qupgrade/qupgrade.qrc
-
-    LinuxBuild:CONFIG += qesp_linux_udev
-
-    include(qupgrade/libs/qextserialport/src/qextserialport.pri)
-}
-# Otherwise notify the user and don't compile it.
-else {
-    warning("Skipping support for QUpgrade (missing submodule, see README)")
-}
-
 #
 # [REQUIRED] Add support for the MAVLink communications protocol.
 # Some logic is involved here in selecting the proper dialect for
diff --git a/files/images/px4/boards/px4flow_1.x.png b/files/images/px4/boards/px4flow_1.x.png
new file mode 100644
index 0000000000000000000000000000000000000000..0f396aa7c8e47cacc0191a91563b74e1ad220728
Binary files /dev/null and b/files/images/px4/boards/px4flow_1.x.png differ
diff --git a/files/images/px4/boards/px4fmu_1.x.png b/files/images/px4/boards/px4fmu_1.x.png
new file mode 100644
index 0000000000000000000000000000000000000000..294fa975ba9aa5086e849ad720e428df90136ed3
Binary files /dev/null and b/files/images/px4/boards/px4fmu_1.x.png differ
diff --git a/files/images/px4/boards/px4fmu_2.x.png b/files/images/px4/boards/px4fmu_2.x.png
new file mode 100644
index 0000000000000000000000000000000000000000..0a26a6883e64f5438de9d22b6c6bb322818eb81f
Binary files /dev/null and b/files/images/px4/boards/px4fmu_2.x.png differ
diff --git a/qgroundcontrol.pro b/qgroundcontrol.pro
index 498ff7e1e31e045f18a703d9aa7e38930f7c1b27..1e1899568ec67cabfba82fa5f5a3a9fea77a8d63 100644
--- a/qgroundcontrol.pro
+++ b/qgroundcontrol.pro
@@ -137,6 +137,7 @@ MacBuild {
 
 LinuxBuild {
 	DEFINES += __STDC_LIMIT_MACROS
+    CONFIG += qesp_linux_udev
 }
 
 WindowsBuild {
@@ -245,6 +246,7 @@ INCLUDEPATH += \
     src/ui/mission \
     src/ui/designer \
     src/ui/configuration \
+    src/ui/px4_configuration \
     src/ui/main
 
 FORMS += \
@@ -358,6 +360,7 @@ FORMS += \
     src/ui/px4_configuration/QGCPX4MulticopterConfig.ui \
     src/ui/px4_configuration/QGCPX4SensorCalibration.ui \
     src/ui/px4_configuration/PX4RCCalibration.ui \
+    src/ui/px4_configuration/PX4FirmwareUpgrade.ui \
     src/ui/QGCUASFileView.ui
 
 HEADERS += \
@@ -544,6 +547,9 @@ HEADERS += \
     src/ui/px4_configuration/QGCPX4MulticopterConfig.h \
     src/ui/px4_configuration/QGCPX4SensorCalibration.h \
     src/ui/px4_configuration/PX4RCCalibration.h \
+    src/ui/px4_configuration/PX4Bootloader.h \
+    src/ui/px4_configuration/PX4FirmwareUpgradeThread.h \
+    src/ui/px4_configuration/PX4FirmwareUpgrade.h \
     src/ui/menuactionhelper.h \
     src/uas/UASManagerInterface.h \
     src/uas/QGCUASParamManagerInterface.h \
@@ -729,6 +735,9 @@ SOURCES += \
     src/ui/px4_configuration/QGCPX4MulticopterConfig.cc \
     src/ui/px4_configuration/QGCPX4SensorCalibration.cc \
     src/ui/px4_configuration/PX4RCCalibration.cc \
+    src/ui/px4_configuration/PX4Bootloader.cc \
+    src/ui/px4_configuration/PX4FirmwareUpgradeThread.cc \
+    src/ui/px4_configuration/PX4FirmwareUpgrade.cc \
     src/ui/menuactionhelper.cpp \
     src/uas/QGCUASFileManager.cc \
     src/ui/QGCUASFileView.cc \
diff --git a/qgroundcontrol.qrc b/qgroundcontrol.qrc
index 31686a27f7b0b60b4b3289b6b152e889d9faf058..5a7d9cdaece71becfacb7e7e073d8eabee05eec4 100644
--- a/qgroundcontrol.qrc
+++ b/qgroundcontrol.qrc
@@ -199,6 +199,9 @@
         <file>files/images/px4/calibration/3dr_gps/gps_24.png</file>
         <file>files/images/px4/calibration/3dr_gps/gps_00.png</file>
         <file>files/images/px4/menu/toggle_switch.png</file>
+        <file>files/images/px4/boards/px4flow_1.x.png</file>
+        <file>files/images/px4/boards/px4fmu_1.x.png</file>
+        <file>files/images/px4/boards/px4fmu_2.x.png</file>
     </qresource>
     <qresource prefix="/general">
         <file alias="vera.ttf">files/styles/Vera.ttf</file>
diff --git a/src/ui/QGCPX4VehicleConfig.cc b/src/ui/QGCPX4VehicleConfig.cc
index 5b540ed617925b916bcf4651b17792df592fc973..88aa88f9670192ab567c4959b4add069b1799136 100644
--- a/src/ui/QGCPX4VehicleConfig.cc
+++ b/src/ui/QGCPX4VehicleConfig.cc
@@ -25,9 +25,7 @@
 #include "px4_configuration/QGCPX4SensorCalibration.h"
 #include "px4_configuration/PX4RCCalibration.h"
 
-#ifdef QGC_QUPGRADE_ENABLED
-#include <dialog_bare.h>
-#endif
+#include "PX4FirmwareUpgrade.h"
 
 #define WIDGET_INDEX_FIRMWARE 0
 #define WIDGET_INDEX_RC 1
@@ -67,18 +65,8 @@ QGCPX4VehicleConfig::QGCPX4VehicleConfig(QWidget *parent) :
     px4RCCalibration = new PX4RCCalibration(this);
     ui->rcLayout->addWidget(px4RCCalibration);
     
-#ifdef QGC_QUPGRADE_ENABLED
-    DialogBare *firmwareDialog = new DialogBare(this);
-    ui->firmwareLayout->addWidget(firmwareDialog);
-
-    connect(firmwareDialog, SIGNAL(connectLinks()), LinkManager::instance(), SLOT(connectAll()));
-    connect(firmwareDialog, SIGNAL(disconnectLinks()), LinkManager::instance(), SLOT(disconnectAll()));
-#else
-
-    QLabel* label = new QLabel(this);
-    label->setText("THIS VERSION OF QGROUNDCONTROL WAS BUILT WITHOUT QUPGRADE. To enable firmware upload support, checkout QUpgrade WITHIN the QGroundControl folder");
-    ui->firmwareLayout->addWidget(label);
-#endif
+    PX4FirmwareUpgrade* firmwareUpgrade = new PX4FirmwareUpgrade(this);
+    ui->firmwareLayout->addWidget(firmwareUpgrade);
 
     connect(ui->rcMenuButton,SIGNAL(clicked()),
             this,SLOT(rcMenuButtonClicked()));
@@ -278,10 +266,6 @@ void QGCPX4VehicleConfig::setActiveUAS(UASInterface* active)
 
     qDebug() << "CALIBRATION!! System Type Name:" << mav->getSystemTypeName();
 
-    //Load configuration after 1ms. This allows it to go into the event loop, and prevents application hangups due to the
-    //amount of time it actually takes to load the configuration windows.
-    QTimer::singleShot(1,this,SLOT(loadConfig()));
-
     updateStatus(QString("Reading from system %1").arg(mav->getUASName()));
 
     // Since a system is now connected, enable the VehicleConfig UI.
diff --git a/src/ui/px4_configuration/PX4Bootloader.cc b/src/ui/px4_configuration/PX4Bootloader.cc
new file mode 100644
index 0000000000000000000000000000000000000000..eabd11ffd8b4b019437e4adf70f015430754838f
--- /dev/null
+++ b/src/ui/px4_configuration/PX4Bootloader.cc
@@ -0,0 +1,481 @@
+/*=====================================================================
+ 
+ QGroundControl Open Source Ground Control Station
+ 
+ (c) 2009, 2014 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org>
+ 
+ This file is part of the QGROUNDCONTROL project
+ 
+ QGROUNDCONTROL is free software: you can redistribute it and/or modify
+ it under the terms of the GNU General Public License as published by
+ the Free Software Foundation, either version 3 of the License, or
+ (at your option) any later version.
+ 
+ QGROUNDCONTROL is distributed in the hope that it will be useful,
+ but WITHOUT ANY WARRANTY; without even the implied warranty of
+ MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
+ GNU General Public License for more details.
+ 
+ You should have received a copy of the GNU General Public License
+ along with QGROUNDCONTROL. If not, see <http://www.gnu.org/licenses/>.
+ 
+ ======================================================================*/
+
+/// @file
+///     @brief PX4 Bootloader Utility routines
+///     @author Don Gagne <don@thegagnes.com>
+
+#include "PX4Bootloader.h"
+
+#include <QFile>
+#include <QSerialPortInfo>
+#include <QDebug>
+#include <QTime>
+
+static const quint32 crctab[] =
+{
+    0x00000000, 0x77073096, 0xee0e612c, 0x990951ba, 0x076dc419, 0x706af48f, 0xe963a535, 0x9e6495a3,
+    0x0edb8832, 0x79dcb8a4, 0xe0d5e91e, 0x97d2d988, 0x09b64c2b, 0x7eb17cbd, 0xe7b82d07, 0x90bf1d91,
+    0x1db71064, 0x6ab020f2, 0xf3b97148, 0x84be41de, 0x1adad47d, 0x6ddde4eb, 0xf4d4b551, 0x83d385c7,
+    0x136c9856, 0x646ba8c0, 0xfd62f97a, 0x8a65c9ec, 0x14015c4f, 0x63066cd9, 0xfa0f3d63, 0x8d080df5,
+    0x3b6e20c8, 0x4c69105e, 0xd56041e4, 0xa2677172, 0x3c03e4d1, 0x4b04d447, 0xd20d85fd, 0xa50ab56b,
+    0x35b5a8fa, 0x42b2986c, 0xdbbbc9d6, 0xacbcf940, 0x32d86ce3, 0x45df5c75, 0xdcd60dcf, 0xabd13d59,
+    0x26d930ac, 0x51de003a, 0xc8d75180, 0xbfd06116, 0x21b4f4b5, 0x56b3c423, 0xcfba9599, 0xb8bda50f,
+    0x2802b89e, 0x5f058808, 0xc60cd9b2, 0xb10be924, 0x2f6f7c87, 0x58684c11, 0xc1611dab, 0xb6662d3d,
+    0x76dc4190, 0x01db7106, 0x98d220bc, 0xefd5102a, 0x71b18589, 0x06b6b51f, 0x9fbfe4a5, 0xe8b8d433,
+    0x7807c9a2, 0x0f00f934, 0x9609a88e, 0xe10e9818, 0x7f6a0dbb, 0x086d3d2d, 0x91646c97, 0xe6635c01,
+    0x6b6b51f4, 0x1c6c6162, 0x856530d8, 0xf262004e, 0x6c0695ed, 0x1b01a57b, 0x8208f4c1, 0xf50fc457,
+    0x65b0d9c6, 0x12b7e950, 0x8bbeb8ea, 0xfcb9887c, 0x62dd1ddf, 0x15da2d49, 0x8cd37cf3, 0xfbd44c65,
+    0x4db26158, 0x3ab551ce, 0xa3bc0074, 0xd4bb30e2, 0x4adfa541, 0x3dd895d7, 0xa4d1c46d, 0xd3d6f4fb,
+    0x4369e96a, 0x346ed9fc, 0xad678846, 0xda60b8d0, 0x44042d73, 0x33031de5, 0xaa0a4c5f, 0xdd0d7cc9,
+    0x5005713c, 0x270241aa, 0xbe0b1010, 0xc90c2086, 0x5768b525, 0x206f85b3, 0xb966d409, 0xce61e49f,
+    0x5edef90e, 0x29d9c998, 0xb0d09822, 0xc7d7a8b4, 0x59b33d17, 0x2eb40d81, 0xb7bd5c3b, 0xc0ba6cad,
+    0xedb88320, 0x9abfb3b6, 0x03b6e20c, 0x74b1d29a, 0xead54739, 0x9dd277af, 0x04db2615, 0x73dc1683,
+    0xe3630b12, 0x94643b84, 0x0d6d6a3e, 0x7a6a5aa8, 0xe40ecf0b, 0x9309ff9d, 0x0a00ae27, 0x7d079eb1,
+    0xf00f9344, 0x8708a3d2, 0x1e01f268, 0x6906c2fe, 0xf762575d, 0x806567cb, 0x196c3671, 0x6e6b06e7,
+    0xfed41b76, 0x89d32be0, 0x10da7a5a, 0x67dd4acc, 0xf9b9df6f, 0x8ebeeff9, 0x17b7be43, 0x60b08ed5,
+    0xd6d6a3e8, 0xa1d1937e, 0x38d8c2c4, 0x4fdff252, 0xd1bb67f1, 0xa6bc5767, 0x3fb506dd, 0x48b2364b,
+    0xd80d2bda, 0xaf0a1b4c, 0x36034af6, 0x41047a60, 0xdf60efc3, 0xa867df55, 0x316e8eef, 0x4669be79,
+    0xcb61b38c, 0xbc66831a, 0x256fd2a0, 0x5268e236, 0xcc0c7795, 0xbb0b4703, 0x220216b9, 0x5505262f,
+    0xc5ba3bbe, 0xb2bd0b28, 0x2bb45a92, 0x5cb36a04, 0xc2d7ffa7, 0xb5d0cf31, 0x2cd99e8b, 0x5bdeae1d,
+    0x9b64c2b0, 0xec63f226, 0x756aa39c, 0x026d930a, 0x9c0906a9, 0xeb0e363f, 0x72076785, 0x05005713,
+    0x95bf4a82, 0xe2b87a14, 0x7bb12bae, 0x0cb61b38, 0x92d28e9b, 0xe5d5be0d, 0x7cdcefb7, 0x0bdbdf21,
+    0x86d3d2d4, 0xf1d4e242, 0x68ddb3f8, 0x1fda836e, 0x81be16cd, 0xf6b9265b, 0x6fb077e1, 0x18b74777,
+    0x88085ae6, 0xff0f6a70, 0x66063bca, 0x11010b5c, 0x8f659eff, 0xf862ae69, 0x616bffd3, 0x166ccf45,
+    0xa00ae278, 0xd70dd2ee, 0x4e048354, 0x3903b3c2, 0xa7672661, 0xd06016f7, 0x4969474d, 0x3e6e77db,
+    0xaed16a4a, 0xd9d65adc, 0x40df0b66, 0x37d83bf0, 0xa9bcae53, 0xdebb9ec5, 0x47b2cf7f, 0x30b5ffe9,
+    0xbdbdf21c, 0xcabac28a, 0x53b39330, 0x24b4a3a6, 0xbad03605, 0xcdd70693, 0x54de5729, 0x23d967bf,
+    0xb3667a2e, 0xc4614ab8, 0x5d681b02, 0x2a6f2b94, 0xb40bbe37, 0xc30c8ea1, 0x5a05df1b, 0x2d02ef8d
+};
+
+static quint32 crc32(const uint8_t *src, unsigned len, unsigned state)
+{
+    for (unsigned i = 0; i < len; i++) {
+        state = crctab[(state ^ src[i]) & 0xff] ^ (state >> 8);
+    }
+    return state;
+}
+
+const struct PX4Bootloader::serialPortErrorString PX4Bootloader::_rgSerialPortErrors[14] = {
+    { QSerialPort::NoError,                     "No error occurred." },
+    { QSerialPort::DeviceNotFoundError,         "An error occurred while attempting to open a non-existing device." },
+    { QSerialPort::PermissionError,             "An error occurred while attempting to open an already opened device by another process or a user not having enough permission and credentials to open." },
+    { QSerialPort::OpenError,                   "An error occurred while attempting to open an already opened device in this object." },
+    { QSerialPort::NotOpenError,                "This error occurs when an operation is executed that can only be successfully performed if the device is open." },
+    { QSerialPort::ParityError,                 "Parity error detected by the hardware while reading data." },
+    { QSerialPort::FramingError,                "Framing error detected by the hardware while reading data." },
+    { QSerialPort::BreakConditionError,         "Break condition detected by the hardware on the input line." },
+    { QSerialPort::WriteError,                  "An I/O error occurred while writing the data." },
+    { QSerialPort::ReadError,                   "An I/O error occurred while reading the data." },
+    { QSerialPort::ResourceError,               "An I/O error occurred when a resource becomes unavailable, e.g. when the device is unexpectedly removed from the system." },
+    { QSerialPort::UnsupportedOperationError,   "The requested device operation is not supported or prohibited by the running operating system." },
+    { QSerialPort::TimeoutError,                "A timeout error occurred." },
+    { QSerialPort::UnknownError,                "An unidentified error occurred." }
+};
+
+PX4Bootloader::PX4Bootloader(QObject *parent) :
+    QObject(parent)
+{
+
+}
+
+/// @brief Translate a QSerialPort::SerialPortError code into a string.
+const char* PX4Bootloader::_serialPortErrorString(int error)
+{
+Again:
+    for (size_t i=0; i<sizeof(_rgSerialPortErrors)/sizeof(_rgSerialPortErrors[0]); i++) {
+        if (error == _rgSerialPortErrors[i].error) {
+            return _rgSerialPortErrors[i].errorString;
+        }
+    }
+    
+    error = QSerialPort::UnknownError;
+    goto Again;
+    
+    Q_ASSERT(false);
+    
+    return NULL;
+}
+
+bool PX4Bootloader::write(QSerialPort* port, const uint8_t* data, qint64 maxSize)
+{
+    qint64 bytesWritten = port->write((const char*)data, maxSize);
+    if (bytesWritten == -1) {
+        _errorString = tr("Write failed: %1").arg(port->errorString());
+        qWarning() << _errorString;
+        return false;
+    }
+    if (bytesWritten != maxSize) {
+        _errorString = tr("Incorrect number of bytes returned for write: actual(%1) expected(%2)").arg(bytesWritten).arg(maxSize);
+        qWarning() << _errorString;
+        return false;
+    }
+    if (!port->waitForBytesWritten(1000)) {
+        _errorString = tr("Timeout waiting for write");
+        qWarning() << _errorString;
+        return false;
+    }
+    
+    return true;
+}
+
+bool PX4Bootloader::write(QSerialPort* port, const uint8_t byte)
+{
+    uint8_t buf[1] = { byte };
+    return write(port, buf, 1);
+}
+
+bool PX4Bootloader::read(QSerialPort* port, uint8_t* data, qint64 maxSize, bool warnOnError, int readTimeout)
+{
+    qint64 bytesRead;
+    
+    if (port->bytesAvailable() < maxSize) {
+        if (!port->waitForReadyRead(readTimeout)) {
+            _errorString = tr("Timeout waiting for read bytes available: %1").arg(port->errorString());
+            if (warnOnError) {
+                qWarning() << _errorString;
+            }
+            return false;
+        }
+    }
+    
+    bytesRead = port->read((char*)data, maxSize);
+    if (bytesRead == -1) {
+        _errorString = tr("Read failed: Could not read %1 resonse, error: 12").arg(port->errorString());
+        if (warnOnError) {
+            qWarning() << _errorString;
+        }
+        return false;
+    }
+    if (bytesRead != maxSize) {
+        _errorString = tr("In correct number of bytes returned for read: actual(%1) expected(%2)").arg(bytesRead).arg(maxSize);
+        if (warnOnError) {
+            qWarning() << _errorString;
+        }
+        return false;
+    }
+    
+    return true;
+}
+
+bool PX4Bootloader::getCommandResponse(QSerialPort* port, bool warnOnError, int responseTimeout)
+{
+    uint8_t response[2];
+    
+    if (!read(port, response, 2, warnOnError, responseTimeout)) {
+        return false;
+    }
+    
+    // Make sure we get a good sync response
+    if (response[0] != PROTO_INSYNC) {
+        _errorString = tr("Invalid sync response: 0x%1 0x%2").arg(response[0], 2, 16, QLatin1Char('0')).arg(response[1], 2, 16, QLatin1Char('0'));
+        if (warnOnError) {
+            qWarning() << _errorString;
+        }
+        return false;
+    } else if (response[1] != PROTO_OK) {
+        QString responseCode = tr("Unknown response code");
+        if (response[1] == PROTO_FAILED) {
+            responseCode = "PROTO_FAILED";
+        } else if (response[1] == PROTO_INVALID) {
+            responseCode = "PROTO_INVALID";
+        }
+        _errorString = tr("Command failed: 0x%1 (%2)").arg(response[1], 2, 16, QLatin1Char('0')).arg(responseCode);
+        if (warnOnError) {
+            qWarning() << _errorString;
+        }
+        return false;
+    }
+    
+    return true;
+}
+
+bool PX4Bootloader::getBoardInfo(QSerialPort* port, uint8_t param, uint32_t& value)
+{
+    uint8_t buf[3] = { PROTO_GET_DEVICE, param, PROTO_EOC };
+    
+    if (!write(port, buf, sizeof(buf))) {
+        return false;
+    }
+    if (!read(port, (uint8_t*)&value, sizeof(value), warnOnError)) {
+        return false;
+    }
+    return getCommandResponse(port, warnOnError);
+}
+
+bool PX4Bootloader::sendCommand(QSerialPort* port, const uint8_t cmd, bool warnOnError, int responseTimeout)
+{
+    uint8_t buf[2] = { cmd, PROTO_EOC };
+    
+    if (!write(port, buf, 2)) {
+        return false;
+    }
+    return getCommandResponse(port, warnOnError, responseTimeout);
+}
+
+bool PX4Bootloader::erase(QSerialPort* port)
+{
+    // Erase is slow, need larger timeout
+    if (!sendCommand(port, PROTO_CHIP_ERASE, warnOnError, _eraseTimeout)) {
+        _errorString = tr("Board erase failed: %1").arg(_errorString);
+        qWarning() << _errorString;
+        return false;
+    }
+    
+    return true;
+}
+
+bool PX4Bootloader::program(QSerialPort* port, const QString& firmwareFilename)
+{
+    QFile firmwareFile(firmwareFilename);
+    if (!firmwareFile.open(QIODevice::ReadOnly)) {
+        _errorString = tr("Unable to open firmware file %1: %2").arg(firmwareFilename).arg(firmwareFile.errorString());
+        qWarning() << _errorString;
+        return false;
+    }
+    uint32_t imageSize = (uint32_t)firmwareFile.size();
+    
+    uint8_t imageBuf[PROG_MULTI_MAX];
+    uint32_t bytesSent = 0;
+    _imageCRC = 0;
+    
+    Q_ASSERT(PROG_MULTI_MAX <= 0x8F);
+    
+    while (bytesSent < imageSize) {
+        int bytesToSend = imageSize - bytesSent;
+        if (bytesToSend > (int)sizeof(imageBuf)) {
+            bytesToSend = (int)sizeof(imageBuf);
+        }
+        
+        Q_ASSERT((bytesToSend % 4) == 0);
+        
+        int bytesRead = firmwareFile.read((char *)imageBuf, bytesToSend);
+        if (bytesRead == -1 || bytesRead != bytesToSend) {
+            _errorString = tr("Read failed: %1").arg(firmwareFile.errorString());
+            qWarning() << _errorString;
+            return false;
+        }
+        
+        Q_ASSERT(bytesToSend <= 0x8F);
+        
+        if (!write(port, PROTO_PROG_MULTI) ||
+                !write(port, (uint8_t)bytesToSend) ||
+                !write(port, imageBuf, bytesToSend) ||
+                !write(port, PROTO_EOC) ||
+                !getCommandResponse(port, warnOnError)) {
+            _errorString = tr("Flash failed: %1").arg(_errorString);
+            qWarning() << _errorString;
+            return false;
+        }
+        
+        bytesSent += bytesToSend;
+        
+        // Calculate the CRC now so we can test it after the board is flashed.
+        _imageCRC = crc32((uint8_t *)imageBuf, bytesToSend, _imageCRC);
+        
+        emit updateProgramProgress(bytesSent, imageSize);
+    }
+    firmwareFile.close();
+    
+    // We calculate the CRC using the entire flash size, filling the remainder with 0xFF.
+    while (bytesSent < _boardFlashSize) {
+        const uint8_t fill = 0xFF;
+        _imageCRC = crc32(&fill, 1, _imageCRC);
+        bytesSent++;
+    }
+    
+    return true;
+}
+
+bool PX4Bootloader::verify(QSerialPort* port, const QString firmwareFilename)
+{
+    bool ret;
+    
+    if (_bootloaderVersion <= 2) {
+        ret = _bootloaderVerifyRev2(port, firmwareFilename);
+    } else {
+        ret = _bootloaderVerifyRev3(port);
+    }
+    
+    sendBootloaderReboot(port);
+    
+    return ret;
+}
+
+/// @brief Verify the flash on bootloader version 2 by reading it back and comparing it against
+/// the original firmware file.
+bool PX4Bootloader::_bootloaderVerifyRev2(QSerialPort* port, const QString firmwareFilename)
+{
+    QFile firmwareFile(firmwareFilename);
+    if (!firmwareFile.open(QIODevice::ReadOnly)) {
+        _errorString = tr("Unable to open firmware file %1: %2").arg(firmwareFilename).arg(firmwareFile.errorString());
+        qWarning() << _errorString;
+        return false;
+    }
+    uint32_t imageSize = (uint32_t)firmwareFile.size();
+    
+    if (!sendCommand(port, PROTO_CHIP_VERIFY, warnOnError)) {
+        return false;
+    }
+    
+    uint8_t fileBuf[READ_MULTI_MAX];
+    uint8_t flashBuf[READ_MULTI_MAX];
+    uint32_t bytesVerified = 0;
+    
+    Q_ASSERT(PROG_MULTI_MAX <= 0x8F);
+    
+    while (bytesVerified < imageSize) {
+        int bytesToRead = imageSize - bytesVerified;
+        if (bytesToRead > (int)sizeof(fileBuf)) {
+            bytesToRead = (int)sizeof(fileBuf);
+        }
+        
+        Q_ASSERT((bytesToRead % 4) == 0);
+        
+        int bytesRead = firmwareFile.read((char *)fileBuf, bytesToRead);
+        if (bytesRead == -1 || bytesRead != bytesToRead) {
+            _errorString = tr("Read failed: %1").arg(firmwareFile.errorString());
+            qWarning() << _errorString;
+            return false;
+        }
+        
+        Q_ASSERT(bytesToRead <= 0x8F);
+        
+        if (!write(port, PROTO_READ_MULTI) ||
+                !write(port, (uint8_t)bytesToRead) ||
+                !write(port, PROTO_EOC) ||
+                !read(port, flashBuf, sizeof(flashBuf), warnOnError) ||
+                !getCommandResponse(port, warnOnError)) {
+            return false;
+        }
+
+        for (int i=0; i<bytesToRead; i++) {
+            if (fileBuf[i] != flashBuf[i]) {
+                _errorString = tr("Compare failed at %1: file(0x%2) flash(0x%3)").arg(bytesVerified + i).arg(fileBuf[i], 2, 16, QLatin1Char('0')).arg(flashBuf[i], 2, 16, QLatin1Char('0'));
+                qWarning() << _errorString;
+                return false;
+            }
+        }
+        
+        bytesVerified += bytesToRead;
+    }
+    firmwareFile.close();
+    
+    return true;
+}
+
+/// @Brief Verify the flash on a version 3 or higher bootloader board by comparing CRCs.
+bool PX4Bootloader::_bootloaderVerifyRev3(QSerialPort* port)
+{
+    return true;
+    
+    uint8_t buf[2] = { PROTO_GET_CRC, PROTO_EOC };
+    quint32 flashCRC;
+    
+    if (!write(port, buf, 2) ||
+        !read(port, (uint8_t*)&flashCRC, sizeof(flashCRC), warnOnError, _verifyTimeout) ||
+        !getCommandResponse(port, warnOnError)) {
+        return false;
+    }
+
+    if (_imageCRC != flashCRC) {
+        _errorString = tr("CRC mismatch: board(0x%1) file(0x%2)").arg(flashCRC, 4, 16, QLatin1Char('0')).arg(_imageCRC, 4, 16, QLatin1Char('0'));
+        return false;
+    }
+    
+    return true;
+}
+
+bool PX4Bootloader::open(QSerialPort* port, const QString portName)
+{
+    Q_ASSERT(!port->isOpen());
+    
+    port->setPortName(portName);
+    port->setBaudRate(QSerialPort::Baud115200);
+    port->setDataBits(QSerialPort::Data8);
+    port->setParity(QSerialPort::NoParity);
+    port->setStopBits(QSerialPort::OneStop);
+    port->setFlowControl(QSerialPort::NoFlowControl);
+    
+    if (!port->open(QIODevice::ReadWrite)) {
+        _errorString = tr("Open failed on port %1: %2").arg(portName).arg(_serialPortErrorString(port->error()));
+        qWarning() << _errorString;
+        return false;
+    }
+    
+    return true;
+}
+
+bool PX4Bootloader::sync(QSerialPort* port)
+{
+    // Drain out any remaining input or output from the port
+    if (!port->clear()) {
+        _errorString = tr("Unable to clear port");
+        qWarning() << _errorString;
+        return false;
+    }
+    
+    // Send sync command
+    return sendCommand(port, PROTO_GET_SYNC, noWarnOnError);
+}
+
+bool PX4Bootloader::getBoardInfo(QSerialPort* port, uint32_t& bootloaderVersion, uint32_t& boardID, uint32_t& flashSize)
+{
+    
+    if (!getBoardInfo(port, INFO_BL_REV, _bootloaderVersion)) {
+        goto Error;
+    }
+    if (_bootloaderVersion < BL_REV_MIN || _bootloaderVersion > BL_REV_MAX) {
+        _errorString = tr("Found unsupported bootloader version: %1").arg(_bootloaderVersion);
+        qWarning() << _errorString;
+        goto Error;
+    }
+    
+    if (!getBoardInfo(port, INFO_BOARD_ID, _boardID)) {
+        goto Error;
+    }
+    if (_boardID != _boardIDPX4Flow && _boardID != _boardIDPX4FMUV1 && _boardID != _boardIDPX4FMUV2) {
+        _errorString = tr("Unsupported board: %1").arg(_boardID);
+        qWarning() << _errorString;
+        goto Error;
+    }
+    
+    if (!getBoardInfo(port, INFO_FLASH_SIZE, _boardFlashSize)) {
+        qWarning() << _errorString;
+        goto Error;
+    }
+    
+    bootloaderVersion = _bootloaderVersion;
+    boardID = _boardID;
+    flashSize = _boardFlashSize;
+    
+    return true;
+    
+Error:
+    return false;
+}
+
+bool PX4Bootloader::sendBootloaderReboot(QSerialPort* port)
+{
+    return write(port, PROTO_BOOT) && write(port, PROTO_EOC);
+}
diff --git a/src/ui/px4_configuration/PX4Bootloader.h b/src/ui/px4_configuration/PX4Bootloader.h
new file mode 100644
index 0000000000000000000000000000000000000000..566bc001832c1e2c2ca7d12d7cc14a754f37a318
--- /dev/null
+++ b/src/ui/px4_configuration/PX4Bootloader.h
@@ -0,0 +1,178 @@
+/*=====================================================================
+ 
+ QGroundControl Open Source Ground Control Station
+ 
+ (c) 2009, 2014 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org>
+ 
+ This file is part of the QGROUNDCONTROL project
+ 
+ QGROUNDCONTROL is free software: you can redistribute it and/or modify
+ it under the terms of the GNU General Public License as published by
+ the Free Software Foundation, either version 3 of the License, or
+ (at your option) any later version.
+ 
+ QGROUNDCONTROL is distributed in the hope that it will be useful,
+ but WITHOUT ANY WARRANTY; without even the implied warranty of
+ MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
+ GNU General Public License for more details.
+ 
+ You should have received a copy of the GNU General Public License
+ along with QGROUNDCONTROL. If not, see <http://www.gnu.org/licenses/>.
+ 
+ ======================================================================*/
+
+/// @file
+///     @brief PX4 Bootloader Utility routines
+///     @author Don Gagne <don@thegagnes.com>
+
+#ifndef PX4Bootloader_H
+#define PX4Bootloader_H
+
+#include <QSerialPort>
+
+#include <stdint.h>
+
+/// @brief This class is used to communicate with the Bootloader.
+class PX4Bootloader : public QObject
+{
+    Q_OBJECT
+    
+public:
+    explicit PX4Bootloader(QObject *parent = 0);
+    
+    /// @brief Returns the error message associated with the last failed call to one of the bootloader
+    ///         utility routine below.
+    QString errorString(void) { return _errorString; }
+
+    static const bool warnOnError = true;       ///< call qWarning to log error message on error
+    static const bool noWarnOnError = false;    ///< Don't call qWarning on error
+    
+    /// @brief Write a byte to the port
+    ///     @param port Port to write to
+    ///     @param data Bytes to write
+    ///     @param maxSize Number of bytes to write
+    /// @return true: success
+    bool write(QSerialPort* port, const uint8_t* data, qint64 maxSize);
+    bool write(QSerialPort* port, const uint8_t byte);
+    
+    /// @brief Read a set of bytes from the port
+    ///     @param data Read bytes into this buffer
+    ///     @param maxSize Number of bytes to read
+    ///     @param warnOnError true: Log error using qWarning
+    ///     @param readTimeout Msecs to wait for bytes to become available on port
+    bool read(QSerialPort* port, uint8_t* data, qint64 maxSize, bool warnOnError, int readTimeout = _readTimout);
+    
+    /// @brief Read a PROTO_SYNC command response from the bootloader
+    ///     @param responseTimeout Msecs to wait for response bytes to become available on port
+    bool getCommandResponse(QSerialPort* port, bool warnOnError, const int responseTimeout = _responseTimeout);
+    
+    /// @brief Send a PROTO_GET_DEVICE command to retrieve a value from the bootloader
+    ///     @param param Value to retrieve using INFO_BOARD_* enums
+    ///     @param value Returned value
+    bool getBoardInfo(QSerialPort* port, uint8_t param, uint32_t& value);
+    
+    /// @brief Send a command to the bootloader
+    ///     @param cmd Command to send using PROTO_* enums
+    /// @return true: Command sent and valid sync response returned
+    bool sendCommand(QSerialPort* port, uint8_t cmd, bool warnOnError, int responseTimeout = _responseTimeout);
+    
+    /// @brief Program the board with the specified firmware
+    bool program(QSerialPort* port, const QString& firmwareFilename);
+    
+    /// @brief Verify the board flash. How it works depend on bootloader rev
+    ///         Rev 2: Read the flash back and compare it against the firmware file
+    ///         Rev 3: Compare CRCs for flash and file
+    bool verify(QSerialPort* port, const QString firmwareFilename);
+    
+    /// @brief Read a PROTO_SYNC response from the bootloader
+    /// @return true: Valid sync response was received
+    bool sync(QSerialPort* port);
+    
+    /// @brief Retrieve a set of board info from the bootloader
+    ///     @param bootloaderVersion Returned INFO_BL_REV
+    ///     @param boardID Returned INFO_BOARD_ID
+    ///     @param flashSize Returned INFO_FLASH_SIZE
+    bool getBoardInfo(QSerialPort* port, uint32_t& bootloaderVersion, uint32_t& boardID, uint32_t& flashSize);
+    
+    /// @brief Opens a port to the bootloader
+    bool open(QSerialPort* port, const QString portName);
+    
+    /// @brief Sends a PROTO_REBOOT command to the bootloader
+    bool sendBootloaderReboot(QSerialPort* port);
+    
+    /// @brief Sends a PROTO_ERASE command to the bootlader
+    bool erase(QSerialPort* port);
+    
+signals:
+    /// @brief Signals progress indicator for long running bootloader utility routines
+    void updateProgramProgress(int curr, int total);
+    
+private:
+    enum {
+        // protocol bytes
+        PROTO_INSYNC =      0x12,   ///< 'in sync' byte sent before status
+        PROTO_EOC = 		0x20,   ///< end of command
+        
+        // Reply bytes
+        PROTO_OK =          0x10,   ///< INSYNC/OK      - 'ok' response
+        PROTO_FAILED =		0x11,   ///< INSYNC/FAILED  - 'fail' response
+        PROTO_INVALID =		0x13,	///< INSYNC/INVALID - 'invalid' response for bad commands
+        
+        // Command bytes
+        PROTO_GET_SYNC =	0x21,   ///< NOP for re-establishing sync
+        PROTO_GET_DEVICE =	0x22,   ///< get device ID bytes
+        PROTO_CHIP_ERASE =	0x23,   ///< erase program area and reset program address
+        PROTO_PROG_MULTI =	0x27,   ///< write bytes at program address and increment
+        PROTO_GET_CRC =		0x29,	///< compute & return a CRC
+        PROTO_BOOT =		0x30,   ///< boot the application
+        
+        // Command bytes - Rev 2 boootloader only
+        PROTO_CHIP_VERIFY	= 0x24, ///< begin verify mode
+        PROTO_READ_MULTI	= 0x28, ///< read bytes at programm address and increment
+        
+        INFO_BL_REV         = 1,    ///< bootloader protocol revision
+        BL_REV_MIN          = 2,    ///< Minimum supported bootlader protocol
+        BL_REV_MAX			= 4,    ///< Maximum supported bootloader protocol
+        INFO_BOARD_ID		= 2,    ///< board type
+        INFO_BOARD_REV		= 3,    ///< board revision
+        INFO_FLASH_SIZE		= 4,    ///< max firmware size in bytes
+        
+        PROG_MULTI_MAX		= 32,   ///< write size for PROTO_PROG_MULTI, must be multiple of 4
+        READ_MULTI_MAX		= 64    ///< read size for PROTO_READ_MULTI, must be multiple of 4
+    };
+    
+    struct serialPortErrorString {
+        int         error;
+        const char* errorString;
+    };
+    
+    bool _findBootloader(void);
+    bool _downloadFirmware(void);
+    bool _bootloaderVerifyRev2(QSerialPort* port, const QString firmwareFilename);
+    bool _bootloaderVerifyRev3(QSerialPort* port);
+    
+    const char* _serialPortErrorString(int error);
+    
+    static const int _boardIDPX4FMUV1 = 5;  ///< Board ID for PX4 V1 board
+    static const int _boardIDPX4FMUV2 = 9;  ///< Board ID for PX4 V2 board
+    static const int _boardIDPX4Flow = 6;   ///< Board ID for PX4 Floaw board
+    
+    uint32_t    _boardID;           ///< board id for currently connected board
+    uint32_t    _boardFlashSize;    ///< flash size for currently connected board
+    uint32_t    _imageCRC;          ///< CRC for image in currently selected firmware file
+    uint32_t    _bootloaderVersion; ///< Bootloader version
+    
+    QString _firmwareFilename;      ///< Currently selected firmware file to flash
+    
+    QString _errorString;           ///< Last error
+    
+    static const struct serialPortErrorString _rgSerialPortErrors[14];  ///< Translation of QSerialPort::SerialPortError into string
+    
+    static const int _eraseTimeout = 20000;     ///< Msecs to wait for response from erase command
+    static const int _rebootTimeout = 10000;    ///< Msecs to wait for reboot command to cause serial port to disconnect
+    static const int _verifyTimeout = 5000;     ///< Msecs to wait for response to PROTO_GET_CRC command
+    static const int _readTimout = 2000;        ///< Msecs to wait for read bytes to become avilable
+    static const int _responseTimeout = 2000;   ///< Msecs to wait for command response bytes
+};
+
+#endif // PX4FirmwareUpgrade_H
diff --git a/src/ui/px4_configuration/PX4FirmwareUpgrade.cc b/src/ui/px4_configuration/PX4FirmwareUpgrade.cc
new file mode 100644
index 0000000000000000000000000000000000000000..70c1e067cedcde58be55ae3dc6ec3076df6310a7
--- /dev/null
+++ b/src/ui/px4_configuration/PX4FirmwareUpgrade.cc
@@ -0,0 +1,815 @@
+/*=====================================================================
+ 
+ QGroundControl Open Source Ground Control Station
+ 
+ (c) 2009, 2014 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org>
+ 
+ This file is part of the QGROUNDCONTROL project
+ 
+ QGROUNDCONTROL is free software: you can redistribute it and/or modify
+ it under the terms of the GNU General Public License as published by
+ the Free Software Foundation, either version 3 of the License, or
+ (at your option) any later version.
+ 
+ QGROUNDCONTROL is distributed in the hope that it will be useful,
+ but WITHOUT ANY WARRANTY; without even the implied warranty of
+ MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
+ GNU General Public License for more details.
+ 
+ You should have received a copy of the GNU General Public License
+ along with QGROUNDCONTROL. If not, see <http://www.gnu.org/licenses/>.
+ 
+ ======================================================================*/
+
+/// @file
+///     @brief PX4 Firmware Upgrade UI
+///     @author Don Gagne <don@thegagnes.com>
+
+#include "PX4FirmwareUpgrade.h"
+
+#include <QFile>
+#include <QFileInfo>
+#include <QStandardPaths>
+#include <QJsonDocument>
+#include <QJsonObject>
+#include <QDir>
+#include <QFileDialog>
+#include <QDebug>
+
+/// @Brief Constructs a new PX4FirmwareUpgrade Widget. This widget is used within the PX4VehicleConfig set of screens.
+PX4FirmwareUpgrade::PX4FirmwareUpgrade(QWidget *parent) :
+    QWidget(parent),
+    _upgradeState(upgradeStateBegin),
+    _downloadManager(NULL),
+    _downloadNetworkReply(NULL)
+{
+    _ui = new Ui::PX4FirmwareUpgrade;
+    _ui->setupUi(this);
+    
+    _threadController = new PX4FirmwareUpgradeThreadController(this);
+    Q_CHECK_PTR(_threadController);
+
+    // Connect standard ui elements
+    connect(_ui->tryAgain, &QPushButton::clicked, this, &PX4FirmwareUpgrade::_tryAgainButton);
+    connect(_ui->cancel, &QPushButton::clicked, this, &PX4FirmwareUpgrade::_cancelButton);
+    connect(_ui->next, &QPushButton::clicked, this, &PX4FirmwareUpgrade::_nextButton);
+    connect(_ui->firmwareCombo, SIGNAL(currentIndexChanged(int)), this, SLOT(_firmwareSelected(int)));
+    
+    connect(_threadController, &PX4FirmwareUpgradeThreadController::foundBoard, this, &PX4FirmwareUpgrade::_foundBoard);
+    connect(_threadController, &PX4FirmwareUpgradeThreadController::foundBootloader, this, &PX4FirmwareUpgrade::_foundBootloader);
+    connect(_threadController, &PX4FirmwareUpgradeThreadController::bootloaderSyncFailed, this, &PX4FirmwareUpgrade::_bootloaderSyncFailed);
+    connect(_threadController, &PX4FirmwareUpgradeThreadController::error, this, &PX4FirmwareUpgrade::_error);
+    connect(_threadController, &PX4FirmwareUpgradeThreadController::complete, this, &PX4FirmwareUpgrade::_complete);
+    connect(_threadController, &PX4FirmwareUpgradeThreadController::findTimeout, this, &PX4FirmwareUpgrade::_findTimeout);
+    connect(_threadController, &PX4FirmwareUpgradeThreadController::updateProgress, this, &PX4FirmwareUpgrade::_updateProgress);
+    
+    connect(&_eraseTimer, &QTimer::timeout, this, &PX4FirmwareUpgrade::_eraseProgressTick);
+    
+    _setupState(upgradeStateBegin);
+}
+
+PX4FirmwareUpgrade::~PX4FirmwareUpgrade()
+{
+}
+
+/// @brief Returns the state machine entry for the specified state.
+const PX4FirmwareUpgrade::stateMachineEntry* PX4FirmwareUpgrade::_getStateMachineEntry(enum PX4FirmwareUpgrade::upgradeStates state)
+{
+    static const char* msgBegin = "If you are currently connected to your Pixhawk board via QGroundControl, you must 'Disconnect' from the board. "
+                                    "If your board is connected via USB, you must unplug the USB cable.\n\n"
+                                    "Click 'Next' when these two steps are complete to begin upgrading.";
+    static const char* msgBoardSearch = "Plug in your board via USB now...";
+    static const char* msgBoardNotFound = "Unable to detect your board. If the board is currently connected via USB. Disconnect it, and click 'Try Again'.";
+    static const char* msgBootloaderSearch = "Searching for Bootloader...";
+    static const char* msgBootloaderNotFound = "Unable to connect to Bootloader. If the board is currently connected via USB. Disconnect it, and click 'Try Again'.";
+    static const char* msgBootloaderError = "An error occured while communicating with the Bootloader.";
+    static const char* msgFirmwareSelect = "Please select the firmware you would like to upload to the board from the dropdown to the right.";
+    static const char* msgFirmwareDownloading = "Firmware downloading...";
+    static const char* msgFirmwareDownloadFailed = "Firmware download failed";
+    static const char* msgFirmwareBoardErasing = "Erasing old firmware from board...";
+    static const char* msgFirmwareBoardEraseFailed = "Board erase failed.";
+    static const char* msgFirmwareBoardFlashing = "Flashing new firmware onto board...";
+    static const char* msgFirmwareBoardFlashError = "A failure has occured while flashing the new firmware to your board. "
+                                                        "This has left the board in an inconsistent state. "
+                                                        "You should click 'Try Again' to attempt the upgrade process again.";
+    static const char* msgFirmwareBoardVerifying = "Verifying firmware on board...";
+    static const char* msgFirmwareBoardVerifyError = "Verification of flash memory on board failed. "
+                                                    "This has left the board in an inconsistent state. "
+                                                    "You should click 'Try Again' to attempt the upgrade process again.";
+    static const char* msgFirmwareBoardUpgraded = "Your board has been upgraded successfully.\n\nYou can now connect to your board via QGroundControl\n\nClick 'Try Again' to do another upgrade.";
+
+    static const stateMachineEntry rgStateMachine[] = {
+        //State                                     Next command                            Cancel command                              Try Again command           State Text
+        { upgradeStateBegin,                        &PX4FirmwareUpgrade::_findBoard,        NULL,                                       NULL,                               msgBegin },
+        { upgradeStateBoardSearch,                  NULL,                                   &PX4FirmwareUpgrade::_cancelFind,           NULL,                               msgBoardSearch },
+        { upgradeStateBoardNotFound,                NULL,                                   &PX4FirmwareUpgrade::_cancel,               &PX4FirmwareUpgrade::_findBoard,    msgBoardNotFound },
+        { upgradeStateBootloaderSearch,             NULL,                                   &PX4FirmwareUpgrade::_cancelFind,           NULL,                               msgBootloaderSearch },
+        { upgradeStateBootloaderNotFound,           NULL,                                   &PX4FirmwareUpgrade::_cancel,               &PX4FirmwareUpgrade::_restart,      msgBootloaderNotFound },
+        { upgradeStateBootloaderError,              NULL,                                   &PX4FirmwareUpgrade::_cancel,               NULL,                               msgBootloaderError },
+        { upgradeStateFirmwareSelect,               &PX4FirmwareUpgrade::_getFirmwareFile,  &PX4FirmwareUpgrade::_cancel,               NULL,                               msgFirmwareSelect },
+        { upgradeStateFirmwareDownloading,          NULL,                                   &PX4FirmwareUpgrade::_cancelDownload,       NULL,                               msgFirmwareDownloading },
+        { upgradeStateDownloadFailed,               NULL,                                   NULL,                                       &PX4FirmwareUpgrade::_restart,      msgFirmwareDownloadFailed },
+        { upgradeStateErasing,                      NULL,                                   NULL,                                       NULL,                               msgFirmwareBoardErasing },
+        { upgradeStateEraseError,                   NULL,                                   &PX4FirmwareUpgrade::_cancel,               NULL,                               msgFirmwareBoardEraseFailed },
+        { upgradeStateFlashing,                     NULL,                                   NULL,                                       NULL,                               msgFirmwareBoardFlashing },
+        { upgradeStateFlashError,                   NULL,                                   NULL,                                       &PX4FirmwareUpgrade::_restart,      msgFirmwareBoardFlashError },
+        { upgradeStateVerifying,                    NULL,                                   NULL,                                       NULL,                               msgFirmwareBoardVerifying },
+        { upgradeStateVerifyError,                  NULL,                                   NULL,                                       &PX4FirmwareUpgrade::_restart,      msgFirmwareBoardVerifyError },
+        { upgradeStateBoardUpgraded,                NULL,                                   NULL,                                       &PX4FirmwareUpgrade::_restart,      msgFirmwareBoardUpgraded },
+    };
+    
+    const stateMachineEntry* entry = &rgStateMachine[state];
+    
+    // Validate that our state array has not gotten out of sync
+    for (size_t i=0; i<upgradeStateMax; i++) {
+        Q_ASSERT(rgStateMachine[i].state == i);
+    }
+
+    return entry;
+}
+
+/// @brief Sets up the Wizard according to the specified state
+void PX4FirmwareUpgrade::_setupState(enum PX4FirmwareUpgrade::upgradeStates state)
+{
+    _upgradeState = state;
+    
+    const stateMachineEntry* stateMachine = _getStateMachineEntry(state);
+    
+    _ui->tryAgain->setEnabled(stateMachine->tryAgain != NULL);
+    _ui->skip->setEnabled(false);
+    _ui->cancel->setEnabled(stateMachine->cancel != NULL);
+    _ui->next->setEnabled(stateMachine->next != NULL);
+    
+    _ui->statusLog->setText(stateMachine->msg);
+    
+    if (_upgradeState == upgradeStateDownloadFailed) {
+        // Bootloader is still open, reboot to close and heopfully get back to FMU
+        _threadController->sendBootloaderReboot();
+    }
+    
+    _updateIndicatorUI();
+}
+
+/// @brief Updates the Indicator UI which is to the right of the Wizard area to match the current
+///         upgrade state.
+void PX4FirmwareUpgrade::_updateIndicatorUI(void)
+{
+    if (_upgradeState == upgradeStateBegin) {
+        // Reset to intial state. All check boxes unchecked, all additional information hidden.
+        
+        _ui->statusLabel->clear();
+        
+        _ui->progressBar->setValue(0);
+        _ui->progressBar->setTextVisible(false);
+        
+        _ui->boardFoundCheck->setCheckState(Qt::Unchecked);
+        _ui->port->setVisible(false);
+        _ui->description->setVisible(false);
+        
+        _ui->bootloaderFoundCheck->setCheckState(Qt::Unchecked);
+        _ui->bootloaderVersion->setVisible(false);
+        _ui->boardID->setVisible(false);
+        _ui->icon->setVisible(false);
+        
+        _ui->firmwareCombo->setVisible(false);
+        _ui->firmwareCombo->setEnabled(true);
+        
+        _ui->selectFirmwareCheck->setCheckState(Qt::Unchecked);
+        _ui->firmwareDownloadedCheck->setCheckState(Qt::Unchecked);
+        _ui->boardUpgradedCheck->setCheckState(Qt::Unchecked);
+        
+    } else if (_upgradeState == upgradeStateBootloaderSearch){
+        // We have found the board
+        
+        _ui->statusLabel->clear();
+        
+        _ui->progressBar->setValue(0);
+        
+        _ui->boardFoundCheck->setCheckState(Qt::Checked);
+        
+        _ui->port->setText("Port: " + _portName);
+        _ui->description->setText("Name: " +_portDescription);
+        
+        _ui->port->setVisible(true);
+        _ui->description->setVisible(true);
+        
+    } else if (_upgradeState == upgradeStateFirmwareSelect) {
+        // We've found the bootloader and need to set up firmware selection
+        
+        _ui->statusLabel->clear();
+
+        _ui->progressBar->setValue(0);
+        
+        _ui->bootloaderFoundCheck->setCheckState(Qt::Checked);
+        
+        
+        _ui->bootloaderVersion->setText(QString("Version: %1").arg(_bootloaderVersion));
+        _ui->boardID->setText(QString("Board ID: %1").arg(_boardID));
+        _setBoardIcon(_boardID);
+        _setFirmwareCombo(_boardID);
+        
+        _ui->bootloaderVersion->setVisible(true);
+        _ui->boardID->setVisible(true);
+        _ui->icon->setVisible(true);
+        _ui->firmwareCombo->setVisible(true);
+        _ui->firmwareCombo->setEnabled(true);
+        _ui->firmwareCombo->setCurrentIndex(0);
+        
+    } else if (_upgradeState == upgradeStateFirmwareDownloading) {
+        
+        _ui->statusLabel->clear();
+        _ui->selectFirmwareCheck->setCheckState(Qt::Checked);
+        _ui->firmwareCombo->setEnabled(false);
+        
+    } else if (_upgradeState == upgradeStateFlashing) {
+        
+        _ui->statusLabel->clear();
+        _ui->progressBar->setValue(0);
+        _ui->firmwareDownloadedCheck->setCheckState(Qt::Checked);
+        
+    } else if (_upgradeState == upgradeStateBoardUpgraded) {
+        
+        _ui->statusLabel->clear();
+        _ui->progressBar->setValue(0);
+        _ui->boardUpgradedCheck->setCheckState((_upgradeState >= upgradeStateBoardUpgraded) ? Qt::Checked : Qt::Unchecked);
+        
+    }
+}
+
+/// @brief Responds to a click on the Next Button calling the appropriate method as specified by the state machine.
+void PX4FirmwareUpgrade::_nextButton(void)
+{
+    const stateMachineEntry* stateMachine = _getStateMachineEntry(_upgradeState);
+    
+    Q_ASSERT(stateMachine->next != NULL);
+    
+    (this->*stateMachine->next)();
+}
+
+
+/// @brief Responds to a click on the Cancel Button calling the appropriate method as specified by the state machine.
+void PX4FirmwareUpgrade::_cancelButton(void)
+{
+    const stateMachineEntry* stateMachine = _getStateMachineEntry(_upgradeState);
+    
+    Q_ASSERT(stateMachine->cancel != NULL);
+    
+    (this->*stateMachine->cancel)();
+}
+
+/// @brief Responds to a click on the Try Again Button calling the appropriate method as specified by the state machine.
+void PX4FirmwareUpgrade::_tryAgainButton(void)
+{
+    const stateMachineEntry* stateMachine = _getStateMachineEntry(_upgradeState);
+    
+    Q_ASSERT(stateMachine->tryAgain != NULL);
+    
+    (this->*stateMachine->tryAgain)();
+}
+
+/// @brief Cancels a findBoard or findBootloader operation.
+void PX4FirmwareUpgrade::_cancelFind(void)
+{
+    _threadController->cancelFind();
+}
+
+/// @brief Cancels the current state and returns to the begin start
+void PX4FirmwareUpgrade::_cancel(void)
+{
+    _setupState(upgradeStateBegin);
+}
+
+/// @brief Begins the process or searching for the board
+void PX4FirmwareUpgrade::_findBoard(void)
+{
+    _setupState(upgradeStateBoardSearch);
+    _threadController->findBoard(_findBoardTimeoutMsec);
+}
+
+/// @brief Called when board has been found by the findBoard process
+void PX4FirmwareUpgrade::_foundBoard(const QString portName, QString portDescription)
+{
+    _portName = portName;
+    _portDescription = portDescription;
+    _setupState(upgradeStateBootloaderSearch);
+    _findBootloader();
+}
+
+/// @brief Begins the findBootloader process to connect to the bootloader
+void PX4FirmwareUpgrade::_findBootloader(void)
+{
+    _setupState(upgradeStateBootloaderSearch);
+    _threadController->findBootloader(_portName, _findBootloaderTimeoutMsec);
+}
+
+/// @brief Called when the bootloader is connected to by the findBootloader process. Moves the state machine
+///         to the next step.
+void PX4FirmwareUpgrade::_foundBootloader(int bootloaderVersion, int boardID, int flashSize)
+{
+    _bootloaderVersion = bootloaderVersion;
+    _boardID = boardID;
+    _boardFlashSize = flashSize;
+    _setupState(upgradeStateFirmwareSelect);
+}
+
+/// @brief Called when the findBootloader process is unable to sync to the bootloader. Moves the state
+///         machine to the appropriate error state.
+void PX4FirmwareUpgrade::_bootloaderSyncFailed(void)
+{
+    if (_upgradeState == upgradeStateBootloaderSearch) {
+        // We can connect to the board, but we still can't talk to the bootloader.
+        qDebug() << "Bootloader sync failed";
+        _setupState(upgradeStateBootloaderNotFound);
+    } else {
+        Q_ASSERT(false);
+    }
+    
+}
+
+/// @brief Called when the findBoard or findBootloader process times out. Moves the state machine to the
+///         appropriate error state.
+void PX4FirmwareUpgrade::_findTimeout(void)
+{
+    if (_upgradeState == upgradeStateBoardSearch) {
+        qDebug() << "Timeout on board search";
+        _setupState(upgradeStateBoardNotFound);
+    } else if (_upgradeState == upgradeStateBootloaderSearch) {
+        qDebug() << "Timeout on bootloader search";
+        _setupState(upgradeStateBoardNotFound);
+    } else {
+        Q_ASSERT(false);
+    }
+}
+
+/// @brief Sets the board image into the icon label according to the board id.
+void PX4FirmwareUpgrade::_setBoardIcon(int boardID)
+{
+    QString imageFile;
+    
+    switch (boardID) {
+        case _boardIDPX4FMUV1:
+            imageFile = ":/files/images/px4/boards/px4fmu_1.x.png";
+            break;
+            
+        case _boardIDPX4Flow:
+            imageFile = ":/files/images/px4/boards/px4flow_1.x.png";
+            break;
+            
+        case _boardIDPX4FMUV2:
+            imageFile = ":/files/images/px4/boards/px4fmu_2.x.png";
+            break;
+    }
+    
+    if (!imageFile.isEmpty()) {
+        bool success = _boardIcon.load(imageFile);
+        Q_ASSERT(success);
+        Q_UNUSED(success);
+        
+        int w = _ui->icon->width();
+        int h = _ui->icon->height();
+        
+        _ui->icon->setPixmap(_boardIcon.scaled(w, h, Qt::KeepAspectRatio));
+    }
+}
+
+/// @brief Sets up the selections in the firmware combox box associated with the specified
+///     board id.
+void PX4FirmwareUpgrade::_setFirmwareCombo(int boardID)
+{
+    _ui->firmwareCombo->clear();
+    
+    static const char* rgPX4FMUV1Firmware[3] =
+    {
+        "http://px4.oznet.ch/stable/px4fmu-v1_default.px4",
+        "http://px4.oznet.ch/beta/px4fmu-v1_default.px4",
+        "http://px4.oznet.ch/continuous/px4fmu-v1_default.px4"
+    };
+    
+    static const char* rgPX4FMUV2Firmware[3] =
+    {
+        "http://px4.oznet.ch/stable/px4fmu-v2_default.px4",
+        "http://px4.oznet.ch/beta/px4fmu-v2_default.px4",
+        "http://px4.oznet.ch/continuous/px4fmu-v2_default.px4"
+    };
+    
+    static const char* rgPX4FlowFirmware[3] =
+    {
+        "http://px4.oznet.ch/stable/px4flow.px4",
+        "http://px4.oznet.ch/beta/px4flow.px4",
+        "http://px4.oznet.ch/continuous/px4flow.px4"
+    };
+    
+    const char** prgFirmware;
+    switch (boardID) {
+        case _boardIDPX4FMUV1:
+            prgFirmware = rgPX4FMUV1Firmware;
+            break;
+
+        case _boardIDPX4Flow:
+            prgFirmware = rgPX4FlowFirmware;
+            break;
+
+        case _boardIDPX4FMUV2:
+            prgFirmware = rgPX4FMUV2Firmware;
+            break;
+            
+        default:
+            prgFirmware = NULL;
+            break;
+    }
+
+    if (prgFirmware) {
+        _ui->firmwareCombo->addItem(tr("Standard Version (stable)"), prgFirmware[0]);
+        _ui->firmwareCombo->addItem(tr("Beta Testing (beta)"), prgFirmware[1]);
+        _ui->firmwareCombo->addItem(tr("Developer Build (master)"), prgFirmware[2]);
+    }
+    _ui->firmwareCombo->addItem(tr("Custom firmware file..."), "selectfile");
+}
+
+/// @brief Called when the selection in the firmware combo box changes. Updates the wizard
+///         text appropriately with licensing and possibly warning information.
+void PX4FirmwareUpgrade::_firmwareSelected(int index)
+{
+#define SELECT_FIRMWARE_LICENSE "By clicking Next you agree to the terms and disclaimer of the BSD open source license, as redistributed with the source code."
+    
+    if (_upgradeState == upgradeStateFirmwareSelect) {
+        switch (index) {
+            case 0:
+            case 3:
+                _ui->statusLog->setText(tr(SELECT_FIRMWARE_LICENSE));
+                break;
+                
+            case 1:
+                _ui->statusLog->setText(tr("WARNING: BETA FIRMWARE\n"
+                                           "This firmware version is ONLY intended for beta testers. "
+                                           "Although it has received FLIGHT TESTING, it represents actively changed code. Do NOT use for normal operation.\n\n"
+                                           SELECT_FIRMWARE_LICENSE));
+                break;
+                
+            case 2:
+                _ui->statusLog->setText(tr("WARNING: CONTINUOUS BUILD FIRMWARE\n"
+                                           "This firmware has NOT BEEN FLIGHT TESTED. "
+                                           "It is only intended for DEVELOPERS. Run bench tests without props first. "
+                                           "Do NOT fly this without addional safety precautions. Follow the mailing "
+                                           "list actively when using it.\n\n"
+                                           SELECT_FIRMWARE_LICENSE));
+                break;
+        }
+        _ui->next->setEnabled(!_ui->firmwareCombo->itemData(index).toString().isEmpty());
+    }
+}
+
+/// @brief Prompts the user to select a firmware file if needed and moves the state machine to the
+///         download firmware state.
+void PX4FirmwareUpgrade::_getFirmwareFile(void)
+{
+    int index = _ui->firmwareCombo->currentIndex();
+    _firmwareFilename = _ui->firmwareCombo->itemData(index).toString();
+    Q_ASSERT(!_firmwareFilename.isEmpty());
+    if (_firmwareFilename == "selectfile") {
+        _firmwareFilename = QFileDialog::getOpenFileName(this,
+                                                    tr("Select Firmware File"),                                             // Dialog title
+                                                     QStandardPaths::writableLocation(QStandardPaths::DocumentsLocation),   // Initial directory
+                                                     tr("Firmware Files (*.px4 *.bin)"));                                   // File filter
+
+    }
+    if (!_firmwareFilename.isEmpty()) {
+        _downloadFirmware();
+    }
+}
+
+/// @brief Begins the process of downloading the selected firmware file.
+void PX4FirmwareUpgrade::_downloadFirmware(void)
+{
+    // Split out filename from path
+    Q_ASSERT(!_firmwareFilename.isEmpty());
+    QString firmwareFilename = QFileInfo(_firmwareFilename).fileName();
+    Q_ASSERT(!firmwareFilename.isEmpty());
+    
+    // Determine location to download file to
+    QString downloadFile = QStandardPaths::writableLocation(QStandardPaths::TempLocation);
+    if (downloadFile.isEmpty()) {
+        downloadFile = QStandardPaths::writableLocation(QStandardPaths::DownloadLocation);
+        if (downloadFile.isEmpty()) {
+            _setupState(upgradeStateDownloadFailed);
+            _ui->statusLabel->setText(tr("Unabled to find writable download location. Tried downloads and temp directory."));
+            return;
+        }
+    }
+    Q_ASSERT(!downloadFile.isEmpty());
+    downloadFile += "/" + firmwareFilename;
+
+    QUrl firmwareUrl;
+    if (_firmwareFilename.startsWith("http:")) {
+        firmwareUrl.setUrl(_firmwareFilename);
+    } else {
+        firmwareUrl = QUrl::fromLocalFile(_firmwareFilename);
+    }
+    Q_ASSERT(firmwareUrl.isValid());
+    
+    QNetworkRequest networkRequest(firmwareUrl);
+    
+    // Store download file location in user attribute so we can retrieve when the download finishes
+    networkRequest.setAttribute(QNetworkRequest::User, downloadFile);
+    
+    _downloadManager = new QNetworkAccessManager(this);
+    Q_CHECK_PTR(_downloadManager);
+    _downloadNetworkReply = _downloadManager->get(networkRequest);
+    Q_ASSERT(_downloadNetworkReply);
+    connect(_downloadNetworkReply, &QNetworkReply::downloadProgress, this, &PX4FirmwareUpgrade::_downloadProgress);
+    connect(_downloadNetworkReply, &QNetworkReply::finished, this, &PX4FirmwareUpgrade::_downloadFinished);
+    // FIXME
+    //connect(_downloadNetworkReply, &QNetworkReply::error, this, &PX4FirmwareUpgrade::_downloadError);
+    connect(_downloadNetworkReply, SIGNAL(error(QNetworkReply::NetworkError)), this, SLOT(_downloadError(QNetworkReply::NetworkError)));
+    
+    _setupState(upgradeStateFirmwareDownloading);
+}
+
+/// @brief Cancels a download which is in progress.
+void PX4FirmwareUpgrade::_cancelDownload(void)
+{
+    _downloadNetworkReply->abort();
+}
+
+/// @brief Updates the progress indicator while downloading
+void PX4FirmwareUpgrade::_downloadProgress(qint64 curr, qint64 total)
+{
+    // Take care of cases where 0 / 0 is emitted as error return value
+    if (total > 0) {
+        _ui->progressBar->setValue((curr*100) / total);
+    }
+}
+
+/// @brief Called when the firmware download completes.
+void PX4FirmwareUpgrade::_downloadFinished(void)
+{
+    QNetworkReply* reply = qobject_cast<QNetworkReply*>(QObject::sender());
+    Q_ASSERT(reply);
+    
+    Q_ASSERT(_downloadNetworkReply == reply);
+    
+    _downloadManager->deleteLater();
+    _downloadManager = NULL;
+    
+    // When an error occurs or the user cancels the download, we still end up here. So bail out in
+    // those cases.
+    if (reply->error() != QNetworkReply::NoError) {
+        return;
+    }
+    
+    // Download file location is in user attribute
+    QString downloadFilename = reply->request().attribute(QNetworkRequest::User).toString();
+    Q_ASSERT(!downloadFilename.isEmpty());
+    
+    // Store downloaded file in download location
+    QFile file(downloadFilename);
+    if (!file.open(QIODevice::WriteOnly)) {
+        _ui->statusLabel->setText(tr("Could not save downloaded file to %1. Error: %2").arg(downloadFilename).arg(file.errorString()));
+        _setupState(upgradeStateDownloadFailed);
+        return;
+    }
+    
+    file.write(reply->readAll());
+    file.close();
+    
+    
+    if (downloadFilename.endsWith(".px4")) {
+        // We need to collect information from the .px4 file as well as pull the binary image out to a seperate file.
+        
+        QFile px4File(downloadFilename);
+        if (!px4File.open(QIODevice::ReadOnly | QIODevice::Text)) {
+            _ui->statusLabel->setText(tr("Unable to open firmware file %1, error: %2").arg(downloadFilename).arg(px4File.errorString()));
+            _setupState(upgradeStateDownloadFailed);
+            return;
+        }
+        
+        QByteArray bytes = px4File.readAll();
+        px4File.close();
+        QJsonDocument doc = QJsonDocument::fromJson(bytes);
+        
+        if (doc.isNull()) {
+            _ui->statusLabel->setText(tr("supplied file is not a valid JSON document"));
+            _setupState(upgradeStateDownloadFailed);
+            return;
+        }
+        
+        QJsonObject px4Json = doc.object();
+
+        // Make sure the keys we need are available
+        static const char* rgJsonKeys[] = { "board_id", "image_size", "description", "git_identity" };
+        for (size_t i=0; i<sizeof(rgJsonKeys)/sizeof(rgJsonKeys[0]); i++) {
+            if (!px4Json.contains(rgJsonKeys[i])) {
+                _ui->statusLabel->setText(tr("Incorrectly formatted firmware file. No %1 key.").arg(rgJsonKeys[i]));
+                _setupState(upgradeStateDownloadFailed);
+                return;
+            }
+        }
+        
+        uint32_t firmwareBoardID = (uint32_t)px4Json.value(QString("board_id")).toInt();
+        if (firmwareBoardID != _boardID) {
+            _ui->statusLabel->setText(tr("Downloaded firmware board id does not match hardware board id: %1 != %2").arg(firmwareBoardID).arg(_boardID));
+            _setupState(upgradeStateDownloadFailed);
+            return;
+        }
+        
+        _imageSize = px4Json.value(QString("image_size")).toInt();
+        if (_imageSize == 0) {
+            _ui->statusLabel->setText(tr("Image size of 0 in .px4 file %1").arg(downloadFilename));
+            _setupState(upgradeStateDownloadFailed);
+            return;
+        }
+        qDebug() << "Image size from px4:" << _imageSize;
+        
+        // Convert image from base-64 and decompress
+        
+        // XXX Qt's JSON string handling is terribly broken, strings
+        // with some length (18K / 25K) are just weirdly cut.
+        // The code below works around this by manually 'parsing'
+        // for the image string. Since its compressed / checksummed
+        // this should be fine.
+        
+        QStringList list = QString(bytes).split("\"image\": \"");
+        list = list.last().split("\"");
+        
+        // Convert String to QByteArray and unzip it
+        QByteArray raw;
+
+        // Store image size
+        raw.append((unsigned char)((_imageSize >> 24) & 0xFF));
+        raw.append((unsigned char)((_imageSize >> 16) & 0xFF));
+        raw.append((unsigned char)((_imageSize >> 8) & 0xFF));
+        raw.append((unsigned char)((_imageSize >> 0) & 0xFF));
+        
+        QByteArray raw64 = list.first().toUtf8();
+        
+        raw.append(QByteArray::fromBase64(raw64));
+        QByteArray uncompressed = qUncompress(raw);
+        
+        QByteArray b = uncompressed;
+
+        if (b.count() == 0) {
+            _ui->statusLabel->setText(tr("Firmware file has 0 length image"));
+            _setupState(upgradeStateDownloadFailed);
+            return;
+        }
+        if (b.count() != (int)_imageSize) {
+            _ui->statusLabel->setText(tr("Image size for decompressed image does not match stored image size: Expected(%1) Actual(%2)").arg(_imageSize).arg(b.count()));
+            _setupState(upgradeStateDownloadFailed);
+            return;
+        }
+        
+        // Pad image to 4-byte boundary
+        while ((b.count() % 4) != 0) {
+            b.append(static_cast<char>(static_cast<unsigned char>(0xFF)));
+        }
+        
+        // Store decompressed image file in same location as original download file
+        QDir downloadDir = QFileInfo(downloadFilename).dir();
+        QString decompressFilename = downloadDir.filePath("PX4FlashUpgrade.bin");
+        
+        QFile decompressFile(decompressFilename);
+        if (!decompressFile.open(QIODevice::WriteOnly | QIODevice::Truncate)) {
+            _ui->statusLabel->setText(tr("Unable to open decompressed file %1 for writing, error: %2").arg(decompressFilename).arg(decompressFile.errorString()));
+            _setupState(upgradeStateDownloadFailed);
+            return;
+        }
+        
+        qint64 bytesWritten = decompressFile.write(b);
+        if (bytesWritten != b.count()) {
+            _ui->statusLabel->setText(tr("Write failed for decompressed image file, error: %1").arg(decompressFile.errorString()));
+            _setupState(upgradeStateDownloadFailed);
+            return;
+        }
+        decompressFile.close();
+        
+        _firmwareFilename = decompressFilename;
+    } else if (downloadFilename.endsWith(".bin")) {
+        uint32_t firmwareBoardID = 0;
+        
+        // Take some educated guesses on board id based on firmware build system file name conventions
+        
+        if (downloadFilename.toLower().contains("px4fmu-v1")) {
+            firmwareBoardID = _boardIDPX4FMUV2;
+        } else if (downloadFilename.toLower().contains("px4flow")) {
+            firmwareBoardID = _boardIDPX4Flow;
+        } else if (downloadFilename.toLower().contains("px4fmu-v1")) {
+            firmwareBoardID = _boardIDPX4FMUV1;
+        }
+        
+        if (firmwareBoardID != 0 &&  firmwareBoardID != _boardID) {
+            _ui->statusLabel->setText(tr("Downloaded firmware board id does not match hardware board id: %1 != %2").arg(firmwareBoardID).arg(_boardID));
+            _setupState(upgradeStateDownloadFailed);
+            return;
+        }
+        
+        _firmwareFilename = downloadFilename;
+        
+        QFile binFile(_firmwareFilename);
+        if (!binFile.open(QIODevice::ReadOnly)) {
+            _ui->statusLabel->setText(tr("Unabled to open firmware file %1, %2").arg(_firmwareFilename).arg(binFile.errorString()));
+            _setupState(upgradeStateDownloadFailed);
+        }
+        _imageSize = (uint32_t)binFile.size();
+        binFile.close();
+    } else {
+        // Standard firmware builds (stable/continuous/...) are always .bin or .px4. Select file dialog for custom
+        // firmware filters to .bin and .px4. So we should never get a file that ends in anything else.
+        Q_ASSERT(false);
+    }
+    
+    if (_imageSize > _boardFlashSize) {
+        _ui->statusLabel->setText(tr("Image size of %1 is too large for board flash size %2").arg(_imageSize).arg(_boardFlashSize));
+        _setupState(upgradeStateDownloadFailed);
+        return;
+    }
+
+    _erase();
+}
+
+/// @brief Called when an error occurs during download
+void PX4FirmwareUpgrade::_downloadError(QNetworkReply::NetworkError code)
+{
+    if (code == QNetworkReply::OperationCanceledError) {
+        _ui->statusLabel->setText(tr("Download cancelled"));
+    } else {
+        _ui->statusLabel->setText(tr("Error during download. Error: %1").arg(code));
+    }
+
+    _setupState(upgradeStateDownloadFailed);
+}
+
+/// @brief Erase the board
+void PX4FirmwareUpgrade::_erase(void)
+{
+    // We set up our own progress bar for erase since the erase command does not provide one
+    _eraseTickCount = 0;
+    _eraseTimer.start(_eraseTickMsec);
+    _setupState(upgradeStateErasing);
+    
+    // Erase command
+    _threadController->erase();
+}
+
+/// @brief Signals completion of one of the specified bootloader commands. Moves the state machine to the
+///         appropriate next step.
+void PX4FirmwareUpgrade::_complete(const int command)
+{
+    if (command == PX4FirmwareUpgradeThreadWorker::commandProgram) {
+        _setupState(upgradeStateVerifying);
+        _threadController->verify(_firmwareFilename);
+    } else if (command == PX4FirmwareUpgradeThreadWorker::commandVerify) {
+        _setupState(upgradeStateBoardUpgraded);
+    } else if (command == PX4FirmwareUpgradeThreadWorker::commandErase) {
+        _eraseTimer.stop();
+        _setupState(upgradeStateFlashing);
+        _threadController->program(_firmwareFilename);
+    } else if (command == PX4FirmwareUpgradeThreadWorker::commandCancel) {
+        if (_upgradeState == upgradeStateBoardSearch) {
+            _setupState(upgradeStateBoardNotFound);
+        } else if (_upgradeState == upgradeStateBootloaderSearch) {
+            _setupState(upgradeStateBootloaderNotFound);
+        } else {
+            Q_ASSERT(false);
+        }
+    } else {
+        Q_ASSERT(false);
+    }
+}
+
+/// @brief Signals that an error has occured with the specified bootloader commands. Moves the state machine
+///         to the appropriate error state.
+void PX4FirmwareUpgrade::_error(const int command, const QString errorString)
+{
+    _ui->statusLabel->setText(tr("Error: %1").arg(errorString));
+    
+    if (command == PX4FirmwareUpgradeThreadWorker::commandProgram) {
+        _setupState(upgradeStateFlashError);
+    } else if (command == PX4FirmwareUpgradeThreadWorker::commandErase) {
+        _setupState(upgradeStateEraseError);
+    } else if (command == PX4FirmwareUpgradeThreadWorker::commandBootloader) {
+        _setupState(upgradeStateBootloaderError);
+    } else if (command == PX4FirmwareUpgradeThreadWorker::commandVerify) {
+        _setupState(upgradeStateVerifyError);
+    } else {
+        Q_ASSERT(false);
+    }
+}
+
+/// @brief Updates the progress bar from long running bootloader commands
+void PX4FirmwareUpgrade::_updateProgress(int curr, int total)
+{
+    _ui->progressBar->setValue((curr*100) / total);
+}
+
+/// @brief Resets the state machine back to the beginning
+void PX4FirmwareUpgrade::_restart(void)
+{
+    _setupState(upgradeStateBegin);
+}
+
+/// @brief Moves the progress bar ahead on tick while erasing the board
+void PX4FirmwareUpgrade::_eraseProgressTick(void)
+{
+    _eraseTickCount++;
+    _ui->progressBar->setValue((_eraseTickCount*_eraseTickMsec*100) / _eraseTotalMsec);
+}
\ No newline at end of file
diff --git a/src/ui/px4_configuration/PX4FirmwareUpgrade.h b/src/ui/px4_configuration/PX4FirmwareUpgrade.h
new file mode 100644
index 0000000000000000000000000000000000000000..ad3e6afe27091a6ceac7624ad79ab341d1fbf0a7
--- /dev/null
+++ b/src/ui/px4_configuration/PX4FirmwareUpgrade.h
@@ -0,0 +1,159 @@
+/*=====================================================================
+ 
+ QGroundControl Open Source Ground Control Station
+ 
+ (c) 2009, 2014 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org>
+ 
+ This file is part of the QGROUNDCONTROL project
+ 
+ QGROUNDCONTROL is free software: you can redistribute it and/or modify
+ it under the terms of the GNU General Public License as published by
+ the Free Software Foundation, either version 3 of the License, or
+ (at your option) any later version.
+ 
+ QGROUNDCONTROL is distributed in the hope that it will be useful,
+ but WITHOUT ANY WARRANTY; without even the implied warranty of
+ MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
+ GNU General Public License for more details.
+ 
+ You should have received a copy of the GNU General Public License
+ along with QGROUNDCONTROL. If not, see <http://www.gnu.org/licenses/>.
+ 
+ ======================================================================*/
+
+/// @file
+///     @brief PX4 Firmware Upgrade UI
+///     @author Don Gagne <don@thegagnes.com>
+
+#ifndef PX4FirmwareUpgrade_H
+#define PX4FirmwareUpgrade_H
+
+#include <QWidget>
+#include <QUrl>
+#include <QSerialPort>
+#include <QTimer>
+#include <QNetworkAccessManager>
+#include <QNetworkReply>
+
+#include <stdint.h>
+
+#include "PX4FirmwareUpgradeThread.h"
+
+#include "ui_PX4FirmwareUpgrade.h"
+
+namespace Ui {
+    class PX4RCCalibration;
+}
+
+class PX4FirmwareUpgrade : public QWidget
+{
+    Q_OBJECT
+
+public:
+    explicit PX4FirmwareUpgrade(QWidget *parent = 0);
+    ~PX4FirmwareUpgrade();
+
+private slots:
+    void _tryAgainButton(void);
+    void _cancelButton(void);
+    void _nextButton(void);
+    void _firmwareSelected(int index);
+    void _downloadProgress(qint64 curr, qint64 total);
+    void _downloadFinished(void);
+    void _downloadError(QNetworkReply::NetworkError code);
+    void _foundBoard(const QString portname, QString portDescription);
+    void _foundBootloader(int bootloaderVersion, int boardID, int flashSize);
+    void _error(const int command, const QString errorString);
+    void _bootloaderSyncFailed(void);
+    void _findTimeout(void);
+    void _complete(const int command);
+    void _updateProgress(int curr, int total);
+    void _restart(void);
+    void _eraseProgressTick(void);
+
+private:
+    /// @brief The various states that the upgrade process progresses through.
+    enum upgradeStates {
+        upgradeStateBegin,
+        upgradeStateBoardSearch,
+        upgradeStateBoardNotFound,
+        upgradeStateBootloaderSearch,
+        upgradeStateBootloaderNotFound,
+        upgradeStateBootloaderError,
+        upgradeStateFirmwareSelect,
+        upgradeStateFirmwareDownloading,
+        upgradeStateDownloadFailed,
+        upgradeStateErasing,
+        upgradeStateEraseError,
+        upgradeStateFlashing,
+        upgradeStateFlashError,
+        upgradeStateVerifying,
+        upgradeStateVerifyError,
+        upgradeStateBoardUpgraded,
+        upgradeStateMax
+    };
+    
+    void _setupState(enum upgradeStates state);
+    void _updateIndicatorUI(void);
+    
+    void _findBoard(void);
+    void _findBootloader(void);
+    void _cancel(void);
+    void _cancelFind(void);
+    void _getFirmwareFile(void);
+    
+    void _setBoardIcon(int boardID);
+    void _setFirmwareCombo(int boardID);
+    
+    void _downloadFirmware(void);
+    void _cancelDownload(void);
+    
+    void _erase(void);
+    
+    typedef void (PX4FirmwareUpgrade::*stateFunc)(void);
+    struct stateMachineEntry {
+        enum upgradeStates  state;      ///< State machine state, used to verify correctness of entry
+        stateFunc           next;       ///< Method to call when Next is clicked, NULL for Next not available
+        stateFunc           cancel;     ///< Method to call when Cancel is clicked, NULL for Cancel not available
+        stateFunc           tryAgain;   ///< Method to call when Try Again is clicked, NULL for Try Again not available
+        const char*         msg;        ///< Text message to display to user for this state
+    };
+    
+    const struct stateMachineEntry* _getStateMachineEntry(enum upgradeStates state);
+    
+    enum upgradeStates _upgradeState;       ///< Current state of the upgrade state machines
+    
+    QString _portName;
+    QString _portDescription;
+    uint32_t _bootloaderVersion;
+
+    static const int _boardIDPX4FMUV1 = 5;  ///< Board ID for PX4 V1 board
+    static const int _boardIDPX4FMUV2 = 9;  ///< Board ID for PX4 V2 board
+    static const int _boardIDPX4Flow = 6;   ///< Board ID for PX4 Flow board
+
+    uint32_t    _boardID;           ///< Board ID
+    uint32_t    _boardFlashSize;    ///< Flash size in bytes of board
+    uint32_t    _imageSize;         ///< Image size of firmware being flashed
+
+    QPixmap _boardIcon;             ///< Icon used to display image of board
+    
+    QString _firmwareFilename;      ///< Image which we are going to flash to the board
+    
+    QNetworkAccessManager*  _downloadManager;       ///< Used for firmware file downloading across the internet
+    QNetworkReply*          _downloadNetworkReply;  ///< Used for firmware file downloading across the internet
+    
+    /// @brief Thread controller which is used to run bootloader commands on seperate thread
+    PX4FirmwareUpgradeThreadController* _threadController;
+    
+    static const int    _eraseTickMsec = 500;       ///< Progress bar update tick time for erase
+    static const int    _eraseTotalMsec = 15000;    ///< Estimated amount of time erase takes
+    int                 _eraseTickCount;            ///< Number of ticks for erase progress update
+    QTimer              _eraseTimer;                ///< Timer used to update progress bar for erase
+
+    static const int    _findBoardTimeoutMsec = 30000;      ///< Amount of time for user to plug in USB
+    static const int    _findBootloaderTimeoutMsec = 5000;  ///< Amount time to look for bootloader
+    
+    Ui::PX4FirmwareUpgrade* _ui;
+};
+
+#endif // PX4FirmwareUpgrade_H
diff --git a/src/ui/px4_configuration/PX4FirmwareUpgrade.ui b/src/ui/px4_configuration/PX4FirmwareUpgrade.ui
new file mode 100644
index 0000000000000000000000000000000000000000..ad460b87ddbe126859f781c5d7cc61d338f7c9e6
--- /dev/null
+++ b/src/ui/px4_configuration/PX4FirmwareUpgrade.ui
@@ -0,0 +1,245 @@
+<?xml version="1.0" encoding="UTF-8"?>
+<ui version="4.0">
+ <class>PX4FirmwareUpgrade</class>
+ <widget class="QWidget" name="PX4FirmwareUpgrade">
+  <property name="geometry">
+   <rect>
+    <x>0</x>
+    <y>0</y>
+    <width>1562</width>
+    <height>1286</height>
+   </rect>
+  </property>
+  <property name="windowTitle">
+   <string>Form</string>
+  </property>
+  <widget class="QWidget" name="layoutWidget">
+   <property name="geometry">
+    <rect>
+     <x>0</x>
+     <y>0</y>
+     <width>726</width>
+     <height>525</height>
+    </rect>
+   </property>
+   <layout class="QGridLayout" name="gridLayout" rowstretch="0" columnstretch="0,0">
+    <item row="0" column="1">
+     <layout class="QVBoxLayout" name="verticalLayout">
+      <item>
+       <widget class="QCheckBox" name="boardFoundCheck">
+        <property name="text">
+         <string>Board found</string>
+        </property>
+       </widget>
+      </item>
+      <item>
+       <widget class="QLabel" name="port">
+        <property name="text">
+         <string>Port</string>
+        </property>
+        <property name="alignment">
+         <set>Qt::AlignLeading|Qt::AlignLeft|Qt::AlignVCenter</set>
+        </property>
+       </widget>
+      </item>
+      <item>
+       <widget class="QLabel" name="description">
+        <property name="text">
+         <string>Description</string>
+        </property>
+        <property name="alignment">
+         <set>Qt::AlignLeading|Qt::AlignLeft|Qt::AlignVCenter</set>
+        </property>
+       </widget>
+      </item>
+      <item>
+       <widget class="QCheckBox" name="bootloaderFoundCheck">
+        <property name="text">
+         <string>Bootloader found</string>
+        </property>
+       </widget>
+      </item>
+      <item>
+       <widget class="QLabel" name="bootloaderVersion">
+        <property name="text">
+         <string>Bootloader Version</string>
+        </property>
+        <property name="alignment">
+         <set>Qt::AlignLeading|Qt::AlignLeft|Qt::AlignVCenter</set>
+        </property>
+       </widget>
+      </item>
+      <item>
+       <widget class="QLabel" name="boardID">
+        <property name="text">
+         <string>Board ID</string>
+        </property>
+        <property name="alignment">
+         <set>Qt::AlignLeading|Qt::AlignLeft|Qt::AlignVCenter</set>
+        </property>
+       </widget>
+      </item>
+      <item>
+       <widget class="QLabel" name="icon">
+        <property name="minimumSize">
+         <size>
+          <width>200</width>
+          <height>100</height>
+         </size>
+        </property>
+        <property name="text">
+         <string>Icon</string>
+        </property>
+       </widget>
+      </item>
+      <item>
+       <widget class="QCheckBox" name="selectFirmwareCheck">
+        <property name="text">
+         <string>Select Firmware</string>
+        </property>
+       </widget>
+      </item>
+      <item>
+       <widget class="QComboBox" name="firmwareCombo"/>
+      </item>
+      <item>
+       <widget class="QCheckBox" name="firmwareDownloadedCheck">
+        <property name="text">
+         <string>Firmware downloaded</string>
+        </property>
+       </widget>
+      </item>
+      <item>
+       <widget class="QCheckBox" name="boardUpgradedCheck">
+        <property name="text">
+         <string>Board upgraded</string>
+        </property>
+       </widget>
+      </item>
+      <item>
+       <spacer name="verticalSpacer">
+        <property name="orientation">
+         <enum>Qt::Vertical</enum>
+        </property>
+        <property name="sizeHint" stdset="0">
+         <size>
+          <width>20</width>
+          <height>40</height>
+         </size>
+        </property>
+       </spacer>
+      </item>
+     </layout>
+    </item>
+    <item row="0" column="0">
+     <layout class="QVBoxLayout" name="verticalLayout_9">
+      <item>
+       <widget class="QLabel" name="statusLog">
+        <property name="sizePolicy">
+         <sizepolicy hsizetype="Expanding" vsizetype="Expanding">
+          <horstretch>0</horstretch>
+          <verstretch>0</verstretch>
+         </sizepolicy>
+        </property>
+        <property name="minimumSize">
+         <size>
+          <width>400</width>
+          <height>180</height>
+         </size>
+        </property>
+        <property name="text">
+         <string>Status log</string>
+        </property>
+        <property name="alignment">
+         <set>Qt::AlignLeading|Qt::AlignLeft|Qt::AlignTop</set>
+        </property>
+        <property name="wordWrap">
+         <bool>true</bool>
+        </property>
+       </widget>
+      </item>
+      <item>
+       <widget class="QLabel" name="statusLabel">
+        <property name="sizePolicy">
+         <sizepolicy hsizetype="Expanding" vsizetype="Preferred">
+          <horstretch>0</horstretch>
+          <verstretch>0</verstretch>
+         </sizepolicy>
+        </property>
+        <property name="minimumSize">
+         <size>
+          <width>400</width>
+          <height>16</height>
+         </size>
+        </property>
+        <property name="text">
+         <string>TextLabel</string>
+        </property>
+        <property name="alignment">
+         <set>Qt::AlignLeading|Qt::AlignLeft|Qt::AlignTop</set>
+        </property>
+        <property name="wordWrap">
+         <bool>true</bool>
+        </property>
+       </widget>
+      </item>
+      <item>
+       <layout class="QHBoxLayout" name="horizontalLayout">
+        <item>
+         <widget class="QPushButton" name="tryAgain">
+          <property name="text">
+           <string>Try Again</string>
+          </property>
+         </widget>
+        </item>
+        <item>
+         <widget class="QPushButton" name="skip">
+          <property name="text">
+           <string>Skip</string>
+          </property>
+         </widget>
+        </item>
+        <item>
+         <widget class="QPushButton" name="cancel">
+          <property name="text">
+           <string>Cancel</string>
+          </property>
+         </widget>
+        </item>
+        <item>
+         <widget class="QPushButton" name="next">
+          <property name="text">
+           <string>Next</string>
+          </property>
+         </widget>
+        </item>
+       </layout>
+      </item>
+      <item>
+       <widget class="QProgressBar" name="progressBar">
+        <property name="value">
+         <number>24</number>
+        </property>
+       </widget>
+      </item>
+      <item>
+       <spacer name="verticalSpacer_3">
+        <property name="orientation">
+         <enum>Qt::Vertical</enum>
+        </property>
+        <property name="sizeHint" stdset="0">
+         <size>
+          <width>20</width>
+          <height>60</height>
+         </size>
+        </property>
+       </spacer>
+      </item>
+     </layout>
+    </item>
+   </layout>
+  </widget>
+ </widget>
+ <resources/>
+ <connections/>
+</ui>
diff --git a/src/ui/px4_configuration/PX4FirmwareUpgradeThread.cc b/src/ui/px4_configuration/PX4FirmwareUpgradeThread.cc
new file mode 100644
index 0000000000000000000000000000000000000000..7e9ee479cdc399217dd2a130b3cfb78b71f7c957
--- /dev/null
+++ b/src/ui/px4_configuration/PX4FirmwareUpgradeThread.cc
@@ -0,0 +1,306 @@
+/*=====================================================================
+ 
+ QGroundControl Open Source Ground Control Station
+ 
+ (c) 2009, 2014 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org>
+ 
+ This file is part of the QGROUNDCONTROL project
+ 
+ QGROUNDCONTROL is free software: you can redistribute it and/or modify
+ it under the terms of the GNU General Public License as published by
+ the Free Software Foundation, either version 3 of the License, or
+ (at your option) any later version.
+ 
+ QGROUNDCONTROL is distributed in the hope that it will be useful,
+ but WITHOUT ANY WARRANTY; without even the implied warranty of
+ MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
+ GNU General Public License for more details.
+ 
+ You should have received a copy of the GNU General Public License
+ along with QGROUNDCONTROL. If not, see <http://www.gnu.org/licenses/>.
+ 
+ ======================================================================*/
+
+/// @file
+///     @brief PX4 Firmware Upgrade operations which occur on a seperate thread.
+///     @author Don Gagne <don@thegagnes.com>
+
+#include "PX4FirmwareUpgradeThread.h"
+#include "PX4Bootloader.h"
+
+#include <QTimer>
+#include <QSerialPortInfo>
+#include <QDebug>
+
+PX4FirmwareUpgradeThreadWorker::PX4FirmwareUpgradeThreadWorker(QObject* parent) :
+    QObject(parent),
+    _bootloader(NULL),
+    _bootloaderPort(NULL),
+    _timerTimeout(NULL),
+    _timerRetry(NULL)   
+{
+    
+}
+
+PX4FirmwareUpgradeThreadWorker::~PX4FirmwareUpgradeThreadWorker()
+{
+    if (_bootloaderPort) {
+        // deleteLater so delete happens on correct thread
+        _bootloaderPort->deleteLater();
+    }
+}
+
+/// @brief Initializes the PX4FirmwareUpgradeThreadWorker with the various child objects which must be created
+///         on the worker thread.
+void PX4FirmwareUpgradeThreadWorker::init(void)
+{
+    // We create the timers here so that they are on the right thread
+    
+    Q_ASSERT(_timerTimeout == NULL);
+    _timerTimeout = new QTimer(this);
+    Q_CHECK_PTR(_timerTimeout);
+    connect(_timerTimeout, &QTimer::timeout, this, &PX4FirmwareUpgradeThreadWorker::timeout);
+    _timerTimeout->setSingleShot(true);
+    
+    Q_ASSERT(_timerRetry == NULL);
+    _timerRetry = new QTimer(this);
+    Q_CHECK_PTR(_timerRetry);
+    _timerRetry->setSingleShot(true);
+    _timerRetry->setInterval(_retryTimeout);
+    
+    Q_ASSERT(_bootloader == NULL);
+    _bootloader = new PX4Bootloader(this);
+    connect(_bootloader, &PX4Bootloader::updateProgramProgress, this, &PX4FirmwareUpgradeThreadWorker::_updateProgramProgress);
+}
+
+void PX4FirmwareUpgradeThreadWorker::findBoard(int msecTimeout)
+{
+    connect(_timerRetry, &QTimer::timeout, this, &PX4FirmwareUpgradeThreadWorker::_findBoardOnce);
+    _timerTimeout->start(msecTimeout);
+    _elapsed.start();
+    _findBoardOnce();
+}
+
+void PX4FirmwareUpgradeThreadWorker::_findBoardOnce(void)
+{
+    qDebug() << "_findBoardOnce";
+    
+    QString portName;
+    QString portDescription;
+    
+    foreach (QSerialPortInfo info, QSerialPortInfo::availablePorts()) {
+        if (!info.portName().isEmpty() && (info.description().contains("PX4") || info.vendorIdentifier() == 9900 /* 3DR */)) {
+            
+            qDebug() << "Found Board:";
+            qDebug() << "\tport name:" << info.portName();
+            qDebug() << "\tdescription:" << info.description();
+            qDebug() << "\tsystem location:" << info.systemLocation();
+            qDebug() << "\tvendor ID:" << info.vendorIdentifier();
+            qDebug() << "\tproduct ID:" << info.productIdentifier();
+            
+            portName = info.portName();
+            portDescription = info.description();
+            
+#ifdef Q_OS_WIN
+            // Stupid windows fixes
+            portName.prepend("\\\\.\\");
+#endif
+            
+            _closeFind();
+            emit foundBoard(portName, portDescription);
+            return;
+        }
+    }
+    
+    emit updateProgress(_elapsed.elapsed(), _timerTimeout->interval());
+    _timerRetry->start();
+}
+
+void PX4FirmwareUpgradeThreadWorker::findBootloader(const QString portName, int msecTimeout)
+{
+    connect(_timerRetry, &QTimer::timeout, this, &PX4FirmwareUpgradeThreadWorker::_findBootloaderOnce);
+    _portName = portName;
+    _timerTimeout->start(msecTimeout);
+    _elapsed.start();
+    _findBootloaderOnce();
+}
+
+void PX4FirmwareUpgradeThreadWorker::_findBootloaderOnce(void)
+{
+    qDebug() << "_findBootloaderOnce";
+    
+    uint32_t    bootloaderVersion, boardID, flashSize;
+
+    _bootloaderPort = new QSerialPort;
+    Q_CHECK_PTR(_bootloaderPort);
+    
+    if (_bootloader->open(_bootloaderPort, _portName)) {
+        if (_bootloader->sync(_bootloaderPort)) {
+            if (_bootloader->getBoardInfo(_bootloaderPort, bootloaderVersion, boardID, flashSize)) {
+                _closeFind();
+                qDebug() << "Found bootloader";
+                emit foundBootloader(bootloaderVersion, boardID, flashSize);
+                return;
+            } else {
+                _closeFind();
+                _bootloaderPort->close();
+                delete _bootloaderPort;
+                _bootloaderPort = NULL;
+                qDebug() << "Bootloader error:" << _bootloader->errorString();
+                emit error(commandBootloader, _bootloader->errorString());
+                return;
+            }
+        } else {
+            _closeFind();
+            _bootloaderPort->close();
+            delete _bootloaderPort;
+            _bootloaderPort = NULL;
+            qDebug() << "Bootloader sync failed";
+            emit bootloaderSyncFailed();
+            return;
+        }
+    }
+    
+    emit updateProgress(_elapsed.elapsed(), _timerTimeout->interval());
+    _timerRetry->start();
+}
+
+void PX4FirmwareUpgradeThreadWorker::_closeFind(void)
+{
+    emit updateProgress(100, 100);
+    disconnect(_timerRetry, SIGNAL(timeout()), 0, 0);
+    _timerRetry->stop();
+    _timerTimeout->stop();
+}
+
+void PX4FirmwareUpgradeThreadWorker::cancelFind(void)
+{
+    _closeFind();
+    emit complete(commandCancel);
+}
+
+void PX4FirmwareUpgradeThreadWorker::timeout(void)
+{
+    qDebug() << "Find timeout";
+    _closeFind();
+    emit findTimeout();
+}
+
+void PX4FirmwareUpgradeThreadWorker::sendBootloaderReboot(void)
+{
+    _bootloader->sendBootloaderReboot(_bootloaderPort);
+    delete _bootloaderPort;
+    _bootloaderPort = NULL;
+}
+
+void PX4FirmwareUpgradeThreadWorker::program(const QString firmwareFilename)
+{
+    qDebug() << "Program";
+    if (!_bootloader->program(_bootloaderPort, firmwareFilename)) {
+        delete _bootloaderPort;
+        _bootloaderPort = NULL;
+        qDebug() << "Program failed:" << _bootloader->errorString();
+        emit error(commandProgram, _bootloader->errorString());
+    } else {
+        qDebug() << "Program complete";
+        emit complete(commandProgram);
+    }
+}
+
+void PX4FirmwareUpgradeThreadWorker::verify(const QString firmwareFilename)
+{
+    qDebug() << "Verify";
+    if (!_bootloader->verify(_bootloaderPort, firmwareFilename)) {
+        qDebug() << "Verify failed:" << _bootloader->errorString();
+        emit error(commandVerify, _bootloader->errorString());
+    } else {
+        qDebug() << "Verify complete";
+        emit complete(commandVerify);
+    }
+    delete _bootloaderPort;
+    _bootloaderPort = NULL;
+}
+
+void PX4FirmwareUpgradeThreadWorker::erase(void)
+{
+    qDebug() << "Erase";
+    if (!_bootloader->erase(_bootloaderPort)) {
+        delete _bootloaderPort;
+        _bootloaderPort = NULL;
+        qDebug() << "Erase failed:" << _bootloader->errorString();
+        emit error(commandErase, _bootloader->errorString());
+    } else {
+        qDebug() << "Erase complete";
+        emit complete(commandErase);
+    }
+}
+
+PX4FirmwareUpgradeThreadController::PX4FirmwareUpgradeThreadController(QObject* parent) :
+    QObject(parent)
+{
+    _worker = new PX4FirmwareUpgradeThreadWorker();
+    Q_CHECK_PTR(_worker);
+    
+    _workerThread = new QThread(this);
+    Q_CHECK_PTR(_workerThread);
+    _worker->moveToThread(_workerThread);
+    
+    connect(_worker, &PX4FirmwareUpgradeThreadWorker::foundBoard, this, &PX4FirmwareUpgradeThreadController::_foundBoard);
+    connect(_worker, &PX4FirmwareUpgradeThreadWorker::foundBootloader, this, &PX4FirmwareUpgradeThreadController::_foundBootloader);
+    connect(_worker, &PX4FirmwareUpgradeThreadWorker::bootloaderSyncFailed, this, &PX4FirmwareUpgradeThreadController::_bootloaderSyncFailed);
+    connect(_worker, &PX4FirmwareUpgradeThreadWorker::error, this, &PX4FirmwareUpgradeThreadController::_error);
+    connect(_worker, &PX4FirmwareUpgradeThreadWorker::complete, this, &PX4FirmwareUpgradeThreadController::_complete);
+    connect(_worker, &PX4FirmwareUpgradeThreadWorker::findTimeout, this, &PX4FirmwareUpgradeThreadController::_findTimeout);
+    connect(_worker, &PX4FirmwareUpgradeThreadWorker::updateProgress, this, &PX4FirmwareUpgradeThreadController::_updateProgress);
+
+    connect(this, &PX4FirmwareUpgradeThreadController::_initThreadWorker, _worker, &PX4FirmwareUpgradeThreadWorker::init);
+    connect(this, &PX4FirmwareUpgradeThreadController::_findBoardOnThread, _worker, &PX4FirmwareUpgradeThreadWorker::findBoard);
+    connect(this, &PX4FirmwareUpgradeThreadController::_findBootloaderOnThread, _worker, &PX4FirmwareUpgradeThreadWorker::findBootloader);
+    connect(this, &PX4FirmwareUpgradeThreadController::_sendBootloaderRebootOnThread, _worker, &PX4FirmwareUpgradeThreadWorker::sendBootloaderReboot);
+    connect(this, &PX4FirmwareUpgradeThreadController::_programOnThread, _worker, &PX4FirmwareUpgradeThreadWorker::program);
+    connect(this, &PX4FirmwareUpgradeThreadController::_verifyOnThread, _worker, &PX4FirmwareUpgradeThreadWorker::verify);
+    connect(this, &PX4FirmwareUpgradeThreadController::_eraseOnThread, _worker, &PX4FirmwareUpgradeThreadWorker::erase);
+    connect(this, &PX4FirmwareUpgradeThreadController::_cancelFindOnThread, _worker, &PX4FirmwareUpgradeThreadWorker::cancelFind);
+    
+    _workerThread->start();
+    
+    emit _initThreadWorker();
+}
+
+PX4FirmwareUpgradeThreadController::~PX4FirmwareUpgradeThreadController()
+{
+    _workerThread->quit();
+    _workerThread->wait();
+}
+
+void PX4FirmwareUpgradeThreadController::findBoard(int msecTimeout)
+{
+    qDebug() << "PX4FirmwareUpgradeThreadController::findBoard";
+    emit _findBoardOnThread(msecTimeout);
+}
+
+void PX4FirmwareUpgradeThreadController::findBootloader(const QString& portName, int msecTimeout)
+{
+    qDebug() << "PX4FirmwareUpgradeThreadController::findBootloader";
+    emit _findBootloaderOnThread(portName, msecTimeout);
+}
+
+void PX4FirmwareUpgradeThreadController::_foundBoard(const QString portName, QString portDescription)
+{
+    emit foundBoard(portName, portDescription);
+}
+
+void PX4FirmwareUpgradeThreadController::_foundBootloader(int bootloaderVersion, int boardID, int flashSize)
+{
+    emit foundBootloader(bootloaderVersion, boardID, flashSize);
+}
+
+void PX4FirmwareUpgradeThreadController::_bootloaderSyncFailed(void)
+{    
+    emit bootloaderSyncFailed();
+}
+
+void PX4FirmwareUpgradeThreadController::_findTimeout(void)
+{
+    emit findTimeout();
+}
diff --git a/src/ui/px4_configuration/PX4FirmwareUpgradeThread.h b/src/ui/px4_configuration/PX4FirmwareUpgradeThread.h
new file mode 100644
index 0000000000000000000000000000000000000000..f51362b06ad12354f35790f541add5cb45bd8bbc
--- /dev/null
+++ b/src/ui/px4_configuration/PX4FirmwareUpgradeThread.h
@@ -0,0 +1,180 @@
+/*=====================================================================
+ 
+ QGroundControl Open Source Ground Control Station
+ 
+ (c) 2009, 2014 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org>
+ 
+ This file is part of the QGROUNDCONTROL project
+ 
+ QGROUNDCONTROL is free software: you can redistribute it and/or modify
+ it under the terms of the GNU General Public License as published by
+ the Free Software Foundation, either version 3 of the License, or
+ (at your option) any later version.
+ 
+ QGROUNDCONTROL is distributed in the hope that it will be useful,
+ but WITHOUT ANY WARRANTY; without even the implied warranty of
+ MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
+ GNU General Public License for more details.
+ 
+ You should have received a copy of the GNU General Public License
+ along with QGROUNDCONTROL. If not, see <http://www.gnu.org/licenses/>.
+ 
+ ======================================================================*/
+
+/// @file
+///     @brief PX4 Firmware Upgrade operations which occur on a seperate thread.
+///     @author Don Gagne <don@thegagnes.com>
+
+#ifndef PX4FirmwareUpgradeThread_H
+#define PX4FirmwareUpgradeThread_H
+
+#include <QObject>
+#include <QSerialPort>
+#include <QThread>
+#include <QTimer>
+#include <QTime>
+
+#include <stdint.h>
+
+#include "PX4Bootloader.h"
+
+/// @brief Used to run bootloader commands on a seperate thread. These routines are mainly meant to to be called
+///         internally by the PX4FirmwareUpgradeThreadController. Clients should call the various public methods
+///         exposed by PX4FirmwareUpgradeThreadController.
+class PX4FirmwareUpgradeThreadWorker : public QObject
+{
+    Q_OBJECT
+    
+public:
+    PX4FirmwareUpgradeThreadWorker(QObject* parent = NULL);
+    ~PX4FirmwareUpgradeThreadWorker();
+    
+    enum {
+        commandBootloader,
+        commandProgram,
+        commandVerify,
+        commandErase,
+        commandCancel
+    };
+    
+public slots:
+    void init(void);
+    void findBoard(int msecTimeout);
+    void findBootloader(const QString portName, int msecTimeout);
+    void timeout(void);
+    void cancelFind(void);
+    void sendBootloaderReboot(void);
+    void program(const QString firmwareFilename);
+    void verify(const QString firmwareFilename);
+    void erase(void);
+    
+signals:
+    void foundBoard(const QString portname, QString portDescription);
+    void foundBootloader(int bootloaderVersion, int boardID, int flashSize);
+    void bootloaderSyncFailed(void);
+    void error(const int command, const QString errorString);
+    void complete(const int command);
+    void findTimeout(void);
+    void updateProgress(int curr, int total);
+    
+private slots:
+    void _findBoardOnce(void);
+    void _findBootloaderOnce(void);
+    void _updateProgramProgress(int curr, int total) { emit updateProgress(curr, total); }
+    void _closeFind(void);
+    
+private:
+    PX4Bootloader*      _bootloader;
+    QSerialPort*        _bootloaderPort;
+    QTimer*             _timerTimeout;
+    QTimer*             _timerRetry;
+    QTime               _elapsed;
+    QString             _portName;
+    static const int    _retryTimeout = 1000;
+};
+
+/// @brief Provides methods to interact with the bootloader. The commands themselves are signalled
+///         across to PX4FirmwareUpgradeThreadWorker so that they run on the seperate thread.
+class PX4FirmwareUpgradeThreadController : public QObject
+{
+    Q_OBJECT
+    
+public:
+    PX4FirmwareUpgradeThreadController(QObject* parent = NULL);
+    ~PX4FirmwareUpgradeThreadController(void);
+    
+    /// @brief Begins the process of searching for a PX4 board connected to any serial port.
+    ///     @param msecTimeout Numbers of msecs to continue looking for a board to become available.
+    void findBoard(int msecTimeout);
+    
+    /// @brief Begins the process of attempting to communicate with the bootloader on the specified port.
+    ///     @param portName Name of port to attempt a bootloader connection on.
+    ///     @param msecTimeout Number of msecs to continue to wait for a bootloader to appear on the port.
+    void findBootloader(const QString& portName, int msecTimeout);
+    
+    /// @brief Cancel an in progress findBoard or FindBootloader
+    void cancelFind(void) { emit _cancelFindOnThread(); }
+    
+    /// @brief Sends a reboot command to the bootloader
+    void sendBootloaderReboot(void) { emit _sendBootloaderRebootOnThread(); }
+    
+    /// @brief Flash the specified firmware onto the board
+    void program(const QString firmwareFilename) { emit _programOnThread(firmwareFilename); }
+    
+    /// @brief Verify the board flash with respect to the specified firmware image
+    void verify(const QString firmwareFilename) { emit _verifyOnThread(firmwareFilename); }
+    
+    /// @brief Send and erase command to the bootloader
+    void erase(void) { emit _eraseOnThread(); }
+
+signals:
+    /// @brief Emitted by the findBoard process when it finds the board.
+    ///     @param portName Port that board is on
+    ///     @param portDescription User friendly port description
+    void foundBoard(const QString portname, QString portDescription);
+    
+    /// @brief Emitted by the findBootloader process when has a connection to the bootloader
+    void foundBootloader(int bootloaderVersion, int boardID, int flashSize);
+    
+    /// @brief Emitted by the bootloader commands when an error occurs.
+    ///     @param errorCommand Command which caused the error, using PX4FirmwareUpgradeThreadWorker command* enum values
+    void error(const int errorCommand, const QString errorString);
+    
+    /// @brief Signalled when the findBootloader process connects to the port, but cannot sync to the
+    ///         bootloader.
+    void bootloaderSyncFailed(void);
+    
+    /// @brief Signalled when the findBoard or findBootloader process times out before success
+    void findTimeout(void);
+    
+    /// @brief Signalled by the bootloader commands other than find* that they have complete successfully.
+    ///     @param command Command which completed, using PX4FirmwareUpgradeThreadWorker command* enum values
+    void complete(const int command);
+    
+    /// @brief Signalled to update progress for long running bootloader commands
+    void updateProgress(int curr, int total);
+    
+    void _initThreadWorker(void);
+    void _findBoardOnThread(int msecTimeout);
+    void _findBootloaderOnThread(const QString& portName, int msecTimeout);
+    void _sendBootloaderRebootOnThread(void);
+    void _programOnThread(const QString firmwareFilename);
+    void _verifyOnThread(const QString firmwareFilename);
+    void _eraseOnThread(void);
+    void _cancelFindOnThread(void);
+    
+private slots:
+    void _foundBoard(const QString portname, QString portDescription);
+    void _foundBootloader(int bootloaderVersion, int boardID, int flashSize);
+    void _bootloaderSyncFailed(void);
+    void _error(const int errorCommand, const QString errorString) { emit error(errorCommand, errorString); }
+    void _complete(const int command) { emit complete(command); }
+    void _findTimeout(void);
+    void _updateProgress(int curr, int total) { emit updateProgress(curr, total); }
+    
+private:
+    PX4FirmwareUpgradeThreadWorker* _worker;
+    QThread*                        _workerThread;  ///< Thread which PX4FirmwareUpgradeThreadWorker runs on
+};
+
+#endif