diff --git a/QGCApplication.pro b/QGCApplication.pro
index f7a22ebcc82815fe9d61b7919d89866572614bc8..61c579de8519fbd0b8181d9f0dd7ec973d040df5 100644
--- a/QGCApplication.pro
+++ b/QGCApplication.pro
@@ -591,8 +591,10 @@ HEADERS+= \
!MobileBuild {
HEADERS += \
src/VehicleSetup/FirmwareUpgradeController.h \
- src/VehicleSetup/PX4Bootloader.h \
- src/VehicleSetup/PX4FirmwareUpgradeThread.h
+ src/VehicleSetup/Bootloader.h \
+ src/VehicleSetup/PX4FirmwareUpgradeThread.h \
+ src/VehicleSetup/FirmwareImage.h \
+
}
SOURCES += \
@@ -621,8 +623,10 @@ SOURCES += \
!MobileBuild {
SOURCES += \
src/VehicleSetup/FirmwareUpgradeController.cc \
- src/VehicleSetup/PX4Bootloader.cc \
- src/VehicleSetup/PX4FirmwareUpgradeThread.cc
+ src/VehicleSetup/Bootloader.cc \
+ src/VehicleSetup/PX4FirmwareUpgradeThread.cc \
+ src/VehicleSetup/FirmwareImage.cc \
+
}
# Fact System code
diff --git a/qgroundcontrol.qrc b/qgroundcontrol.qrc
index 20fd3daf37cfa51a456b4b13b7f75b193e9f597f..56201fbca7617943b736f2d0705784bce2cae6df 100644
--- a/qgroundcontrol.qrc
+++ b/qgroundcontrol.qrc
@@ -201,6 +201,12 @@
resources/QGroundControlConnect.svg
+
+ resources/firmware/px4.png
+ resources/firmware/apm.png
+ resources/firmware/3drradio.png
+
+
resources/mavs/helicopter.svg
resources/mavs/unknown.svg
diff --git a/resources/firmware/3drradio.png b/resources/firmware/3drradio.png
new file mode 100644
index 0000000000000000000000000000000000000000..7dd84905b38c8518f2a52ff1ce1289cfe6ba3772
Binary files /dev/null and b/resources/firmware/3drradio.png differ
diff --git a/resources/firmware/apm.png b/resources/firmware/apm.png
new file mode 100644
index 0000000000000000000000000000000000000000..ebfec2919c10ebc6fb41dd09c2424090df9090f7
Binary files /dev/null and b/resources/firmware/apm.png differ
diff --git a/resources/firmware/px4.png b/resources/firmware/px4.png
new file mode 100644
index 0000000000000000000000000000000000000000..27459899a06fa1f77d9cd9ef5def3f4d2c011e3e
Binary files /dev/null and b/resources/firmware/px4.png differ
diff --git a/src/QGCLoggingCategory.cc b/src/QGCLoggingCategory.cc
index 7a7c3cdaeb62ad7056e963391913212f4fc6744c..bd102e4380c5849bf4b109a0f50785769d8df100 100644
--- a/src/QGCLoggingCategory.cc
+++ b/src/QGCLoggingCategory.cc
@@ -27,7 +27,7 @@
#include "QGCLoggingCategory.h"
// Add Global logging categories (not class specific) here using QGC_LOGGING_CATEGORY
- // There currently are no global categories
+QGC_LOGGING_CATEGORY(FirmwareUpgradeLog, "FirmwareUpgradeLog")
QGCLoggingCategoryRegister* _instance = NULL;
diff --git a/src/QGCLoggingCategory.h b/src/QGCLoggingCategory.h
index e059f833dd0567c8edbc82e8fd152e30e968ec51..a77ad830f0b839284b60506a34604ee8ab4e6f33 100644
--- a/src/QGCLoggingCategory.h
+++ b/src/QGCLoggingCategory.h
@@ -31,7 +31,7 @@
#include
// Add Global logging categories (not class specific) here using Q_DECLARE_LOGGING_CATEGORY
- // There currently are no global categories
+Q_DECLARE_LOGGING_CATEGORY(FirmwareUpgradeLog)
/// @def QGC_LOGGING_CATEGORY
/// This is a QGC specific replacement for Q_LOGGING_CATEGORY. It will register the category name into a
diff --git a/src/VehicleSetup/PX4Bootloader.cc b/src/VehicleSetup/Bootloader.cc
similarity index 52%
rename from src/VehicleSetup/PX4Bootloader.cc
rename to src/VehicleSetup/Bootloader.cc
index 81eb339c77d4a21d041fa82f4fbd068aa3a5fe5c..0b85c2deadeb3a97a5d59540cce62176fcbe8fe6 100644
--- a/src/VehicleSetup/PX4Bootloader.cc
+++ b/src/VehicleSetup/Bootloader.cc
@@ -25,7 +25,8 @@
/// @brief PX4 Bootloader Utility routines
/// @author Don Gagne
-#include "PX4Bootloader.h"
+#include "Bootloader.h"
+#include "QGCLoggingCategory.h"
#include
#include
@@ -78,13 +79,13 @@ static quint32 crc32(const uint8_t *src, unsigned len, unsigned state)
return state;
}
-PX4Bootloader::PX4Bootloader(QObject *parent) :
+Bootloader::Bootloader(QObject *parent) :
QObject(parent)
{
}
-bool PX4Bootloader::write(QextSerialPort* port, const uint8_t* data, qint64 maxSize)
+bool Bootloader::_write(QextSerialPort* port, const uint8_t* data, qint64 maxSize)
{
qint64 bytesWritten = port->write((const char*)data, maxSize);
if (bytesWritten == -1) {
@@ -101,13 +102,13 @@ bool PX4Bootloader::write(QextSerialPort* port, const uint8_t* data, qint64 maxS
return true;
}
-bool PX4Bootloader::write(QextSerialPort* port, const uint8_t byte)
+bool Bootloader::_write(QextSerialPort* port, const uint8_t byte)
{
uint8_t buf[1] = { byte };
- return write(port, buf, 1);
+ return _write(port, buf, 1);
}
-bool PX4Bootloader::read(QextSerialPort* port, uint8_t* data, qint64 maxSize, int readTimeout)
+bool Bootloader::_read(QextSerialPort* port, uint8_t* data, qint64 maxSize, int readTimeout)
{
qint64 bytesAlreadyRead = 0;
@@ -137,11 +138,13 @@ bool PX4Bootloader::read(QextSerialPort* port, uint8_t* data, qint64 maxSize, in
return true;
}
-bool PX4Bootloader::getCommandResponse(QextSerialPort* port, int responseTimeout)
+/// Read a PROTO_SYNC command response from the bootloader
+/// @param responseTimeout Msecs to wait for response bytes to become available on port
+bool Bootloader::_getCommandResponse(QextSerialPort* port, int responseTimeout)
{
uint8_t response[2];
- if (!read(port, response, 2, responseTimeout)) {
+ if (!_read(port, response, 2, responseTimeout)) {
_errorString.prepend("Get Command Response: ");
return false;
}
@@ -164,18 +167,21 @@ bool PX4Bootloader::getCommandResponse(QextSerialPort* port, int responseTimeout
return true;
}
-bool PX4Bootloader::getBoardInfo(QextSerialPort* port, uint8_t param, uint32_t& value)
+/// Send a PROTO_GET_DEVICE command to retrieve a value from the PX4 bootloader
+/// @param param Value to retrieve using INFO_BOARD_* enums
+/// @param value Returned value
+bool Bootloader::_getPX4BoardInfo(QextSerialPort* port, uint8_t param, uint32_t& value)
{
uint8_t buf[3] = { PROTO_GET_DEVICE, param, PROTO_EOC };
- if (!write(port, buf, sizeof(buf))) {
+ if (!_write(port, buf, sizeof(buf))) {
goto Error;
}
port->flush();
- if (!read(port, (uint8_t*)&value, sizeof(value))) {
+ if (!_read(port, (uint8_t*)&value, sizeof(value))) {
goto Error;
}
- if (!getCommandResponse(port)) {
+ if (!_getCommandResponse(port)) {
goto Error;
}
@@ -186,15 +192,18 @@ Error:
return false;
}
-bool PX4Bootloader::sendCommand(QextSerialPort* port, const uint8_t cmd, int responseTimeout)
+/// Send a command to the bootloader
+/// @param cmd Command to send using PROTO_* enums
+/// @return true: Command sent and valid sync response returned
+bool Bootloader::_sendCommand(QextSerialPort* port, const uint8_t cmd, int responseTimeout)
{
uint8_t buf[2] = { cmd, PROTO_EOC };
- if (!write(port, buf, 2)) {
+ if (!_write(port, buf, 2)) {
goto Error;
}
port->flush();
- if (!getCommandResponse(port, responseTimeout)) {
+ if (!_getCommandResponse(port, responseTimeout)) {
goto Error;
}
@@ -205,10 +214,10 @@ Error:
return false;
}
-bool PX4Bootloader::erase(QextSerialPort* port)
+bool Bootloader::erase(QextSerialPort* port)
{
// Erase is slow, need larger timeout
- if (!sendCommand(port, PROTO_CHIP_ERASE, _eraseTimeout)) {
+ if (!_sendCommand(port, PROTO_CHIP_ERASE, _eraseTimeout)) {
_errorString = tr("Board erase failed: %1").arg(_errorString);
return false;
}
@@ -216,11 +225,20 @@ bool PX4Bootloader::erase(QextSerialPort* port)
return true;
}
-bool PX4Bootloader::program(QextSerialPort* port, const QString& firmwareFilename)
+bool Bootloader::program(QextSerialPort* port, const FirmwareImage* image)
{
- QFile firmwareFile(firmwareFilename);
+ if (image->imageIsBinFormat()) {
+ return _binProgram(port, image);
+ } else {
+ return _ihxProgram(port, image);
+ }
+}
+
+bool Bootloader::_binProgram(QextSerialPort* port, const FirmwareImage* image)
+{
+ QFile firmwareFile(image->binFilename());
if (!firmwareFile.open(QIODevice::ReadOnly)) {
- _errorString = tr("Unable to open firmware file %1: %2").arg(firmwareFilename).arg(firmwareFile.errorString());
+ _errorString = tr("Unable to open firmware file %1: %2").arg(image->binFilename()).arg(firmwareFile.errorString());
return false;
}
uint32_t imageSize = (uint32_t)firmwareFile.size();
@@ -248,12 +266,12 @@ bool PX4Bootloader::program(QextSerialPort* port, const QString& firmwareFilenam
Q_ASSERT(bytesToSend <= 0x8F);
bool failed = true;
- if (write(port, PROTO_PROG_MULTI)) {
- if (write(port, (uint8_t)bytesToSend)) {
- if (write(port, imageBuf, bytesToSend)) {
- if (write(port, PROTO_EOC)) {
+ if (_write(port, PROTO_PROG_MULTI)) {
+ if (_write(port, (uint8_t)bytesToSend)) {
+ if (_write(port, imageBuf, bytesToSend)) {
+ if (_write(port, PROTO_EOC)) {
port->flush();
- if (getCommandResponse(port)) {
+ if (_getCommandResponse(port)) {
failed = false;
}
}
@@ -270,7 +288,7 @@ bool PX4Bootloader::program(QextSerialPort* port, const QString& firmwareFilenam
// 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);
+ emit updateProgress(bytesSent, imageSize);
}
firmwareFile.close();
@@ -284,46 +302,131 @@ bool PX4Bootloader::program(QextSerialPort* port, const QString& firmwareFilenam
return true;
}
-bool PX4Bootloader::verify(QextSerialPort* port, const QString firmwareFilename)
+bool Bootloader::_ihxProgram(QextSerialPort* port, const FirmwareImage* image)
+{
+ uint32_t imageSize = image->imageSize();
+ uint32_t bytesSent = 0;
+
+ for (uint16_t index=0; indexihxBlockCount(); index++) {
+ bool failed;
+ uint16_t flashAddress;
+ QByteArray bytes;
+
+ if (!image->ihxGetBlock(index, flashAddress, bytes)) {
+ _errorString = QString("Unable to retrieve block from ihx: index %1").arg(index);
+ return false;
+ }
+
+ qCDebug(FirmwareUpgradeLog) << QString("Bootloader::_ihxProgram - address:%1 size:%2 block:%3").arg(flashAddress).arg(bytes.count()).arg(index);
+
+ // Set flash address
+
+ failed = true;
+ if (_write(port, PROTO_LOAD_ADDRESS) &&
+ _write(port, flashAddress & 0xFF) &&
+ _write(port, (flashAddress >> 8) & 0xFF) &&
+ _write(port, PROTO_EOC)) {
+ port->flush();
+ if (_getCommandResponse(port)) {
+ failed = false;
+ }
+ }
+
+ if (failed) {
+ _errorString = QString("Unable to set flash start address: 0x%2").arg(flashAddress, 8, 16, QLatin1Char('0'));
+ return false;
+ }
+
+ // Flash
+
+ int bytesIndex = 0;
+ uint16_t bytesLeftToWrite = bytes.count();
+
+ while (bytesLeftToWrite > 0) {
+ uint8_t bytesToWrite;
+
+ if (bytesLeftToWrite > PROG_MULTI_MAX) {
+ bytesToWrite = PROG_MULTI_MAX;
+ } else {
+ bytesToWrite = bytesLeftToWrite;
+ }
+
+ failed = true;
+ if (_write(port, PROTO_PROG_MULTI) &&
+ _write(port, bytesToWrite) &&
+ _write(port, &((uint8_t *)bytes.data())[bytesIndex], bytesToWrite) &&
+ _write(port, PROTO_EOC)) {
+ port->flush();
+ if (_getCommandResponse(port)) {
+ failed = false;
+ }
+ }
+ if (failed) {
+ _errorString = QString("Flash failed: %1 at address 0x%2").arg(_errorString).arg(flashAddress, 8, 16, QLatin1Char('0'));
+ return false;
+ }
+
+ bytesIndex += bytesToWrite;
+ bytesLeftToWrite -= bytesToWrite;
+ bytesSent += bytesToWrite;
+
+ emit updateProgress(bytesSent, imageSize);
+ }
+ }
+
+ return true;
+}
+
+bool Bootloader::verify(QextSerialPort* port, const FirmwareImage* image)
{
bool ret;
- if (_bootloaderVersion <= 2) {
- ret = _bootloaderVerifyRev2(port, firmwareFilename);
+ if (!image->imageIsBinFormat() || _bootloaderVersion <= 2) {
+ ret = _verifyBytes(port, image);
} else {
- ret = _bootloaderVerifyRev3(port);
+ ret = _verifyCRC(port);
}
- sendBootloaderReboot(port);
+ reboot(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(QextSerialPort* port, const QString firmwareFilename)
+/// @brief Verify the flash on bootloader eading it back and comparing it against the original image->
+bool Bootloader::_verifyBytes(QextSerialPort* port, const FirmwareImage* image)
{
- QFile firmwareFile(firmwareFilename);
+ if (image->imageIsBinFormat()) {
+ return _binVerifyBytes(port, image);
+ } else {
+ return _ihxVerifyBytes(port, image);
+ }
+}
+
+bool Bootloader::_binVerifyBytes(QextSerialPort* port, const FirmwareImage* image)
+{
+ Q_ASSERT(image->imageIsBinFormat());
+
+ QFile firmwareFile(image->binFilename());
if (!firmwareFile.open(QIODevice::ReadOnly)) {
- _errorString = tr("Unable to open firmware file %1: %2").arg(firmwareFilename).arg(firmwareFile.errorString());
+ _errorString = tr("Unable to open firmware file %1: %2").arg(image->binFilename()).arg(firmwareFile.errorString());
return false;
}
uint32_t imageSize = (uint32_t)firmwareFile.size();
- if (!sendCommand(port, PROTO_CHIP_VERIFY)) {
+ if (!_sendCommand(port, PROTO_CHIP_VERIFY)) {
return false;
}
uint8_t fileBuf[READ_MULTI_MAX];
- uint8_t flashBuf[READ_MULTI_MAX];
+ uint8_t readBuf[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);
+ if (bytesToRead > (int)sizeof(readBuf)) {
+ bytesToRead = (int)sizeof(readBuf);
}
Q_ASSERT((bytesToRead % 4) == 0);
@@ -337,48 +440,137 @@ bool PX4Bootloader::_bootloaderVerifyRev2(QextSerialPort* port, const QString fi
Q_ASSERT(bytesToRead <= 0x8F);
bool failed = true;
- if (write(port, PROTO_READ_MULTI)) {
- if (write(port, (uint8_t)bytesToRead)) {
- if (write(port, PROTO_EOC)) {
- port->flush();
- if (read(port, flashBuf, sizeof(flashBuf))) {
- if (getCommandResponse(port)) {
- failed = false;
- }
- }
+ if (_write(port, PROTO_READ_MULTI) &&
+ _write(port, (uint8_t)bytesToRead) &&
+ _write(port, PROTO_EOC)) {
+ port->flush();
+ if (_read(port, readBuf, sizeof(readBuf))) {
+ if (_getCommandResponse(port)) {
+ failed = false;
}
}
}
if (failed) {
- _errorString = tr("Verify failed: %1 at address: 0x%2").arg(_errorString).arg(bytesVerified, 8, 16, QLatin1Char('0'));
+ _errorString = tr("Read failed: %1 at address: 0x%2").arg(_errorString).arg(bytesVerified, 8, 16, QLatin1Char('0'));
return false;
}
for (int i=0; iimageIsBinFormat());
+
+ uint32_t imageSize = image->imageSize();
+ uint32_t bytesVerified = 0;
+
+ for (uint16_t index=0; indexihxBlockCount(); index++) {
+ bool failed;
+ uint16_t readAddress;
+ QByteArray imageBytes;
+
+ if (!image->ihxGetBlock(index, readAddress, imageBytes)) {
+ _errorString = QString("Unable to retrieve block from ihx: index %1").arg(index);
+ return false;
+ }
+
+ qCDebug(FirmwareUpgradeLog) << QString("Bootloader::_ihxVerifyBytes - address:%1 size:%2 block:%3").arg(readAddress).arg(imageBytes.count()).arg(index);
+
+ // Set read address
+
+ failed = true;
+ if (_write(port, PROTO_LOAD_ADDRESS) &&
+ _write(port, readAddress & 0xFF) &&
+ _write(port, (readAddress >> 8) & 0xFF) &&
+ _write(port, PROTO_EOC)) {
+ port->flush();
+ if (_getCommandResponse(port)) {
+ failed = false;
+ }
+ }
+
+ if (failed) {
+ _errorString = QString("Unable to set read start address: 0x%2").arg(readAddress, 8, 16, QLatin1Char('0'));
+ return false;
+ }
+
+ // Read back
+
+ int bytesIndex = 0;
+ uint16_t bytesLeftToRead = imageBytes.count();
+
+ while (bytesLeftToRead > 0) {
+ uint8_t bytesToRead;
+ uint8_t readBuf[READ_MULTI_MAX];
+
+ if (bytesLeftToRead > READ_MULTI_MAX) {
+ bytesToRead = READ_MULTI_MAX;
+ } else {
+ bytesToRead = bytesLeftToRead;
+ }
+
+ failed = true;
+ if (_write(port, PROTO_READ_MULTI) &&
+ _write(port, bytesToRead) &&
+ _write(port, PROTO_EOC)) {
+ port->flush();
+ if (_read(port, readBuf, bytesToRead)) {
+ if (_getCommandResponse(port)) {
+ failed = false;
+ }
+ }
+ }
+ if (failed) {
+ _errorString = tr("Read failed: %1 at address: 0x%2").arg(_errorString).arg(readAddress, 8, 16, QLatin1Char('0'));
+ return false;
+ }
+
+ // Compare
+
+ for (int i=0; iflush();
- if (read(port, (uint8_t*)&flashCRC, sizeof(flashCRC), _verifyTimeout)) {
- if (getCommandResponse(port)) {
+ if (_read(port, (uint8_t*)&flashCRC, sizeof(flashCRC), _verifyTimeout)) {
+ if (_getCommandResponse(port)) {
failed = false;
}
}
@@ -395,7 +587,7 @@ bool PX4Bootloader::_bootloaderVerifyRev3(QextSerialPort* port)
return true;
}
-bool PX4Bootloader::open(QextSerialPort* port, const QString portName)
+bool Bootloader::open(QextSerialPort* port, const QString portName)
{
Q_ASSERT(!port->isOpen());
@@ -414,10 +606,10 @@ bool PX4Bootloader::open(QextSerialPort* port, const QString portName)
return true;
}
-bool PX4Bootloader::sync(QextSerialPort* port)
+bool Bootloader::sync(QextSerialPort* port)
{
// Send sync command
- if (sendCommand(port, PROTO_GET_SYNC)) {
+ if (_sendCommand(port, PROTO_GET_SYNC)) {
return true;
} else {
_errorString.prepend("Sync: ");
@@ -425,10 +617,10 @@ bool PX4Bootloader::sync(QextSerialPort* port)
}
}
-bool PX4Bootloader::getBoardInfo(QextSerialPort* port, uint32_t& bootloaderVersion, uint32_t& boardID, uint32_t& flashSize)
+bool Bootloader::getPX4BoardInfo(QextSerialPort* port, uint32_t& bootloaderVersion, uint32_t& boardID, uint32_t& flashSize)
{
- if (!getBoardInfo(port, INFO_BL_REV, _bootloaderVersion)) {
+ if (!_getPX4BoardInfo(port, INFO_BL_REV, _bootloaderVersion)) {
goto Error;
}
if (_bootloaderVersion < BL_REV_MIN || _bootloaderVersion > BL_REV_MAX) {
@@ -436,11 +628,11 @@ bool PX4Bootloader::getBoardInfo(QextSerialPort* port, uint32_t& bootloaderVersi
goto Error;
}
- if (!getBoardInfo(port, INFO_BOARD_ID, _boardID)) {
+ if (!_getPX4BoardInfo(port, INFO_BOARD_ID, _boardID)) {
goto Error;
}
- if (!getBoardInfo(port, INFO_FLASH_SIZE, _boardFlashSize)) {
+ if (!_getPX4BoardInfo(port, INFO_FLASH_SIZE, _boardFlashSize)) {
qWarning() << _errorString;
goto Error;
}
@@ -456,7 +648,35 @@ Error:
return false;
}
-bool PX4Bootloader::sendBootloaderReboot(QextSerialPort* port)
+bool Bootloader::get3DRRadioBoardId(QextSerialPort* port, uint32_t& boardID)
+{
+ uint8_t buf[2] = { PROTO_GET_DEVICE, PROTO_EOC };
+
+ if (!_write(port, buf, sizeof(buf))) {
+ goto Error;
+ }
+ port->flush();
+
+ if (!_read(port, (uint8_t*)buf, 2)) {
+ goto Error;
+ }
+ if (!_getCommandResponse(port)) {
+ goto Error;
+ }
+
+ boardID = buf[0];
+
+ _bootloaderVersion = 0;
+ _boardFlashSize = 0;
+
+ return true;
+
+Error:
+ _errorString.prepend("Get Board Id: ");
+ return false;
+}
+
+bool Bootloader::reboot(QextSerialPort* port)
{
- return write(port, PROTO_BOOT) && write(port, PROTO_EOC);
+ return _write(port, PROTO_BOOT) && _write(port, PROTO_EOC);
}
diff --git a/src/VehicleSetup/Bootloader.h b/src/VehicleSetup/Bootloader.h
new file mode 100644
index 0000000000000000000000000000000000000000..ccd0355f6aaa9e116e1420eb190a6f8094ee1d14
--- /dev/null
+++ b/src/VehicleSetup/Bootloader.h
@@ -0,0 +1,156 @@
+/*=====================================================================
+
+ QGroundControl Open Source Ground Control Station
+
+ (c) 2009, 2014 QGROUNDCONTROL PROJECT
+
+ 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 .
+
+ ======================================================================*/
+
+/// @file
+/// @author Don Gagne
+
+#ifndef Bootloader_H
+#define Bootloader_H
+
+#include "FirmwareImage.h"
+
+#include "qextserialport.h"
+
+#include
+
+/// Bootloader Utility routines. Works with PX4 bootloader and 3DR Radio bootloader.
+class Bootloader : public QObject
+{
+ Q_OBJECT
+
+public:
+ explicit Bootloader(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; }
+
+ /// @brief Opens a port to the bootloader
+ bool open(QextSerialPort* port, const QString portName);
+
+ /// @brief Read a PROTO_SYNC response from the bootloader
+ /// @return true: Valid sync response was received
+ bool sync(QextSerialPort* port);
+
+ /// @brief Erases the current program
+ bool erase(QextSerialPort* port);
+
+ /// @brief Program the board with the specified image
+ bool program(QextSerialPort* port, const FirmwareImage* image);
+
+ /// @brief Verify the board flash.
+ bool verify(QextSerialPort* port, const FirmwareImage* image);
+
+ /// @brief Retrieve a set of board info from the bootloader of PX4 FMU and PX4 Flow boards
+ /// @param bootloaderVersion Returned INFO_BL_REV
+ /// @param boardID Returned INFO_BOARD_ID
+ /// @param flashSize Returned INFO_FLASH_SIZE
+ bool getPX4BoardInfo(QextSerialPort* port, uint32_t& bootloaderVersion, uint32_t& boardID, uint32_t& flashSize);
+
+ /// @brief Retrieve the board id from a 3DR Radio
+ bool get3DRRadioBoardId(QextSerialPort* port, uint32_t& boardID);
+
+ /// @brief Sends a PROTO_REBOOT command to the bootloader
+ bool reboot(QextSerialPort* port);
+
+ // Supported bootloader board ids
+ static const int boardIDPX4FMUV1 = 5; ///< PX4 V1 board
+ static const int boardIDPX4FMUV2 = 9; ///< PX4 V2 board
+ static const int boardIDPX4Flow = 6; ///< PX4 Flow board
+ static const int boardIDAeroCore = 98; ///< Gumstix AeroCore board
+ static const int boardID3DRRadio = 78; ///< 3DR Radio
+
+signals:
+ /// @brief Signals progress indicator for long running bootloader utility routines
+ void updateProgress(int curr, int total);
+
+private:
+ bool _binProgram(QextSerialPort* port, const FirmwareImage* image);
+ bool _ihxProgram(QextSerialPort* port, const FirmwareImage* image);
+
+ bool _write(QextSerialPort* port, const uint8_t* data, qint64 maxSize);
+ bool _write(QextSerialPort* port, const uint8_t byte);
+
+ bool _read(QextSerialPort* port, uint8_t* data, qint64 maxSize, int readTimeout = _readTimout);
+
+ bool _sendCommand(QextSerialPort* port, uint8_t cmd, int responseTimeout = _responseTimeout);
+ bool _getCommandResponse(QextSerialPort* port, const int responseTimeout = _responseTimeout);
+
+ bool _getPX4BoardInfo(QextSerialPort* port, uint8_t param, uint32_t& value);
+
+ bool _verifyBytes(QextSerialPort* port, const FirmwareImage* image);
+ bool _binVerifyBytes(QextSerialPort* port, const FirmwareImage* image);
+ bool _ihxVerifyBytes(QextSerialPort* port, const FirmwareImage* image);
+ bool _verifyCRC(QextSerialPort* port);
+
+ 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_LOAD_ADDRESS = 0x24, ///< set next programming 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 = 64, ///< write size for PROTO_PROG_MULTI, must be multiple of 4
+ READ_MULTI_MAX = 255 ///< read size for PROTO_READ_MULTI, must be multiple of 4
+ };
+
+ 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 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/VehicleSetup/FirmwareImage.cc b/src/VehicleSetup/FirmwareImage.cc
new file mode 100644
index 0000000000000000000000000000000000000000..1f49de63c315dc8e00dfaeeef47d0a653fecac02
--- /dev/null
+++ b/src/VehicleSetup/FirmwareImage.cc
@@ -0,0 +1,393 @@
+/*=====================================================================
+
+ QGroundControl Open Source Ground Control Station
+
+ (c) 2009, 2015 QGROUNDCONTROL PROJECT
+
+ 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 .
+
+ ======================================================================*/
+
+/// @file
+/// @brief Support for Intel Hex firmware file
+/// @author Don Gagne
+
+#include "FirmwareImage.h"
+#include "QGCLoggingCategory.h"
+
+#include
+#include
+#include
+#include
+#include
+#include
+#include
+#include
+
+FirmwareImage::FirmwareImage(QObject* parent) :
+ QObject(parent),
+ _imageSize(0)
+{
+
+}
+
+bool FirmwareImage::load(const QString& imageFilename, uint32_t boardId)
+{
+ _imageSize = 0;
+ _boardId = boardId;
+
+ if (imageFilename.endsWith(".bin")) {
+ return _binLoad(imageFilename);
+ _binFormat = true;
+ return true;
+ } else if (imageFilename.endsWith(".px4")) {
+ _binFormat = true;
+ return _px4Load(imageFilename);
+ } else if (imageFilename.endsWith(".ihx")) {
+ _binFormat = false;
+ return _ihxLoad(imageFilename);
+ } else {
+ emit errorMessage("Unsupported file format");
+ return false;
+ }
+}
+
+bool FirmwareImage::_readByteFromStream(QTextStream& stream, uint8_t& byte)
+{
+ QString hex = stream.read(2);
+
+ if (hex.count() != 2) {
+ return false;
+ }
+
+ bool success;
+ byte = (uint8_t)hex.toInt(&success, 16);
+
+ return success;
+}
+
+bool FirmwareImage::_readWordFromStream(QTextStream& stream, uint16_t& word)
+{
+ QString hex = stream.read(4);
+
+ if (hex.count() != 4) {
+ return false;
+ }
+
+ bool success;
+ word = (uint16_t)hex.toInt(&success, 16);
+
+ return success;
+}
+
+bool FirmwareImage::_readBytesFromStream(QTextStream& stream, uint8_t byteCount, QByteArray& bytes)
+{
+ bytes.clear();
+
+ while (byteCount) {
+ uint8_t byte;
+
+ if (!_readByteFromStream(stream, byte)) {
+ return false;
+ }
+ bytes += byte;
+
+ byteCount--;
+ }
+
+ return true;
+}
+
+bool FirmwareImage::_ihxLoad(const QString& ihxFilename)
+{
+ _imageSize = 0;
+ _ihxBlocks.clear();
+
+ QFile ihxFile(ihxFilename);
+ if (!ihxFile.open(QIODevice::ReadOnly | QIODevice::Text)) {
+ emit errorMessage(QString("Unable to open firmware file %1, error: %2").arg(ihxFilename).arg(ihxFile.errorString()));
+ return false;
+ }
+
+ QTextStream stream(&ihxFile);
+
+ while (true) {
+ if (stream.read(1) != ":") {
+ emit errorMessage("Incorrectly formatted .ihx file, line does not begin with :");
+ return false;
+ }
+
+ uint8_t blockByteCount;
+ uint16_t address;
+ uint8_t recordType;
+ QByteArray bytes;
+ uint8_t crc;
+
+ if (!_readByteFromStream(stream, blockByteCount) ||
+ !_readWordFromStream(stream, address) ||
+ !_readByteFromStream(stream, recordType) ||
+ !_readBytesFromStream(stream, blockByteCount, bytes) ||
+ !_readByteFromStream(stream, crc)) {
+ emit errorMessage("Incorrectly formatted line in .ihx file, line too short");
+ return false;
+ }
+
+ if (!(recordType == 0 || recordType == 1)) {
+ emit errorMessage(QString("Unsupported record type in file: %1").arg(recordType));
+ return false;
+ }
+
+ if (recordType == 0) {
+ bool appendToLastBlock = false;
+
+ // Can we append this block to the last one?
+
+ if (_ihxBlocks.count()) {
+ int lastBlockIndex = _ihxBlocks.count() - 1;
+
+ if (_ihxBlocks[lastBlockIndex].address + _ihxBlocks[lastBlockIndex].bytes.count() == address) {
+ appendToLastBlock = true;
+ }
+ }
+
+ if (appendToLastBlock) {
+ _ihxBlocks[_ihxBlocks.count() - 1].bytes += bytes;
+ qCDebug(FirmwareUpgradeLog) << QString("_ihxLoad - append - address:%1 size:%2 block:%3").arg(address).arg(blockByteCount).arg(ihxBlockCount());
+ } else {
+ IntelHexBlock_t block;
+
+ block.address = address;
+ block.bytes = bytes;
+
+ _ihxBlocks += block;
+ qCDebug(FirmwareUpgradeLog) << QString("_ihxLoad - new block - address:%1 size:%2 block:%3").arg(address).arg(blockByteCount).arg(ihxBlockCount());
+ }
+
+ _imageSize += blockByteCount;
+ } else if (recordType == 1) {
+ // EOF
+ qCDebug(FirmwareUpgradeLog) << QString("_ihxLoad - EOF");
+ break;
+ }
+
+ // Move to next line
+ stream.readLine();
+ }
+
+ ihxFile.close();
+
+ return true;
+}
+
+bool FirmwareImage::_px4Load(const QString& imageFilename)
+{
+ _imageSize = 0;
+
+ // We need to collect information from the .px4 file as well as pull the binary image out to a seperate file.
+
+ QFile px4File(imageFilename);
+ if (!px4File.open(QIODevice::ReadOnly | QIODevice::Text)) {
+ emit errorMessage(QString("Unable to open firmware file %1, error: %2").arg(imageFilename).arg(px4File.errorString()));
+ return false;
+ }
+
+ QByteArray bytes = px4File.readAll();
+ px4File.close();
+ QJsonDocument doc = QJsonDocument::fromJson(bytes);
+
+ if (doc.isNull()) {
+ emit errorMessage("Supplied file is not a valid JSON document");
+ return false;
+ }
+
+ 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(static_cast(0xFF)));
+ }
+
+ // Store decompressed image file in same location as original download file
+ QDir imageDir = QFileInfo(imageFilename).dir();
+ QString decompressFilename = imageDir.filePath("PX4FlashUpgrade.bin");
+
+ QFile decompressFile(decompressFilename);
+ if (!decompressFile.open(QIODevice::WriteOnly | QIODevice::Truncate)) {
+ emit errorMessage(QString("Unable to open decompressed file %1 for writing, error: %2").arg(decompressFilename).arg(decompressFile.errorString()));
+ return false;
+ }
+
+ qint64 bytesWritten = decompressFile.write(decompressedBytes);
+ if (bytesWritten != decompressedBytes.count()) {
+ emit errorMessage(QString("Write failed for decompressed image file, error: %1").arg(decompressFile.errorString()));
+ return false;
+ }
+ decompressFile.close();
+
+ _binFilename = decompressFilename;
+
+ return true;
+}
+
+/// Decompress a set of bytes stored in a Json document.
+bool FirmwareImage::_decompressJsonValue(const QJsonObject& jsonObject, ///< JSON object
+ const QByteArray& jsonDocBytes, ///< Raw bytes of JSON document
+ const QString& sizeKey, ///< key which holds byte size
+ const QString& bytesKey, ///< key which holds compress bytes
+ QByteArray& decompressedBytes) ///< Returned decompressed bytes
+{
+ // Validate decompressed size key
+ if (!jsonObject.contains(sizeKey)) {
+ emit statusMessage(QString("Firmware file missing %1 key").arg(sizeKey));
+ return false;
+ }
+ int decompressedSize = jsonObject.value(QString(sizeKey)).toInt();
+ if (decompressedSize == 0) {
+ emit errorMessage(QString("Firmware file has invalid decompressed size for %1").arg(sizeKey));
+ return false;
+ }
+
+ // 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 parts = QString(jsonDocBytes).split(QString("\"%1\": \"").arg(bytesKey));
+ if (parts.count() == 1) {
+ emit errorMessage(QString("Could not find compressed bytes for %1 in Firmware file").arg(bytesKey));
+ return false;
+ }
+ parts = parts.last().split("\"");
+ if (parts.count() == 1) {
+ emit errorMessage(QString("Incorrectly formed compressed bytes section for %1 in Firmware file").arg(bytesKey));
+ return false;
+ }
+
+ // Store decompressed size as first four bytes. This is required by qUncompress routine.
+ QByteArray raw;
+ raw.append((unsigned char)((decompressedSize >> 24) & 0xFF));
+ raw.append((unsigned char)((decompressedSize >> 16) & 0xFF));
+ raw.append((unsigned char)((decompressedSize >> 8) & 0xFF));
+ raw.append((unsigned char)((decompressedSize >> 0) & 0xFF));
+
+ QByteArray raw64 = parts.first().toUtf8();
+ raw.append(QByteArray::fromBase64(raw64));
+ decompressedBytes = qUncompress(raw);
+
+ if (decompressedBytes.count() == 0) {
+ emit errorMessage(QString("Firmware file has 0 length %1").arg(bytesKey));
+ return false;
+ }
+ if (decompressedBytes.count() != decompressedSize) {
+ emit errorMessage(QString("Size for decompressed %1 does not match stored size: Expected(%1) Actual(%2)").arg(decompressedSize).arg(decompressedBytes.count()));
+ return false;
+ }
+
+ emit statusMessage(QString("Succesfully decompressed %1").arg(bytesKey));
+
+ return true;
+}
+
+uint16_t FirmwareImage::ihxBlockCount(void) const
+{
+ return _ihxBlocks.count();
+}
+
+bool FirmwareImage::ihxGetBlock(uint16_t index, uint16_t& address, QByteArray& bytes) const
+{
+ address = 0;
+ bytes.clear();
+
+ if (index < ihxBlockCount()) {
+ address = _ihxBlocks[index].address;
+ bytes = _ihxBlocks[index].bytes;
+ return true;
+ } else {
+ return false;
+ }
+}
+
+bool FirmwareImage::_binLoad(const QString& imageFilename)
+{
+ QFile binFile(imageFilename);
+ if (!binFile.open(QIODevice::ReadOnly)) {
+ emit errorMessage(QString("Unabled to open firmware file %1, %2").arg(imageFilename).arg(binFile.errorString()));
+ return false;
+ }
+
+ _imageSize = (uint32_t)binFile.size();
+
+ binFile.close();
+
+ return true;
+}
diff --git a/src/VehicleSetup/FirmwareImage.h b/src/VehicleSetup/FirmwareImage.h
new file mode 100644
index 0000000000000000000000000000000000000000..6c3467dff74ea27aa172292180210a34f310f45a
--- /dev/null
+++ b/src/VehicleSetup/FirmwareImage.h
@@ -0,0 +1,103 @@
+/*=====================================================================
+
+ QGroundControl Open Source Ground Control Station
+
+ (c) 2009, 2015 QGROUNDCONTROL PROJECT
+
+ 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 .
+
+ ======================================================================*/
+
+/// @file
+/// @author Don Gagne
+
+#ifndef FirmwareImage_H
+#define FirmwareImage_H
+
+#include
+#include
+#include
+#include
+#include
+
+#include
+
+/// Support for Intel Hex firmware file
+class FirmwareImage : public QObject
+{
+ Q_OBJECT
+
+public:
+ FirmwareImage(QObject *parent = 0);
+
+ /// Loads the specified image file. Supported formats: .px4, .bin, .ihx.
+ /// Emits errorMesssage and statusMessage signals while loading.
+ /// @param imageFilename Image file to load
+ /// @param boardId Board id that we are going to load this image onto
+ /// @return true: success, false: failure
+ bool load(const QString& imageFilename, uint32_t boardId);
+
+ /// Returns the number of bytes in the image.
+ uint32_t imageSize(void) const { return _imageSize; }
+
+ /// @return true: image format is .bin
+ bool imageIsBinFormat(void) const { return _binFormat; }
+
+ /// @return Filename for .bin file
+ QString binFilename(void) const { return _binFilename; }
+
+ /// @return Block count from .ihx image
+ uint16_t ihxBlockCount(void) const;
+
+ /// Retrieves the specified block from the .ihx image
+ /// @param index Index of block to return
+ /// @param address Address of returned block
+ /// @param byets Bytes of returned block
+ /// @return true: block retrieved
+ bool ihxGetBlock(uint16_t index, uint16_t& address, QByteArray& bytes) const;
+
+signals:
+ void errorMessage(const QString& errorString);
+ void statusMessage(const QString& warningtring);
+
+private:
+ bool _binLoad(const QString& px4Filename);
+ bool _px4Load(const QString& px4Filename);
+ bool _ihxLoad(const QString& ihxFilename);
+
+ bool _readByteFromStream(QTextStream& stream, uint8_t& byte);
+ bool _readWordFromStream(QTextStream& stream, uint16_t& word);
+ bool _readBytesFromStream(QTextStream& stream, uint8_t byteCount, QByteArray& bytes);
+
+ bool _decompressJsonValue(const QJsonObject& jsonObject,
+ const QByteArray& jsonDocBytes,
+ const QString& sizeKey,
+ const QString& bytesKey,
+ QByteArray& decompressedBytes);
+
+ typedef struct {
+ uint16_t address;
+ QByteArray bytes;
+ } IntelHexBlock_t;
+
+ bool _binFormat;
+ uint32_t _boardId;
+ QString _binFilename;
+ QList _ihxBlocks;
+ uint32_t _imageSize;
+};
+
+#endif
diff --git a/src/VehicleSetup/FirmwareUpgrade.qml b/src/VehicleSetup/FirmwareUpgrade.qml
index f5ed9f980dc059d85fef840d4c7dcd580d630f86..f4d5627d4010dc04a35c29ab4a5ca3915779ce24 100644
--- a/src/VehicleSetup/FirmwareUpgrade.qml
+++ b/src/VehicleSetup/FirmwareUpgrade.qml
@@ -34,158 +34,337 @@ import QGroundControl.Controllers 1.0
import QGroundControl.ScreenTools 1.0
QGCView {
- viewPanel: panel
+ id: qgcView
+ viewPanel: panel
+
+ // User visible strings
+ readonly property string title: "FIRMWARE UPDATE"
+ readonly property string highlightPrefix: ""
+ readonly property string highlightSuffix: ""
+ readonly property string welcomeText: "QGroundControl can upgrade the firmware on Pixhawk devices, 3DR Radios and PX4 Flow Smart Cameras."
+ readonly property string plugInText: highlightPrefix + "Plug in your device" + highlightSuffix + " via USB to " + highlightPrefix + "start" + highlightSuffix + " firmware upgrade"
+ readonly property string qgcDisconnectText: "All QGroundControl connections to vehicles must be disconnected prior to firmware upgrade. " +
+ "Click " + highlightPrefix + "Disconnect" + highlightSuffix + " in the toolbar above."
+ property string usbUnplugText: "Device must be disconnected from USB to start firmware upgrade. " +
+ highlightPrefix + "Disconnect {0}" + highlightSuffix + " from usb."
property string firmwareWarningMessage
+ property bool controllerCompleted: false
+ property bool initialBoardSearch: true
+ property string firmwareName
+
+ function cancelFlash() {
+ statusTextArea.append(highlightPrefix + "Upgrade cancelled" + highlightSuffix)
+ statusTextArea.append("------------------------------------------")
+ controller.cancel()
+ flashCompleteWaitTimer.running = true
+ }
QGCPalette { id: qgcPal; colorGroupEnabled: panel.enabled }
FirmwareUpgradeController {
id: controller
- upgradeButton: upgradeButton
progressBar: progressBar
statusLog: statusTextArea
- firmwareType: FirmwareUpgradeController.StableFirmware
- onShowMessage: {
- showMessage(title, message, StandardButton.Ok)
+ Component.onCompleted: {
+ controllerCompleted = true
+ if (qgcView.completedSignalled) {
+ // We can only start the board search when the Qml and Controller are completely done loading
+ controller.startBoardSearch()
+ }
+ }
+
+ onNoBoardFound: {
+ initialBoardSearch = false
+ statusTextArea.append(plugInText)
}
+
+ onBoardGone: {
+ initialBoardSearch = false
+ statusTextArea.append(plugInText)
+ }
+
+ onBoardFound: {
+ if (initialBoardSearch) {
+ // Board was found right away, so something is already plugged in before we've started upgrade
+ if (controller.qgcConnections) {
+ statusTextArea.append(qgcDisconnectText)
+ } else {
+ statusTextArea.append(usbUnplugText.replace('{0}', controller.boardType))
+ }
+ } else {
+ // We end up here when we detect a board plugged in after we've started upgrade
+ statusTextArea.append(highlightPrefix + "Found device" + highlightSuffix + ": " + controller.boardType)
+ if (controller.boardType == "Pixhawk") {
+ showDialog(pixhawkFirmwareSelectDialog, title, 50, StandardButton.Ok | StandardButton.Cancel)
+ }
+ }
+ }
+
+ onError: {
+ hideDialog()
+ flashCompleteWaitTimer.running = true
+ }
+
+ onFlashComplete: flashCompleteWaitTimer.running = true
}
- QGCViewPanel {
- id: panel
- anchors.fill: parent
+ onCompleted: {
+ if (controllerCompleted) {
+ // We can only start the board search when the Qml and Controller are completely done loading
+ controller.startBoardSearch()
+ }
+ }
- Component {
- id: firmwareWarningComponent
+ // After a flash completes we start this timer to trigger resetting the ui back to it's initial state of being ready to
+ // flash another board. We do this only after the timer triggers to leave the results of the previous flash on the screen
+ // for a small amount amount of time.
- QGCViewMessage {
- message: firmwareWarningMessage
+ Timer {
+ id: flashCompleteWaitTimer
+ interval: 15000
- function accept() {
- hideDialog()
- controller.doFirmwareUpgrade();
- }
- }
+ onTriggered: {
+ initialBoardSearch = true
+ progressBar.value = 0
+ statusTextArea.append(welcomeText)
+ controller.startBoardSearch()
}
+ }
+
+ Component {
+ id: pixhawkFirmwareSelectDialog
- Column {
+ QGCViewDialog {
anchors.fill: parent
+
+ property bool showVersionSelection: apmFlightStack.checked || advancedMode.checked
- QGCLabel {
- text: "FIRMWARE UPDATE"
- font.pixelSize: ScreenTools.largeFontPixelSize
+ function accept() {
+ hideDialog()
+ controller.flash(firmwareVersionCombo.model.get(firmwareVersionCombo.currentIndex).firmwareType)
+ }
+
+ function reject() {
+ cancelFlash()
+ hideDialog()
+ }
+
+ ExclusiveGroup {
+ id: firmwareGroup
+ }
+
+ ListModel {
+ id: px4FirmwareTypeList
+
+ ListElement {
+ text: qsTr("Standard Version (stable)");
+ firmwareType: FirmwareUpgradeController.PX4StableFirmware
+ }
+ ListElement {
+ text: qsTr("Beta Testing (beta)");
+ firmwareType: FirmwareUpgradeController.PX4BetaFirmware
+ }
+ ListElement {
+ text: qsTr("Developer Build (master)");
+ firmwareType: FirmwareUpgradeController.PX4DeveloperFirmware
+ }
+ ListElement {
+ text: qsTr("Custom firmware file...");
+ firmwareType: FirmwareUpgradeController.PX4CustomFirmware
+ }
}
+
+ ListModel {
+ id: apmFirmwareTypeList
- Item {
- // Just used as a spacer
- height: 20
- width: 10
+ ListElement {
+ text: "ArduCopter Quad"
+ firmwareType: FirmwareUpgradeController.ApmArduCopterQuadFirmware
+ }
+ ListElement {
+ text: "ArduCopter X8"
+ firmwareType: FirmwareUpgradeController.ApmArduCopterX8Firmware
+ }
+ ListElement {
+ text: "ArduCopter Hexa"
+ firmwareType: FirmwareUpgradeController.ApmArduCopterHexaFirmware
+ }
+ ListElement {
+ text: "ArduCopter Octo"
+ firmwareType: FirmwareUpgradeController.ApmArduCopterOctoFirmware
+ }
+ ListElement {
+ text: "ArduCopter Y"
+ firmwareType: FirmwareUpgradeController.ApmArduCopterYFirmware
+ }
+ ListElement {
+ text: "ArduCopter Y6"
+ firmwareType: FirmwareUpgradeController.ApmArduCopterY6Firmware
+ }
+ ListElement {
+ text: "ArduCopter Heli"
+ firmwareType: FirmwareUpgradeController.ApmArduCopterHeliFirmware
+ }
+ ListElement {
+ text: "ArduPlane"
+ firmwareType: FirmwareUpgradeController.ApmArduPlaneFirmware
+ }
+ ListElement {
+ text: "Rover"
+ firmwareType: FirmwareUpgradeController.ApmRoverFirmware
+ }
}
- Row {
- spacing: 10
-
- ListModel {
- id: firmwareItems
- ListElement {
- text: qsTr("Standard Version (stable)");
- firmwareType: FirmwareUpgradeController.StableFirmware
- }
- ListElement {
- text: qsTr("Beta Testing (beta)");
- firmwareType: FirmwareUpgradeController.BetaFirmware
- }
- ListElement {
- text: qsTr("Developer Build (master)");
- firmwareType: FirmwareUpgradeController.DeveloperFirmware
- }
- ListElement {
- text: qsTr("Custom firmware file...");
- firmwareType: FirmwareUpgradeController.CustomFirmware
- }
+ Column {
+ anchors.fill: parent
+ spacing: defaultTextHeight
+
+ QGCLabel {
+ width: parent.width
+ wrapMode: Text.WordWrap
+ text: "Detected Pixhawk board. You can select from the following flight stacks:"
}
- QGCComboBox {
- id: firmwareCombo
- width: 200
- height: upgradeButton.height
- model: firmwareItems
- }
-
- QGCButton {
- id: upgradeButton
- text: "UPGRADE"
- primary: true
- onClicked: {
- if (controller.activeQGCConnections()) {
- showMessage("Firmware Upgrade",
- "There are still vehicles connected to QGroundControl. " +
- "You must disconnect all vehicles from QGroundControl prior to Firmware Upgrade.",
- StandardButton.Ok)
- return
- }
+ function firmwareVersionChanged(model) {
+ firmwareVersionWarningLabel.visible = false
+ // All of this bizarre, setting model to null and index to 1 and then to 0 is to work around
+ // strangeness in the combo box implementation. This sequence of steps correctly changes the combo model
+ // without generating any warnings and correctly updates the combo text with the new selection.
+ firmwareVersionCombo.model = null
+ firmwareVersionCombo.model = model
+ firmwareVersionCombo.currentIndex = 1
+ firmwareVersionCombo.currentIndex = 0
+ }
- if (controller.pluggedInBoard()) {
- showMessage("Firmware Upgrade",
- "You vehicle is currently connected via USB. " +
- "You must unplug your vehicle from USB prior to Firmware Upgrade.",
- StandardButton.Ok)
- return
- }
+ QGCRadioButton {
+ id: px4FlightStack
+ checked: true
+ exclusiveGroup: firmwareGroup
+ text: "PX4 Flight Stack (full QGC support)"
+
+ onClicked: parent.firmwareVersionChanged(px4FirmwareTypeList)
+ }
+
+ QGCRadioButton {
+ id: apmFlightStack
+ exclusiveGroup: firmwareGroup
+ text: "APM Flight Stack (partial QGC support)"
- controller.firmwareType = firmwareItems.get(firmwareCombo.currentIndex).firmwareType
-
- if (controller.firmwareType == 1) {
- firmwareWarningMessage = "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" +
- "Click Cancel to abort upgrade, Click Ok to Upgrade anwyay"
- showDialog(firmwareWarningComponent, "Firmware Upgrade", 50, StandardButton.Cancel | StandardButton.Ok)
- } else if (controller.firmwareType == 2) {
- firmwareWarningMessage = "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" +
- "Click Cancel to abort upgrade, Click Ok to Upgrade anwyay"
- showDialog(firmwareWarningComponent, "Firmware Upgrade", 50, StandardButton.Cancel | StandardButton.Ok)
- } else {
- controller.doFirmwareUpgrade();
+ onClicked: parent.firmwareVersionChanged(apmFirmwareTypeList)
+ }
+
+ QGCLabel {
+ width: parent.width
+ wrapMode: Text.WordWrap
+ visible: showVersionSelection
+ text: "Select which version of the above flight stack you would like to install:"
+ }
+
+ QGCComboBox {
+ id: firmwareVersionCombo
+ width: 200
+ visible: showVersionSelection
+ model: px4FirmwareTypeList
+
+ onActivated: {
+ if (model.get(index).firmwareType == FirmwareUpgradeController.PX4BetaFirmware) {
+ firmwareVersionWarningLabel.visible = true
+ firmwareVersionWarningLabel.text = "WARNING: BETA FIRMWARE. " +
+ "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."
+ } else if (model.get(index).firmwareType == FirmwareUpgradeController.PX4DeveloperFirmware) {
+ firmwareVersionWarningLabel.visible = true
+ firmwareVersionWarningLabel.text = "WARNING: CONTINUOUS BUILD FIRMWARE. " +
+ "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."
+ } else {
+ firmwareVersionWarningLabel.visible = false
}
- }
+ }
+ }
+
+ QGCLabel {
+ id: firmwareVersionWarningLabel
+ width: parent.width
+ wrapMode: Text.WordWrap
+ visible: false
+ }
+ }
+
+ QGCCheckBox {
+ id: advancedMode
+ anchors.bottom: parent.bottom
+ text: "Advanced mode"
+
+ onClicked: {
+ firmwareVersionCombo.currentIndex = 0
+ firmwareVersionWarningLabel.visible = false
}
}
- Item {
- // Just used as a spacer
- height: 20
- width: 10
+ QGCButton {
+ anchors.leftMargin: ScreenTools.defaultFontPixelWidth * 2
+ anchors.left: advancedMode.right
+ anchors.bottom: parent.bottom
+ text: "Help me pick a flight stack"
+ onClicked: Qt.openUrlExternally("http://pixhawk.org/choice")
}
+ } // QGCViewDialog
+ } // Component - pixhawkFirmwareSelectDialog
+
+
+ Component {
+ id: firmwareWarningDialog
+
+ QGCViewMessage {
+ message: firmwareWarningMessage
- ProgressBar {
- id: progressBar
- width: parent.width
+ function accept() {
+ hideDialog()
+ controller.doFirmwareUpgrade();
}
+ }
+ }
+
+ QGCViewPanel {
+ id: panel
+ anchors.fill: parent
- TextArea {
- id: statusTextArea
+ QGCLabel {
+ id: titleLabel
+ text: title
+ font.pixelSize: ScreenTools.largeFontPixelSize
+ }
- width: parent.width
- height: 300
- readOnly: true
- frameVisible: false
- font.pixelSize: ScreenTools.defaultFontPixelSize
-
- text: qsTr("Please disconnect all vehicles from QGroundControl before selecting Upgrade.")
+ ProgressBar {
+ id: progressBar
+ anchors.topMargin: ScreenTools.defaultFontPixelHeight
+ anchors.top: titleLabel.bottom
+ width: parent.width
+ }
- style: TextAreaStyle {
- textColor: qgcPal.text
- backgroundColor: qgcPal.windowShade
- }
+ TextArea {
+ id: statusTextArea
+ anchors.topMargin: ScreenTools.defaultFontPixelHeight
+ anchors.top: progressBar.bottom
+ anchors.bottom: parent.bottom
+ width: parent.width
+ readOnly: true
+ frameVisible: false
+ font.pixelSize: ScreenTools.defaultFontPixelSize
+ textFormat: TextEdit.RichText
+ text: welcomeText
+
+ style: TextAreaStyle {
+ textColor: qgcPal.text
+ backgroundColor: qgcPal.windowShade
}
- } // Column
- } // QGCViewPanel
-} // QGCView
+ }
+ } // QGCViewPabel
+} // QGCView
\ No newline at end of file
diff --git a/src/VehicleSetup/FirmwareUpgradeController.cc b/src/VehicleSetup/FirmwareUpgradeController.cc
index 70019000347931ccbf7c8760eda55ad79dc480fe..a00922c77558e2f36e9f6178e29f628dd8743fbf 100644
--- a/src/VehicleSetup/FirmwareUpgradeController.cc
+++ b/src/VehicleSetup/FirmwareUpgradeController.cc
@@ -26,16 +26,7 @@
/// @author Don Gagne
#include "FirmwareUpgradeController.h"
-
-#include
-#include
-#include
-#include
-#include
-#include
-#include
-#include
-
+#include "Bootloader.h"
#include "QGCFileDialog.h"
#include "QGCMessageBox.h"
@@ -43,187 +34,229 @@
FirmwareUpgradeController::FirmwareUpgradeController(void) :
_downloadManager(NULL),
_downloadNetworkReply(NULL),
- _firmwareType(StableFirmware),
- _upgradeButton(NULL),
- _statusLog(NULL)
+ _statusLog(NULL),
+ _image(NULL)
{
_threadController = new PX4FirmwareUpgradeThreadController(this);
Q_CHECK_PTR(_threadController);
- connect(_threadController, &PX4FirmwareUpgradeThreadController::foundBoard, this, &FirmwareUpgradeController::_foundBoard);
- connect(_threadController, &PX4FirmwareUpgradeThreadController::foundBootloader, this, &FirmwareUpgradeController::_foundBootloader);
- connect(_threadController, &PX4FirmwareUpgradeThreadController::bootloaderSyncFailed, this, &FirmwareUpgradeController::_bootloaderSyncFailed);
- connect(_threadController, &PX4FirmwareUpgradeThreadController::error, this, &FirmwareUpgradeController::_error);
- connect(_threadController, &PX4FirmwareUpgradeThreadController::complete, this, &FirmwareUpgradeController::_complete);
- connect(_threadController, &PX4FirmwareUpgradeThreadController::findTimeout, this, &FirmwareUpgradeController::_findTimeout);
- connect(_threadController, &PX4FirmwareUpgradeThreadController::updateProgress, this, &FirmwareUpgradeController::_updateProgress);
-
+ connect(_threadController, &PX4FirmwareUpgradeThreadController::foundBoard, this, &FirmwareUpgradeController::_foundBoard);
+ connect(_threadController, &PX4FirmwareUpgradeThreadController::noBoardFound, this, &FirmwareUpgradeController::_noBoardFound);
+ connect(_threadController, &PX4FirmwareUpgradeThreadController::boardGone, this, &FirmwareUpgradeController::_boardGone);
+ connect(_threadController, &PX4FirmwareUpgradeThreadController::foundBootloader, this, &FirmwareUpgradeController::_foundBootloader);
+ connect(_threadController, &PX4FirmwareUpgradeThreadController::bootloaderSyncFailed, this, &FirmwareUpgradeController::_bootloaderSyncFailed);
+ connect(_threadController, &PX4FirmwareUpgradeThreadController::error, this, &FirmwareUpgradeController::_error);
+ connect(_threadController, &PX4FirmwareUpgradeThreadController::updateProgress, this, &FirmwareUpgradeController::_updateProgress);
+ connect(_threadController, &PX4FirmwareUpgradeThreadController::status, this, &FirmwareUpgradeController::_status);
+ connect(_threadController, &PX4FirmwareUpgradeThreadController::eraseStarted, this, &FirmwareUpgradeController::_eraseStarted);
+ connect(_threadController, &PX4FirmwareUpgradeThreadController::eraseComplete, this, &FirmwareUpgradeController::_eraseComplete);
+ connect(_threadController, &PX4FirmwareUpgradeThreadController::flashComplete, this, &FirmwareUpgradeController::_flashComplete);
+ connect(_threadController, &PX4FirmwareUpgradeThreadController::updateProgress, this, &FirmwareUpgradeController::_updateProgress);
+
+ connect(LinkManager::instance(), &LinkManager::linkDisconnected, this, &FirmwareUpgradeController::_linkDisconnected);
+
connect(&_eraseTimer, &QTimer::timeout, this, &FirmwareUpgradeController::_eraseProgressTick);
}
-/// @brief Cancels the current state and returns to the begin start
-void FirmwareUpgradeController::_cancel(void)
+void FirmwareUpgradeController::startBoardSearch(void)
{
- // Bootloader may still still open, reboot to close and heopfully get back to FMU
- _threadController->sendBootloaderReboot();
-
- Q_ASSERT(_upgradeButton);
- _upgradeButton->setEnabled(true);
+ _bootloaderFound = false;
+ _startFlashWhenBootloaderFound = false;
+ _threadController->startFindBoardLoop();
}
-/// @brief Begins the process or searching for the board
-void FirmwareUpgradeController::_findBoard(void)
+void FirmwareUpgradeController::flash(FirmwareType_t firmwareType)
{
- QString msg("Plug your board into USB now. Press Ok when board is plugged in.");
-
- _appendStatusLog(msg);
- emit showMessage("Firmware Upgrade", msg);
-
- _searchingForBoard = true;
- _threadController->findBoard(_findBoardTimeoutMsec);
+ if (_bootloaderFound) {
+ _getFirmwareFile(firmwareType);
+ } else {
+ // We haven't found the bootloader yet. Need to wait until then to flash
+ _startFlashWhenBootloaderFound = true;
+ _startFlashWhenBootloaderFoundFirmwareType = firmwareType;
+ }
}
-/// @brief Called when board has been found by the findBoard process
-void FirmwareUpgradeController::_foundBoard(bool firstTry, const QString portName, QString portDescription)
+void FirmwareUpgradeController::cancel(void)
{
- if (firstTry) {
- // Board is still plugged
- _cancel();
- emit showMessage("Board plugged in",
- "Please unplug your board before beginning the Firmware Upgrade process. "
- "Click Upgrade again once the board is unplugged.");
- } else {
- _portName = portName;
- _portDescription = portDescription;
+ _eraseTimer.stop();
+ _threadController->cancel();
+}
- _appendStatusLog(tr("Board found:"));
- _appendStatusLog(tr(" Port: %1").arg(_portName));
- _appendStatusLog(tr(" Description: %1").arg(_portName));
-
- _findBootloader();
+void FirmwareUpgradeController::_foundBoard(bool firstAttempt, const QSerialPortInfo& info, int type)
+{
+ _foundBoardInfo = info;
+ switch (type) {
+ case FoundBoardPX4FMUV1:
+ _foundBoardType = "PX4 FMU V1";
+ _startFlashWhenBootloaderFound = false;
+ break;
+ case FoundBoardPX4FMUV2:
+ _foundBoardType = "Pixhawk";
+ _startFlashWhenBootloaderFound = false;
+ break;
+ case FoundBoardPX4Flow:
+ case FoundBoard3drRadio:
+ _foundBoardType = type == FoundBoardPX4Flow ? "PX4 Flow" : "3DR Radio";
+ if (!firstAttempt) {
+ // PX4 Flow and Radio always flash stable firmware, so we can start right away without
+ // any further user input.
+ _startFlashWhenBootloaderFound = true;
+ _startFlashWhenBootloaderFoundFirmwareType = PX4StableFirmware;
+ }
+ break;
}
+
+ qCDebug(FirmwareUpgradeLog) << _foundBoardType;
+ emit boardFound();
}
-/// @brief Begins the findBootloader process to connect to the bootloader
-void FirmwareUpgradeController::_findBootloader(void)
+
+void FirmwareUpgradeController::_noBoardFound(void)
{
- _appendStatusLog(tr("Attemping to communicate with bootloader..."));
- _searchingForBoard = false;
- _threadController->findBootloader(_portName, _findBootloaderTimeoutMsec);
+ emit noBoardFound();
+}
+
+void FirmwareUpgradeController::_boardGone(void)
+{
+ emit boardGone();
}
/// @brief Called when the bootloader is connected to by the findBootloader process. Moves the state machine
/// to the next step.
void FirmwareUpgradeController::_foundBootloader(int bootloaderVersion, int boardID, int flashSize)
{
+ _bootloaderFound = true;
_bootloaderVersion = bootloaderVersion;
- _boardID = boardID;
- _boardFlashSize = flashSize;
+ _bootloaderBoardID = boardID;
+ _bootloaderBoardFlashSize = flashSize;
- _appendStatusLog(tr("Connected to bootloader:"));
- _appendStatusLog(tr(" Version: %1").arg(_bootloaderVersion));
- _appendStatusLog(tr(" Board ID: %1").arg(_boardID));
- _appendStatusLog(tr(" Flash size: %1").arg(_boardFlashSize));
+ _appendStatusLog("Connected to bootloader:");
+ _appendStatusLog(QString(" Version: %1").arg(_bootloaderVersion));
+ _appendStatusLog(QString(" Board ID: %1").arg(_bootloaderBoardID));
+ _appendStatusLog(QString(" Flash size: %1").arg(_bootloaderBoardFlashSize));
- _getFirmwareFile();
+ if (_startFlashWhenBootloaderFound) {
+ flash(_startFlashWhenBootloaderFoundFirmwareType);
+ }
}
/// @brief Called when the findBootloader process is unable to sync to the bootloader. Moves the state
/// machine to the appropriate error state.
void FirmwareUpgradeController::_bootloaderSyncFailed(void)
{
- _appendStatusLog(tr("Unable to sync with bootloader."));
- _cancel();
-}
-
-/// @brief Called when the findBoard or findBootloader process times out. Moves the state machine to the
-/// appropriate error state.
-void FirmwareUpgradeController::_findTimeout(void)
-{
- QString msg;
-
- if (_searchingForBoard) {
- msg = tr("Unable to detect your board. If the board is currently connected via USB. Disconnect it and try Upgrade again.");
- } else {
- msg = tr("Unable to communicate with Bootloader. If the board is currently connected via USB. Disconnect it and try Upgrade again.");
- }
- _cancel();
- emit showMessage("Error", msg);
+ _errorCancel("Unable to sync with bootloader.");
}
/// @brief Prompts the user to select a firmware file if needed and moves the state machine to the next state.
-void FirmwareUpgradeController::_getFirmwareFile(void)
+void FirmwareUpgradeController::_getFirmwareFile(FirmwareType_t firmwareType)
{
- static const char* rgPX4FMUV1Firmware[3] =
- {
- "http://px4-travis.s3.amazonaws.com/Firmware/stable/px4fmu-v1_default.px4",
- "http://px4-travis.s3.amazonaws.com/Firmware/beta/px4fmu-v1_default.px4",
- "http://px4-travis.s3.amazonaws.com/Firmware/master/px4fmu-v1_default.px4"
+ static DownloadLocationByFirmwareType_t rgPX4FMUV2Firmware[] = {
+ { PX4StableFirmware, "http://px4-travis.s3.amazonaws.com/Firmware/stable/px4fmu-v2_default.px4" },
+ { PX4BetaFirmware, "http://px4-travis.s3.amazonaws.com/Firmware/beta/px4fmu-v2_default.px4" },
+ { PX4DeveloperFirmware, "http://px4-travis.s3.amazonaws.com/Firmware/master/px4fmu-v2_default.px4"},
+ { ApmArduCopterQuadFirmware, "http://firmware.diydrones.com/Copter/stable/PX4-quad/ArduCopter-v2.px4" },
+ { ApmArduCopterX8Firmware, "http://firmware.diydrones.com/Copter/stable/PX4-octa-quad/ArduCopter-v2.px4" },
+ { ApmArduCopterHexaFirmware, "http://firmware.diydrones.com/Copter/stable/PX4-hexa/ArduCopter-v2.px4" },
+ { ApmArduCopterOctoFirmware, "http://firmware.diydrones.com/Copter/stable/PX4-octa/ArduCopter-v2.px4" },
+ { ApmArduCopterYFirmware, "http://firmware.diydrones.com/Copter/stable/PX4-tri/ArduCopter-v2.px4" },
+ { ApmArduCopterY6Firmware, "http://firmware.diydrones.com/Copter/stable/PX4-y6/ArduCopter-v2.px4" },
+ { ApmArduCopterHeliFirmware, "http://firmware.diydrones.com/Copter/stable/PX4-heli/ArduCopter-v2.px4" },
+ { ApmArduPlaneFirmware, "http://firmware.diydrones.com/Plane/stable/PX4/ArduPlane-v2.px4" },
+ { ApmRoverFirmware, "http://firmware.diydrones.com/Plane/stable/PX4/APMrover2-v2.px4" },
};
+ static const size_t crgPX4FMUV2Firmware = sizeof(rgPX4FMUV2Firmware) / sizeof(rgPX4FMUV2Firmware[0]);
- static const char* rgPX4FMUV2Firmware[3] =
- {
- "http://px4-travis.s3.amazonaws.com/Firmware/stable/px4fmu-v2_default.px4",
- "http://px4-travis.s3.amazonaws.com/Firmware/beta/px4fmu-v2_default.px4",
- "http://px4-travis.s3.amazonaws.com/Firmware/master/px4fmu-v2_default.px4"
+ static const DownloadLocationByFirmwareType_t rgAeroCoreFirmware[] = {
+ { PX4StableFirmware, "http://s3-us-west-2.amazonaws.com/gumstix-aerocore/PX4/stable/aerocore_default.px4" },
+ { PX4BetaFirmware, "http://s3-us-west-2.amazonaws.com/gumstix-aerocore/PX4/beta/aerocore_default.px4" },
+ { PX4DeveloperFirmware, "http://s3-us-west-2.amazonaws.com/gumstix-aerocore/PX4/master/aerocore_default.px4" },
};
-
- static const char* rgAeroCoreFirmware[3] =
- {
- "http://gumstix-aerocore.s3.amazonaws.com/PX4/stable/aerocore_default.px4",
- "http://gumstix-aerocore.s3.amazonaws.com/PX4/beta/aerocore_default.px4",
- "http://gumstix-aerocore.s3.amazonaws.com/PX4/master/aerocore_default.px4"
+ static const size_t crgAeroCoreFirmware = sizeof(rgAeroCoreFirmware) / sizeof(rgAeroCoreFirmware[0]);
+
+ static const DownloadLocationByFirmwareType_t rgPX4FMUV1Firmware[] = {
+ { PX4StableFirmware, "http://px4-travis.s3.amazonaws.com/Firmware/stable/px4fmu-v1_default.px4" },
+ { PX4BetaFirmware, "http://px4-travis.s3.amazonaws.com/Firmware/beta/px4fmu-v1_default.px4" },
+ { PX4DeveloperFirmware, "http://px4-travis.s3.amazonaws.com/Firmware/master/px4fmu-v1_default.px4" },
};
-
- static const char* rgPX4FlowFirmware[3] =
- {
- "http://px4-travis.s3.amazonaws.com/Flow/master/px4flow.px4",
- "http://px4-travis.s3.amazonaws.com/Flow/master/px4flow.px4",
- "http://px4-travis.s3.amazonaws.com/Flow/master/px4flow.px4"
+ static const size_t crgPX4FMUV1Firmware = sizeof(rgPX4FMUV1Firmware) / sizeof(rgPX4FMUV1Firmware[0]);
+
+ static const DownloadLocationByFirmwareType_t rgPX4FlowFirmware[] = {
+ { PX4StableFirmware, "http://px4-travis.s3.amazonaws.com/Flow/master/px4flow.px4" },
};
+ static const size_t crgPX4FlowFirmware = sizeof(rgPX4FlowFirmware) / sizeof(rgPX4FlowFirmware[0]);
- Q_ASSERT(sizeof(rgPX4FMUV1Firmware) == sizeof(rgPX4FMUV2Firmware) && sizeof(rgPX4FMUV1Firmware) == sizeof(rgPX4FlowFirmware));
+ static const DownloadLocationByFirmwareType_t rg3DRRadioFirmware[] = {
+ { PX4StableFirmware, "http://firmware.diydrones.com/SiK/stable/radio~hm_trp.ihx" },
+ };
+ static const size_t crg3DRRadioFirmware = sizeof(rg3DRRadioFirmware) / sizeof(rg3DRRadioFirmware[0]);
+
+ // Select the firmware set based on board type
- const char** prgFirmware;
- switch (_boardID) {
- case _boardIDPX4FMUV1:
+ const DownloadLocationByFirmwareType_t* prgFirmware;
+ size_t crgFirmware;
+
+ switch (_bootloaderBoardID) {
+ case Bootloader::boardIDPX4FMUV1:
prgFirmware = rgPX4FMUV1Firmware;
+ crgFirmware = crgPX4FMUV1Firmware;
break;
- case _boardIDPX4Flow:
+ case Bootloader::boardIDPX4Flow:
prgFirmware = rgPX4FlowFirmware;
+ crgFirmware = crgPX4FlowFirmware;
break;
- case _boardIDPX4FMUV2:
+ case Bootloader::boardIDPX4FMUV2:
prgFirmware = rgPX4FMUV2Firmware;
+ crgFirmware = crgPX4FMUV2Firmware;
break;
-
- case _boardIDAeroCore:
+
+ case Bootloader::boardIDAeroCore:
prgFirmware = rgAeroCoreFirmware;
+ crgFirmware = crgAeroCoreFirmware;
break;
-
+
+ case Bootloader::boardID3DRRadio:
+ prgFirmware = rg3DRRadioFirmware;
+ crgFirmware = crg3DRRadioFirmware;
+ break;
+
default:
prgFirmware = NULL;
break;
}
-
- if (prgFirmware == NULL && _firmwareType != CustomFirmware) {
- QGCMessageBox::critical(tr("Firmware Upgrade"), tr("Attemping to flash an unknown board type, you must select 'Custom firmware file'"));
- _cancel();
- return;
+
+ if (prgFirmware == NULL && firmwareType != PX4CustomFirmware) {
+ _errorCancel("Attempting to flash an unknown board type, you must select 'Custom firmware file'");
+ return;
}
- if (_firmwareType == CustomFirmware) {
+ if (firmwareType == PX4CustomFirmware) {
_firmwareFilename = QGCFileDialog::getOpenFileName(NULL, // Parent to main window
- tr("Select Firmware File"), // Dialog Caption
+ "Select Firmware File", // Dialog Caption
QStandardPaths::writableLocation(QStandardPaths::DocumentsLocation), // Initial directory
- tr("Firmware Files (*.px4 *.bin)")); // File filter
+ "Firmware Files (*.px4 *.bin *.ihx)"); // File filter
} else {
- _firmwareFilename = prgFirmware[_firmwareType];
+ bool found = false;
+
+ for (size_t i=0; ifirmwareType == firmwareType) {
+ found = true;
+ break;
+ }
+ prgFirmware++;
+ }
+
+ if (found) {
+ _firmwareFilename = prgFirmware->downloadLocation;
+ } else {
+ _errorCancel("Unable to find specified firmware download location");
+ return;
+ }
}
if (_firmwareFilename.isEmpty()) {
- _cancel();
+ _errorCancel("No firmware file selected");
} else {
_downloadFirmware();
}
@@ -234,8 +267,8 @@ void FirmwareUpgradeController::_downloadFirmware(void)
{
Q_ASSERT(!_firmwareFilename.isEmpty());
- _appendStatusLog(tr("Downloading firmware..."));
- _appendStatusLog(tr(" From: %1").arg(_firmwareFilename));
+ _appendStatusLog("Downloading firmware...");
+ _appendStatusLog(QString(" From: %1").arg(_firmwareFilename));
// Split out filename from path
QString firmwareFilename = QFileInfo(_firmwareFilename).fileName();
@@ -246,13 +279,12 @@ void FirmwareUpgradeController::_downloadFirmware(void)
if (downloadFile.isEmpty()) {
downloadFile = QStandardPaths::writableLocation(QStandardPaths::DownloadLocation);
if (downloadFile.isEmpty()) {
- _appendStatusLog(tr("Unabled to find writable download location. Tried downloads and temp directory."));
- _cancel();
+ _errorCancel("Unabled to find writable download location. Tried downloads and temp directory.");
return;
}
}
Q_ASSERT(!downloadFile.isEmpty());
- downloadFile += "/" + firmwareFilename;
+ downloadFile += "/" + firmwareFilename;
QUrl firmwareUrl;
if (_firmwareFilename.startsWith("http:")) {
@@ -290,7 +322,7 @@ void FirmwareUpgradeController::_downloadProgress(qint64 curr, qint64 total)
/// @brief Called when the firmware download completes.
void FirmwareUpgradeController::_downloadFinished(void)
{
- _appendStatusLog(tr("Download complete"));
+ _appendStatusLog("Download complete");
QNetworkReply* reply = qobject_cast(QObject::sender());
Q_ASSERT(reply);
@@ -313,286 +345,72 @@ void FirmwareUpgradeController::_downloadFinished(void)
// Store downloaded file in download location
QFile file(downloadFilename);
if (!file.open(QIODevice::WriteOnly)) {
- _appendStatusLog(tr("Could not save downloaded file to %1. Error: %2").arg(downloadFilename).arg(file.errorString()));
- _cancel();
+ _errorCancel(QString("Could not save downloaded file to %1. Error: %2").arg(downloadFilename).arg(file.errorString()));
return;
}
file.write(reply->readAll());
file.close();
+ FirmwareImage* image = new FirmwareImage(this);
+ connect(image, &FirmwareImage::statusMessage, this, &FirmwareUpgradeController::_status);
+ connect(image, &FirmwareImage::errorMessage, this, &FirmwareUpgradeController::_error);
- 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)) {
- _appendStatusLog(tr("Unable to open firmware file %1, error: %2").arg(downloadFilename).arg(px4File.errorString()));
- return;
- }
-
- QByteArray bytes = px4File.readAll();
- px4File.close();
- QJsonDocument doc = QJsonDocument::fromJson(bytes);
-
- if (doc.isNull()) {
- _appendStatusLog(tr("Supplied file is not a valid JSON document"));
- _cancel();
- 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(static_cast(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)) {
- _appendStatusLog(tr("Unable to open decompressed file %1 for writing, error: %2").arg(decompressFilename).arg(decompressFile.errorString()));
- _cancel();
- return;
- }
-
- qint64 bytesWritten = decompressFile.write(decompressedBytes);
- if (bytesWritten != decompressedBytes.count()) {
- _appendStatusLog(tr("Write failed for decompressed image file, error: %1").arg(decompressFile.errorString()));
- _cancel();
- 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;
- } else if (downloadFilename.toLower().contains("aerocore")) {
- firmwareBoardID = _boardIDAeroCore;
- }
-
- if (firmwareBoardID != 0 && firmwareBoardID != _boardID) {
- _appendStatusLog(tr("Downloaded firmware board id does not match hardware board id: %1 != %2").arg(firmwareBoardID).arg(_boardID));
- _cancel();
- return;
- }
-
- _firmwareFilename = downloadFilename;
-
- QFile binFile(_firmwareFilename);
- if (!binFile.open(QIODevice::ReadOnly)) {
- _appendStatusLog(tr("Unabled to open firmware file %1, %2").arg(_firmwareFilename).arg(binFile.errorString()));
- _cancel();
- return;
- }
- _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 (!image->load(downloadFilename, _bootloaderBoardID)) {
+ _errorCancel("Image load failed");
+ return;
}
- if (_imageSize > _boardFlashSize) {
- _appendStatusLog(tr("Image size of %1 is too large for board flash size %2").arg(_imageSize).arg(_boardFlashSize));
- _cancel();
+ // We can't proceed unless we have the bootloader
+ if (!_bootloaderFound) {
+ _errorCancel(QString("Bootloader not found").arg(_imageSize).arg(_bootloaderBoardFlashSize));
return;
}
-
- _erase();
-}
-
-/// Decompress a set of bytes stored in a Json document.
-bool FirmwareUpgradeController::_decompressJsonValue(const QJsonObject& jsonObject, ///< JSON object
- const QByteArray& jsonDocBytes, ///< Raw bytes of JSON document
- const QString& sizeKey, ///< key which holds byte size
- const QString& bytesKey, ///< key which holds compress bytes
- QByteArray& decompressedBytes) ///< Returned decompressed bytes
-{
- // Validate decompressed size key
- if (!jsonObject.contains(sizeKey)) {
- _appendStatusLog(QString("Firmware file missing %1 key").arg(sizeKey));
- return false;
- }
- int decompressedSize = jsonObject.value(QString(sizeKey)).toInt();
- if (decompressedSize == 0) {
- _appendStatusLog(QString("Firmware file has invalid decompressed size for %1").arg(sizeKey));
- return false;
- }
- // 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 parts = QString(jsonDocBytes).split(QString("\"%1\": \"").arg(bytesKey));
- if (parts.count() == 1) {
- _appendStatusLog(QString("Could not find compressed bytes for %1 in Firmware file").arg(bytesKey));
- return false;
- }
- parts = parts.last().split("\"");
- if (parts.count() == 1) {
- _appendStatusLog(QString("Incorrectly formed compressed bytes section for %1 in Firmware file").arg(bytesKey));
- return false;
- }
-
- // Store decompressed size as first four bytes. This is required by qUncompress routine.
- QByteArray raw;
- raw.append((unsigned char)((decompressedSize >> 24) & 0xFF));
- raw.append((unsigned char)((decompressedSize >> 16) & 0xFF));
- raw.append((unsigned char)((decompressedSize >> 8) & 0xFF));
- raw.append((unsigned char)((decompressedSize >> 0) & 0xFF));
-
- QByteArray raw64 = parts.first().toUtf8();
- raw.append(QByteArray::fromBase64(raw64));
- decompressedBytes = qUncompress(raw);
-
- if (decompressedBytes.count() == 0) {
- _appendStatusLog(QString("Firmware file has 0 length %1").arg(bytesKey));
- return false;
- }
- if (decompressedBytes.count() != decompressedSize) {
- _appendStatusLog(QString("Size for decompressed %1 does not match stored size: Expected(%1) Actual(%2)").arg(decompressedSize).arg(decompressedBytes.count()));
- return false;
+ if (_bootloaderBoardFlashSize != 0 && _imageSize > _bootloaderBoardFlashSize) {
+ _errorCancel(QString("Image size of %1 is too large for board flash size %2").arg(_imageSize).arg(_bootloaderBoardFlashSize));
+ return;
}
-
- _appendStatusLog(QString("Succesfully decompressed %1").arg(bytesKey));
- return true;
+
+ _threadController->flash(image);
}
/// @brief Called when an error occurs during download
void FirmwareUpgradeController::_downloadError(QNetworkReply::NetworkError code)
{
+ QString errorMsg;
+
if (code == QNetworkReply::OperationCanceledError) {
- _appendStatusLog(tr("Download cancelled"));
+ errorMsg = "Download cancelled";
} else {
- _appendStatusLog(tr("Error during download. Error: %1").arg(code));
+ errorMsg = QString("Error during download. Error: %1").arg(code);
}
- _cancel();
+ _errorCancel(errorMsg);
}
-/// @brief Erase the board
-void FirmwareUpgradeController::_erase(void)
+/// @brief Signals completion of one of the specified bootloader commands. Moves the state machine to the
+/// appropriate next step.
+void FirmwareUpgradeController::_flashComplete(void)
{
- _appendStatusLog(tr("Erasing previous firmware..."));
-
- // We set up our own progress bar for erase since the erase command does not provide one
- _eraseTickCount = 0;
- _eraseTimer.start(_eraseTickMsec);
+ delete _image;
+ _image = NULL;
- // Erase command
- _threadController->erase();
+ _appendStatusLog("Upgrade complete", true);
+ _appendStatusLog("------------------------------------------", false);
+ emit flashComplete();
}
-/// @brief Signals completion of one of the specified bootloader commands. Moves the state machine to the
-/// appropriate next step.
-void FirmwareUpgradeController::_complete(const int command)
+void FirmwareUpgradeController::_error(const QString& errorString)
{
- if (command == PX4FirmwareUpgradeThreadWorker::commandProgram) {
- _appendStatusLog(tr("Verifying board programming..."));
- _threadController->verify(_firmwareFilename);
- } else if (command == PX4FirmwareUpgradeThreadWorker::commandVerify) {
- _appendStatusLog(tr("Upgrade complete"));
- QGCMessageBox::information(tr("Firmware Upgrade"), tr("Upgrade completed succesfully"));
- _cancel();
- } else if (command == PX4FirmwareUpgradeThreadWorker::commandErase) {
- _eraseTimer.stop();
- _appendStatusLog(tr("Flashing new firmware to board..."));
- _threadController->program(_firmwareFilename);
- } else if (command == PX4FirmwareUpgradeThreadWorker::commandCancel) {
- // FIXME: This is no longer needed, no Cancel
- if (_searchingForBoard) {
- _appendStatusLog(tr("Board not found"));
- _cancel();
- } else {
- _appendStatusLog(tr("Bootloader not found"));
- _cancel();
- }
- } else {
- Q_ASSERT(false);
- }
+ delete _image;
+ _image = NULL;
+
+ _errorCancel(QString("Error: %1").arg(errorString));
}
-/// @brief Signals that an error has occured with the specified bootloader commands. Moves the state machine
-/// to the appropriate error state.
-void FirmwareUpgradeController::_error(const int command, const QString errorString)
+void FirmwareUpgradeController::_status(const QString& statusString)
{
- Q_UNUSED(command);
-
- _appendStatusLog(tr("Error: %1").arg(errorString));
- _cancel();
+ _appendStatusLog(statusString);
}
/// @brief Updates the progress bar from long running bootloader commands
@@ -604,13 +422,6 @@ void FirmwareUpgradeController::_updateProgress(int curr, int total)
}
}
-/// @brief Resets the state machine back to the beginning
-void FirmwareUpgradeController::_restart(void)
-{
- // FIXME: NYI
- //_setupState(upgradeStateBegin);
-}
-
/// @brief Moves the progress bar ahead on tick while erasing the board
void FirmwareUpgradeController::_eraseProgressTick(void)
{
@@ -618,33 +429,54 @@ void FirmwareUpgradeController::_eraseProgressTick(void)
_progressBar->setProperty("value", (float)(_eraseTickCount*_eraseTickMsec) / (float)_eraseTotalMsec);
}
-void FirmwareUpgradeController::doFirmwareUpgrade(void)
-{
- Q_ASSERT(_upgradeButton);
- _upgradeButton->setEnabled(false);
-
- _findBoard();
-}
-
/// Appends the specified text to the status log area in the ui
-void FirmwareUpgradeController::_appendStatusLog(const QString& text)
+void FirmwareUpgradeController::_appendStatusLog(const QString& text, bool critical)
{
Q_ASSERT(_statusLog);
QVariant returnedValue;
- QVariant varText = text;
+ QVariant varText;
+
+ if (critical) {
+ varText = QString("%1").arg(text);
+ } else {
+ varText = text;
+ }
+
QMetaObject::invokeMethod(_statusLog,
"append",
Q_RETURN_ARG(QVariant, returnedValue),
Q_ARG(QVariant, varText));
}
-bool FirmwareUpgradeController::activeQGCConnections(void)
+bool FirmwareUpgradeController::qgcConnections(void)
{
return LinkManager::instance()->anyConnectedLinks();
}
-bool FirmwareUpgradeController::pluggedInBoard(void)
+void FirmwareUpgradeController::_linkDisconnected(LinkInterface* link)
+{
+ Q_UNUSED(link);
+ emit qgcConnectionsChanged(qgcConnections());
+}
+
+void FirmwareUpgradeController::_errorCancel(const QString& msg)
+{
+ _appendStatusLog(msg, false);
+ _appendStatusLog("Upgrade cancelled", true);
+ _appendStatusLog("------------------------------------------", false);
+ emit error();
+ cancel();
+}
+
+void FirmwareUpgradeController::_eraseStarted(void)
+{
+ // We set up our own progress bar for erase since the erase command does not provide one
+ _eraseTickCount = 0;
+ _eraseTimer.start(_eraseTickMsec);
+}
+
+void FirmwareUpgradeController::_eraseComplete(void)
{
- return _threadController->pluggedInBoard();
+ _eraseTimer.stop();
}
diff --git a/src/VehicleSetup/FirmwareUpgradeController.h b/src/VehicleSetup/FirmwareUpgradeController.h
index 039aa2e2789ef78aab0f366f73fd9153d2a7f517..6065ddafb8f35aed096ba53a810b7fc4695419f8 100644
--- a/src/VehicleSetup/FirmwareUpgradeController.h
+++ b/src/VehicleSetup/FirmwareUpgradeController.h
@@ -28,6 +28,8 @@
#define FirmwareUpgradeController_H
#include "PX4FirmwareUpgradeThread.h"
+#include "LinkManager.h"
+#include "FirmwareImage.h"
#include
#include
@@ -51,37 +53,46 @@ public:
/// Supported firmware types. If you modify these you will need to update the qml file as well.
typedef enum {
- StableFirmware,
- BetaFirmware,
- DeveloperFirmware,
- CustomFirmware
+ PX4StableFirmware,
+ PX4BetaFirmware,
+ PX4DeveloperFirmware,
+ PX4CustomFirmware,
+ ApmArduCopterQuadFirmware,
+ ApmArduCopterX8Firmware,
+ ApmArduCopterHexaFirmware,
+ ApmArduCopterOctoFirmware,
+ ApmArduCopterYFirmware,
+ ApmArduCopterY6Firmware,
+ ApmArduCopterHeliFirmware,
+ ApmArduPlaneFirmware,
+ ApmRoverFirmware,
} FirmwareType_t;
Q_ENUMS(FirmwareType_t)
- /// Firmare type to load
- Q_PROPERTY(FirmwareType_t firmwareType READ firmwareType WRITE setFirmwareType)
+ Q_PROPERTY(QString boardPort READ boardPort NOTIFY boardFound)
+ Q_PROPERTY(QString boardDescription READ boardDescription NOTIFY boardFound)
+ Q_PROPERTY(QString boardType MEMBER _foundBoardType NOTIFY boardFound)
- /// Upgrade push button in UI
- Q_PROPERTY(QQuickItem* upgradeButton READ upgradeButton WRITE setUpgradeButton)
-
/// TextArea for log output
Q_PROPERTY(QQuickItem* statusLog READ statusLog WRITE setStatusLog)
/// Progress bar for you know what
Q_PROPERTY(QQuickItem* progressBar READ progressBar WRITE setProgressBar)
+
+ /// Returns true if there are active QGC connections
+ Q_PROPERTY(bool qgcConnections READ qgcConnections NOTIFY qgcConnectionsChanged)
- Q_INVOKABLE bool activeQGCConnections(void);
- Q_INVOKABLE bool pluggedInBoard(void);
+ /// Starts searching for boards on the background thread
+ Q_INVOKABLE void startBoardSearch(void);
- /// Begins the firware upgrade process
- Q_INVOKABLE void doFirmwareUpgrade(void);
-
- FirmwareType_t firmwareType(void) { return _firmwareType; }
- void setFirmwareType(FirmwareType_t firmwareType) { _firmwareType = firmwareType; }
+ /// Cancels whatever state the upgrade worker thread is in
+ Q_INVOKABLE void cancel(void);
- QQuickItem* upgradeButton(void) { return _upgradeButton; }
- void setUpgradeButton(QQuickItem* upgradeButton) { _upgradeButton = upgradeButton; }
+ /// Called when the firmware type has been selected by the user to continue the flash process.
+ Q_INVOKABLE void flash(FirmwareType_t firmwareType);
+
+ // Property accessors
QQuickItem* progressBar(void) { return _progressBar; }
void setProgressBar(QQuickItem* progressBar) { _progressBar = progressBar; }
@@ -89,48 +100,61 @@ public:
QQuickItem* statusLog(void) { return _statusLog; }
void setStatusLog(QQuickItem* statusLog) { _statusLog = statusLog; }
+ bool qgcConnections(void);
+
+ QString boardPort(void) { return _foundBoardInfo.portName(); }
+ QString boardDescription(void) { return _foundBoardInfo.description(); }
+
signals:
- void showMessage(const QString& title, const QString& message);
+ void boardFound(void);
+ void noBoardFound(void);
+ void boardGone(void);
+ void flashComplete(void);
+ void flashCancelled(void);
+ void qgcConnectionsChanged(bool connections);
+ void error(void);
private slots:
void _downloadProgress(qint64 curr, qint64 total);
void _downloadFinished(void);
void _downloadError(QNetworkReply::NetworkError code);
- void _foundBoard(bool firstTry, const QString portname, QString portDescription);
+ void _foundBoard(bool firstAttempt, const QSerialPortInfo& portInfo, int type);
+ void _noBoardFound(void);
+ void _boardGone();
void _foundBootloader(int bootloaderVersion, int boardID, int flashSize);
- void _error(const int command, const QString errorString);
+ void _error(const QString& errorString);
+ void _status(const QString& statusString);
void _bootloaderSyncFailed(void);
- void _findTimeout(void);
- void _complete(const int command);
+ void _flashComplete(void);
void _updateProgress(int curr, int total);
- void _restart(void);
+ void _eraseStarted(void);
+ void _eraseComplete(void);
void _eraseProgressTick(void);
+ void _linkDisconnected(LinkInterface* link);
private:
- void _findBoard(void);
- void _findBootloader(void);
- void _cancel(void);
- void _getFirmwareFile(void);
+ void _getFirmwareFile(FirmwareType_t firmwareType);
void _downloadFirmware(void);
- void _erase(void);
- void _appendStatusLog(const QString& text);
- bool _decompressJsonValue(const QJsonObject& jsonObject,
- const QByteArray& jsonDocBytes,
- const QString& sizeKey,
- const QString& bytesKey,
- QByteArray& decompressedBytes);
+ void _appendStatusLog(const QString& text, bool critical = false);
+ void _errorCancel(const QString& msg);
+
+ typedef struct {
+ FirmwareType_t firmwareType;
+ const char* downloadLocation;
+ } DownloadLocationByFirmwareType_t;
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
- static const int _boardIDAeroCore = 98; ///< Board ID for Gumstix AeroCore board
- uint32_t _boardID; ///< Board ID
- uint32_t _boardFlashSize; ///< Flash size in bytes of board
+ /// Information which comes back from the bootloader
+ bool _bootloaderFound; ///< true: we have received the foundBootloader signals
+ uint32_t _bootloaderVersion; ///< Bootloader version
+ uint32_t _bootloaderBoardID; ///< Board ID
+ uint32_t _bootloaderBoardFlashSize; ///< Flash size in bytes of board
+
+ bool _startFlashWhenBootloaderFound;
+ FirmwareType_t _startFlashWhenBootloaderFoundFirmwareType;
+
uint32_t _imageSize; ///< Image size of firmware being flashed
QPixmap _boardIcon; ///< Icon used to display image of board
@@ -151,12 +175,15 @@ private:
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
- FirmwareType_t _firmwareType; ///< Firmware type to load
- QQuickItem* _upgradeButton; ///< Upgrade button in ui
QQuickItem* _statusLog; ///< Status log TextArea Qml control
QQuickItem* _progressBar;
bool _searchingForBoard; ///< true: searching for board, false: search for bootloader
+
+ QSerialPortInfo _foundBoardInfo;
+ QString _foundBoardType;
+
+ FirmwareImage* _image;
};
#endif
diff --git a/src/VehicleSetup/PX4Bootloader.h b/src/VehicleSetup/PX4Bootloader.h
deleted file mode 100644
index dcf35d5c9fa204f250b729cd379938b696372a4d..0000000000000000000000000000000000000000
--- a/src/VehicleSetup/PX4Bootloader.h
+++ /dev/null
@@ -1,161 +0,0 @@
-/*=====================================================================
-
- QGroundControl Open Source Ground Control Station
-
- (c) 2009, 2014 QGROUNDCONTROL PROJECT
-
- 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 .
-
- ======================================================================*/
-
-/// @file
-/// @brief PX4 Bootloader Utility routines
-/// @author Don Gagne
-
-#ifndef PX4Bootloader_H
-#define PX4Bootloader_H
-
-#include "qextserialport.h"
-
-#include
-
-/// @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; }
-
- /// @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(QextSerialPort* port, const uint8_t* data, qint64 maxSize);
- bool write(QextSerialPort* 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 readTimeout Msecs to wait for bytes to become available on port
- bool read(QextSerialPort* port, uint8_t* data, qint64 maxSize, 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(QextSerialPort* port, 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(QextSerialPort* 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(QextSerialPort* port, uint8_t cmd, int responseTimeout = _responseTimeout);
-
- /// @brief Program the board with the specified firmware
- bool program(QextSerialPort* 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(QextSerialPort* port, const QString firmwareFilename);
-
- /// @brief Read a PROTO_SYNC response from the bootloader
- /// @return true: Valid sync response was received
- bool sync(QextSerialPort* 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(QextSerialPort* port, uint32_t& bootloaderVersion, uint32_t& boardID, uint32_t& flashSize);
-
- /// @brief Opens a port to the bootloader
- bool open(QextSerialPort* port, const QString portName);
-
- /// @brief Sends a PROTO_REBOOT command to the bootloader
- bool sendBootloaderReboot(QextSerialPort* port);
-
- /// @brief Sends a PROTO_ERASE command to the bootlader
- bool erase(QextSerialPort* 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 = 32 ///< read size for PROTO_READ_MULTI, must be multiple of 4
- };
-
- bool _findBootloader(void);
- bool _downloadFirmware(void);
- bool _bootloaderVerifyRev2(QextSerialPort* port, const QString firmwareFilename);
- bool _bootloaderVerifyRev3(QextSerialPort* port);
-
- 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 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/VehicleSetup/PX4FirmwareUpgradeThread.cc b/src/VehicleSetup/PX4FirmwareUpgradeThread.cc
index 642c115dbe55d1b21355f93079247b85dd50c8d6..a8c0d7d4797bfe22aa8777db32cc1d9e18590510 100644
--- a/src/VehicleSetup/PX4FirmwareUpgradeThread.cc
+++ b/src/VehicleSetup/PX4FirmwareUpgradeThread.cc
@@ -26,20 +26,30 @@
/// @author Don Gagne
#include "PX4FirmwareUpgradeThread.h"
-#include "PX4Bootloader.h"
+#include "Bootloader.h"
+#include "QGCLoggingCategory.h"
+#include "QGC.h"
#include
#include
#include
+#include
-PX4FirmwareUpgradeThreadWorker::PX4FirmwareUpgradeThreadWorker(QObject* parent) :
- QObject(parent),
+PX4FirmwareUpgradeThreadWorker::PX4FirmwareUpgradeThreadWorker(PX4FirmwareUpgradeThreadController* controller) :
+ _controller(controller),
_bootloader(NULL),
_bootloaderPort(NULL),
- _timerTimeout(NULL),
- _timerRetry(NULL)
+ _timerRetry(NULL),
+ _foundBoard(false),
+ _findBoardFirstAttempt(true)
{
+ Q_ASSERT(_controller);
+ connect(_controller, &PX4FirmwareUpgradeThreadController::_initThreadWorker, this, &PX4FirmwareUpgradeThreadWorker::_init);
+ connect(_controller, &PX4FirmwareUpgradeThreadController::_startFindBoardLoopOnThread, this, &PX4FirmwareUpgradeThreadWorker::_startFindBoardLoop);
+ connect(_controller, &PX4FirmwareUpgradeThreadController::_flashOnThread, this, &PX4FirmwareUpgradeThreadWorker::_flash);
+ connect(_controller, &PX4FirmwareUpgradeThreadController::_rebootOnThread, this, &PX4FirmwareUpgradeThreadWorker::_reboot);
+ connect(_controller, &PX4FirmwareUpgradeThreadController::_cancel, this, &PX4FirmwareUpgradeThreadWorker::_cancel);
}
PX4FirmwareUpgradeThreadWorker::~PX4FirmwareUpgradeThreadWorker()
@@ -52,77 +62,112 @@ PX4FirmwareUpgradeThreadWorker::~PX4FirmwareUpgradeThreadWorker()
/// @brief Initializes the PX4FirmwareUpgradeThreadWorker with the various child objects which must be created
/// on the worker thread.
-void PX4FirmwareUpgradeThreadWorker::init(void)
+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);
+ connect(_timerRetry, &QTimer::timeout, this, &PX4FirmwareUpgradeThreadWorker::_findBoardOnce);
Q_ASSERT(_bootloader == NULL);
- _bootloader = new PX4Bootloader(this);
- connect(_bootloader, &PX4Bootloader::updateProgramProgress, this, &PX4FirmwareUpgradeThreadWorker::_updateProgramProgress);
+ _bootloader = new Bootloader(this);
+ connect(_bootloader, &Bootloader::updateProgress, this, &PX4FirmwareUpgradeThreadWorker::_updateProgress);
}
-void PX4FirmwareUpgradeThreadWorker::findBoard(int msecTimeout)
+void PX4FirmwareUpgradeThreadWorker::_cancel(void)
{
+ if (_bootloaderPort) {
+ _bootloaderPort->close();
+ _bootloaderPort->deleteLater();
+ _bootloaderPort = NULL;
+ }
+}
+
+void PX4FirmwareUpgradeThreadWorker::_startFindBoardLoop(void)
+{
+ _foundBoard = false;
_findBoardFirstAttempt = true;
- connect(_timerRetry, &QTimer::timeout, this, &PX4FirmwareUpgradeThreadWorker::_findBoardOnce);
- _timerTimeout->start(msecTimeout);
- _elapsed.start();
_findBoardOnce();
}
void PX4FirmwareUpgradeThreadWorker::_findBoardOnce(void)
{
- qDebug() << "_findBoardOnce";
+ qCDebug(FirmwareUpgradeLog) << "_findBoardOnce";
- QString portName;
- QString portDescription;
+ QSerialPortInfo portInfo;
+ PX4FirmwareUpgradeFoundBoardType_t boardType;
- 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.systemLocation();
- portDescription = info.description();
-
- _closeFind();
- emit foundBoard(_findBoardFirstAttempt, portName, portDescription);
- return;
+ if (_findBoardFromPorts(portInfo, boardType)) {
+ if (!_foundBoard) {
+ _foundBoard = true;
+ _foundBoardPortInfo = portInfo;
+ emit foundBoard(_findBoardFirstAttempt, portInfo, boardType);
+ if (!_findBoardFirstAttempt) {
+ if (boardType == FoundBoard3drRadio) {
+ _3drRadioForceBootloader(portInfo);
+ return;
+ } else {
+ _findBootloader(portInfo, false /* radio mode */, true /* errorOnNotFound */);
+ return;
+ }
+ }
+ }
+ } else {
+ if (_foundBoard) {
+ _foundBoard = false;
+ qCDebug(FirmwareUpgradeLog) << "Board gone";
+ emit boardGone();
+ } else if (_findBoardFirstAttempt) {
+ emit noBoardFound();
}
}
_findBoardFirstAttempt = false;
-
- emit updateProgress(_elapsed.elapsed(), _timerTimeout->interval());
_timerRetry->start();
}
-bool PX4FirmwareUpgradeThreadController::pluggedInBoard(void)
+bool PX4FirmwareUpgradeThreadWorker::_findBoardFromPorts(QSerialPortInfo& portInfo, PX4FirmwareUpgradeFoundBoardType_t& type)
{
- qDebug() << "pluggedInBoard";
-
- QString portName;
- QString portDescription;
+ bool found = false;
foreach (QSerialPortInfo info, QSerialPortInfo::availablePorts()) {
- if (!info.portName().isEmpty() && (info.description().contains("PX4") || info.vendorIdentifier() == 9900 /* 3DR */)) {
+#if 0
+ qCDebug(FirmwareUpgradeLog) << "Serial Port --------------";
+ qCDebug(FirmwareUpgradeLog) << "\tport name:" << info.portName();
+ qCDebug(FirmwareUpgradeLog) << "\tdescription:" << info.description();
+ qCDebug(FirmwareUpgradeLog) << "\tsystem location:" << info.systemLocation();
+ qCDebug(FirmwareUpgradeLog) << "\tvendor ID:" << info.vendorIdentifier();
+ qCDebug(FirmwareUpgradeLog) << "\tproduct ID:" << info.productIdentifier();
+#endif
+
+ if (!info.portName().isEmpty()) {
+ if (info.vendorIdentifier() == _px4VendorId) {
+ if (info.productIdentifier() == _pixhawkFMUV2ProductId) {
+ qCDebug(FirmwareUpgradeLog) << "Found PX4 FMU V2";
+ type = FoundBoardPX4FMUV2;
+ found = true;
+ } else if (info.productIdentifier() == _pixhawkFMUV1ProductId) {
+ qCDebug(FirmwareUpgradeLog) << "Found PX4 FMU V1";
+ type = FoundBoardPX4FMUV2;
+ found = true;
+ } else if (info.productIdentifier() == _flowProductId) {
+ qCDebug(FirmwareUpgradeLog) << "Found PX4 Flow";
+ type = FoundBoardPX4Flow;
+ found = true;
+ }
+ } else if (info.vendorIdentifier() == _3drRadioVendorId && info.productIdentifier() == _3drRadioProductId) {
+ qCDebug(FirmwareUpgradeLog) << "Found 3DR Radio";
+ type = FoundBoard3drRadio;
+ found = true;
+ }
+ }
+
+ if (found) {
+ portInfo = info;
return true;
}
}
@@ -130,144 +175,197 @@ bool PX4FirmwareUpgradeThreadController::pluggedInBoard(void)
return false;
}
-void PX4FirmwareUpgradeThreadWorker::findBootloader(const QString portName, int msecTimeout)
+void PX4FirmwareUpgradeThreadWorker::_3drRadioForceBootloader(const QSerialPortInfo& portInfo)
{
- Q_UNUSED(msecTimeout);
+ // First make sure we can't get the bootloader
+
+ if (_findBootloader(portInfo, true /* radio Mode */, false /* errorOnNotFound */)) {
+ return;
+ }
+
+ // Couldn't find the bootloader. We'll need to reboot the radio into bootloader.
+
+ QSerialPort port(portInfo);
- // Once the port shows up, we only try to connect to the bootloader a single time
- _portName = portName;
- _findBootloaderOnce();
+ port.setBaudRate(QSerialPort::Baud57600);
+
+ emit status("Putting radio into command mode");
+
+ // Wait a little while for the USB port to initialize. 3DR Radio boot is really slow.
+ for (int i=0; i<12; i++) {
+ if (port.open(QIODevice::ReadWrite)) {
+ break;
+ } else {
+ QGC::SLEEP::msleep(250);
+ }
+ }
+
+ if (!port.isOpen()) {
+ emit error(QString("Unable to open port: %1 error: %2").arg(portInfo.systemLocation()).arg(port.errorString()));
+ return;
+ }
+
+ // Put radio into command mode
+ port.write("+++", 3);
+ if (!port.waitForReadyRead(1500)) {
+ emit error("Unable to put radio into command mode");
+ return;
+ }
+ QByteArray bytes = port.readAll();
+ if (!bytes.contains("OK")) {
+ emit error("Unable to put radio into command mode");
+ return;
+ }
+
+ emit status("Rebooting radio to bootloader");
+
+ port.write("AT&UPDATE\r\n");
+ if (!port.waitForBytesWritten(1500)) {
+ emit error("Unable to reboot radio");
+ return;
+ }
+ QGC::SLEEP::msleep(2000);
+ port.close();
+
+ // The bootloader should be waiting for us now
+
+ _findBootloader(portInfo, true /* radio mode */, true /* errorOnNotFound */);
}
-void PX4FirmwareUpgradeThreadWorker::_findBootloaderOnce(void)
+bool PX4FirmwareUpgradeThreadWorker::_findBootloader(const QSerialPortInfo& portInfo, bool radioMode, bool errorOnNotFound)
{
- qDebug() << "_findBootloaderOnce";
+ qCDebug(FirmwareUpgradeLog) << "_findBootloader";
- uint32_t bootloaderVersion, boardID, flashSize;
+ uint32_t bootloaderVersion = 0;
+ uint32_t boardID;
+ uint32_t flashSize = 0;
+
_bootloaderPort = new QextSerialPort(QextSerialPort::Polling);
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;
- }
+ // Wait a little while for the USB port to initialize.
+ for (int i=0; i<10; i++) {
+ if (_bootloader->open(_bootloaderPort, portInfo.systemLocation())) {
+ break;
+ } else {
+ QGC::SLEEP::msleep(100);
+ }
+ }
+
+ QGC::SLEEP::msleep(2000);
+
+ if (_bootloader->sync(_bootloaderPort)) {
+ bool success;
+
+ if (radioMode) {
+ success = _bootloader->get3DRRadioBoardId(_bootloaderPort, boardID);
+ } else {
+ success = _bootloader->getPX4BoardInfo(_bootloaderPort, bootloaderVersion, boardID, flashSize);
+ }
+ if (success) {
+ qCDebug(FirmwareUpgradeLog) << "Found bootloader";
+ emit foundBootloader(bootloaderVersion, boardID, flashSize);
+ return true;
}
}
- _closeFind();
_bootloaderPort->close();
_bootloaderPort->deleteLater();
_bootloaderPort = NULL;
- qDebug() << "Bootloader error:" << _bootloader->errorString();
- emit error(commandBootloader, _bootloader->errorString());
-}
-
-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();
+ qCDebug(FirmwareUpgradeLog) << "Bootloader error:" << _bootloader->errorString();
+ if (errorOnNotFound) {
+ emit error(_bootloader->errorString());
+ }
+
+ return false;
}
-void PX4FirmwareUpgradeThreadWorker::sendBootloaderReboot(void)
+void PX4FirmwareUpgradeThreadWorker::_reboot(void)
{
if (_bootloaderPort) {
if (_bootloaderPort->isOpen()) {
- _bootloader->sendBootloaderReboot(_bootloaderPort);
+ _bootloader->reboot(_bootloaderPort);
}
_bootloaderPort->deleteLater();
_bootloaderPort = NULL;
}
}
-void PX4FirmwareUpgradeThreadWorker::program(const QString firmwareFilename)
-{
- qDebug() << "Program";
- if (!_bootloader->program(_bootloaderPort, firmwareFilename)) {
- _bootloaderPort->deleteLater();
- _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)
+void PX4FirmwareUpgradeThreadWorker::_flash(void)
{
- qDebug() << "Verify";
- if (!_bootloader->verify(_bootloaderPort, firmwareFilename)) {
- qDebug() << "Verify failed:" << _bootloader->errorString();
- emit error(commandVerify, _bootloader->errorString());
- } else {
- qDebug() << "Verify complete";
- emit complete(commandVerify);
+ qCDebug(FirmwareUpgradeLog) << "PX4FirmwareUpgradeThreadWorker::_flash";
+
+ if (_erase()) {
+ emit status("Programming new version...");
+
+ if (_bootloader->program(_bootloaderPort, _controller->image())) {
+ qCDebug(FirmwareUpgradeLog) << "Program complete";
+ emit status("Program complete");
+ } else {
+ _bootloaderPort->deleteLater();
+ _bootloaderPort = NULL;
+ qCDebug(FirmwareUpgradeLog) << "Program failed:" << _bootloader->errorString();
+ emit error(_bootloader->errorString());
+ }
+
+ emit status("Verifying program...");
+
+ if (_bootloader->verify(_bootloaderPort, _controller->image())) {
+ qCDebug(FirmwareUpgradeLog) << "Verify complete";
+ emit status("Verify complete");
+ } else {
+ qCDebug(FirmwareUpgradeLog) << "Verify failed:" << _bootloader->errorString();
+ emit error(_bootloader->errorString());
+ }
}
- _bootloaderPort->deleteLater();
- _bootloaderPort = NULL;
+
+ emit _reboot();
+
+ emit flashComplete();
}
-void PX4FirmwareUpgradeThreadWorker::erase(void)
+bool PX4FirmwareUpgradeThreadWorker::_erase(void)
{
- qDebug() << "Erase";
- if (!_bootloader->erase(_bootloaderPort)) {
- _bootloaderPort->deleteLater();
- _bootloaderPort = NULL;
- qDebug() << "Erase failed:" << _bootloader->errorString();
- emit error(commandErase, _bootloader->errorString());
+ qCDebug(FirmwareUpgradeLog) << "PX4FirmwareUpgradeThreadWorker::_erase";
+
+ emit eraseStarted();
+ emit status("Erasing previous program...");
+
+ if (_bootloader->erase(_bootloaderPort)) {
+ qCDebug(FirmwareUpgradeLog) << "Erase complete";
+ emit status("Erase complete");
+ emit eraseComplete();
+ return true;
} else {
- qDebug() << "Erase complete";
- emit complete(commandErase);
+ qCDebug(FirmwareUpgradeLog) << "Erase failed:" << _bootloader->errorString();
+ emit error(_bootloader->errorString());
+ return false;
}
}
PX4FirmwareUpgradeThreadController::PX4FirmwareUpgradeThreadController(QObject* parent) :
QObject(parent)
{
- _worker = new PX4FirmwareUpgradeThreadWorker();
+ _worker = new PX4FirmwareUpgradeThreadWorker(this);
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::updateProgress, this, &PX4FirmwareUpgradeThreadController::_updateProgress);
+ connect(_worker, &PX4FirmwareUpgradeThreadWorker::foundBoard, this, &PX4FirmwareUpgradeThreadController::_foundBoard);
+ connect(_worker, &PX4FirmwareUpgradeThreadWorker::noBoardFound, this, &PX4FirmwareUpgradeThreadController::_noBoardFound);
+ connect(_worker, &PX4FirmwareUpgradeThreadWorker::boardGone, this, &PX4FirmwareUpgradeThreadController::_boardGone);
+ 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(_worker, &PX4FirmwareUpgradeThreadWorker::error, this, &PX4FirmwareUpgradeThreadController::_error);
+ connect(_worker, &PX4FirmwareUpgradeThreadWorker::status, this, &PX4FirmwareUpgradeThreadController::_status);
+ connect(_worker, &PX4FirmwareUpgradeThreadWorker::eraseStarted, this, &PX4FirmwareUpgradeThreadController::_eraseStarted);
+ connect(_worker, &PX4FirmwareUpgradeThreadWorker::eraseComplete, this, &PX4FirmwareUpgradeThreadController::_eraseComplete);
+ connect(_worker, &PX4FirmwareUpgradeThreadWorker::flashComplete, this, &PX4FirmwareUpgradeThreadController::_flashComplete);
- 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();
@@ -277,36 +375,24 @@ PX4FirmwareUpgradeThreadController::~PX4FirmwareUpgradeThreadController()
{
_workerThread->quit();
_workerThread->wait();
+
+ delete _workerThread;
}
-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(bool firstTry, const QString portName, QString portDescription)
+void PX4FirmwareUpgradeThreadController::startFindBoardLoop(void)
{
- emit foundBoard(firstTry, portName, portDescription);
+ qCDebug(FirmwareUpgradeLog) << "PX4FirmwareUpgradeThreadController::findBoard";
+ emit _startFindBoardLoopOnThread();
}
-void PX4FirmwareUpgradeThreadController::_foundBootloader(int bootloaderVersion, int boardID, int flashSize)
+void PX4FirmwareUpgradeThreadController::cancel(void)
{
- emit foundBootloader(bootloaderVersion, boardID, flashSize);
-}
-
-void PX4FirmwareUpgradeThreadController::_bootloaderSyncFailed(void)
-{
- emit bootloaderSyncFailed();
+ qCDebug(FirmwareUpgradeLog) << "PX4FirmwareUpgradeThreadController::cancel";
+ emit _cancel();
}
-void PX4FirmwareUpgradeThreadController::_findTimeout(void)
+void PX4FirmwareUpgradeThreadController::flash(const FirmwareImage* image)
{
- emit findTimeout();
+ _image = image;
+ emit _flashOnThread();
}
diff --git a/src/VehicleSetup/PX4FirmwareUpgradeThread.h b/src/VehicleSetup/PX4FirmwareUpgradeThread.h
index ff67235943460bd5cea6a12e4a0bd3cc9fe35c78..afbe5990d803676d112e3196638d09c79a27ea14 100644
--- a/src/VehicleSetup/PX4FirmwareUpgradeThread.h
+++ b/src/VehicleSetup/PX4FirmwareUpgradeThread.h
@@ -28,16 +28,27 @@
#ifndef PX4FirmwareUpgradeThread_H
#define PX4FirmwareUpgradeThread_H
+#include "Bootloader.h"
+#include "FirmwareImage.h"
+
#include
#include
#include
#include
+#include
#include "qextserialport.h"
#include
-#include "PX4Bootloader.h"
+typedef enum {
+ FoundBoardPX4FMUV1,
+ FoundBoardPX4FMUV2,
+ FoundBoardPX4Flow,
+ FoundBoard3drRadio
+} PX4FirmwareUpgradeFoundBoardType_t;
+
+class PX4FirmwareUpgradeThreadController;
/// @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
@@ -47,52 +58,59 @@ class PX4FirmwareUpgradeThreadWorker : public QObject
Q_OBJECT
public:
- PX4FirmwareUpgradeThreadWorker(QObject* parent = NULL);
+ PX4FirmwareUpgradeThreadWorker(PX4FirmwareUpgradeThreadController* controller);
~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(bool firstTry, const QString portname, QString portDescription);
+ void updateProgress(int curr, int total);
+ void foundBoard(bool firstAttempt, const QSerialPortInfo& portInfo, int type);
+ void noBoardFound(void);
+ void boardGone(void);
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);
+ void error(const QString& errorString);
+ void status(const QString& statusText);
+ void eraseStarted(void);
+ void eraseComplete(void);
+ void flashComplete(void);
private slots:
+ void _init(void);
+ void _startFindBoardLoop(void);
+ void _reboot(void);
+ void _flash(void);
void _findBoardOnce(void);
- void _findBootloaderOnce(void);
- void _updateProgramProgress(int curr, int total) { emit updateProgress(curr, total); }
- void _closeFind(void);
+ void _updateProgress(int curr, int total) { emit updateProgress(curr, total); }
+ void _cancel(void);
private:
- PX4Bootloader* _bootloader;
+ bool _findBoardFromPorts(QSerialPortInfo& portInfo, PX4FirmwareUpgradeFoundBoardType_t& type);
+ bool _findBootloader(const QSerialPortInfo& portInfo, bool radioMode, bool errorOnNotFound);
+ void _3drRadioForceBootloader(const QSerialPortInfo& portInfo);
+ bool _erase(void);
+
+ PX4FirmwareUpgradeThreadController* _controller;
+
+ Bootloader* _bootloader;
QextSerialPort* _bootloaderPort;
- QTimer* _timerTimeout;
QTimer* _timerRetry;
QTime _elapsed;
- QString _portName;
static const int _retryTimeout = 1000;
- bool _findBoardFirstAttempt;
+
+ bool _foundBoard; ///< true: board is currently connected
+ bool _findBoardFirstAttempt; ///< true: this is our first try looking for a board
+ QSerialPortInfo _foundBoardPortInfo; ///< port info for found board
+
+ // Serial port info for supported devices
+
+ static const int _px4VendorId = 9900;
+
+ static const int _pixhawkFMUV2ProductId = 17;
+ static const int _pixhawkFMUV1ProductId = 16;
+ static const int _flowProductId = 21;
+
+ static const int _3drRadioVendorId = 1027;
+ static const int _3drRadioProductId = 24597;
};
/// @brief Provides methods to interact with the bootloader. The commands themselves are signalled
@@ -105,82 +123,74 @@ public:
PX4FirmwareUpgradeThreadController(QObject* parent = NULL);
~PX4FirmwareUpgradeThreadController(void);
- /// Returns true is a board is currently connected via USB
- bool pluggedInBoard(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 Begins the process of searching for a supported board connected to any serial port. This will
+ /// continue until cancelFind is called. Signals foundBoard and boardGone as boards come and go.
+ void startFindBoardLoop(void);
- /// @brief Cancel an in progress findBoard or FindBootloader
- void cancelFind(void) { emit _cancelFindOnThread(); }
+ void cancel(void);
/// @brief Sends a reboot command to the bootloader
- void sendBootloaderReboot(void) { emit _sendBootloaderRebootOnThread(); }
+ void reboot(void) { emit _rebootOnThread(); }
- /// @brief Flash the specified firmware onto the board
- void program(const QString firmwareFilename) { emit _programOnThread(firmwareFilename); }
+ void flash(const FirmwareImage* image);
- /// @brief Verify the board flash with respect to the specified firmware image
- void verify(const QString firmwareFilename) { emit _verifyOnThread(firmwareFilename); }
+ const FirmwareImage* image(void) { return _image; }
- /// @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 firstTry true: board found on first attempt
- /// @param portName Port that board is on
- /// @param portDescription User friendly port description
- void foundBoard(bool firstTry, const QString portname, QString portDescription);
+ /// @brief Emitted by the find board process when it finds a board.
+ void foundBoard(bool firstAttempt, const QSerialPortInfo &portInfo, int type);
+
+ void noBoardFound(void);
+
+ /// @brief Emitted by the find board process when a board it previously reported as found disappears.
+ void boardGone(void);
/// @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);
+ void error(const QString& errorString);
+
+ void status(const QString& status);
/// @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);
+ void eraseStarted(void);
+ void eraseComplete(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);
+ void flashComplete(void);
/// @brief Signalled to update progress for long running bootloader commands
void updateProgress(int curr, int total);
+ // Internal signals to communicate with thread worker
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);
+ void _startFindBoardLoopOnThread(void);
+ void _rebootOnThread(void);
+ void _flashOnThread(void);
+ void _cancel(void);
private slots:
- void _foundBoard(bool firstTry, 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); }
+ void _foundBoard(bool firstAttempt, const QSerialPortInfo& portInfo, int type) { emit foundBoard(firstAttempt, portInfo, type); }
+ void _noBoardFound(void) { emit noBoardFound(); }
+ void _boardGone(void) { emit boardGone(); }
+ void _foundBootloader(int bootloaderVersion, int boardID, int flashSize) { emit foundBootloader(bootloaderVersion, boardID, flashSize); }
+ void _bootloaderSyncFailed(void) { emit bootloaderSyncFailed(); }
+ void _error(const QString& errorString) { emit error(errorString); }
+ void _status(const QString& statusText) { emit status(statusText); }
+ void _eraseStarted(void) { emit eraseStarted(); }
+ void _eraseComplete(void) { emit eraseComplete(); }
+ void _flashComplete(void) { emit flashComplete(); }
private:
+ void _updateProgress(int curr, int total) { emit updateProgress(curr, total); }
+
PX4FirmwareUpgradeThreadWorker* _worker;
QThread* _workerThread; ///< Thread which PX4FirmwareUpgradeThreadWorker runs on
+
+ const FirmwareImage* _image;
};
#endif
diff --git a/src/main.cc b/src/main.cc
index 585a46c7e7c8de598a1499242c99f5d3b280f5e7..8c097575cc2ebaeef5ff104b017a5efa7f2fcb38 100644
--- a/src/main.cc
+++ b/src/main.cc
@@ -30,6 +30,7 @@ This file is part of the QGROUNDCONTROL project
#include
#include
+#include
#include "QGCApplication.h"
#include "MainWindow.h"
@@ -49,6 +50,7 @@ This file is part of the QGROUNDCONTROL project
#undef main
#endif
+Q_DECLARE_METATYPE(QSerialPortInfo)
#ifdef Q_OS_WIN
@@ -107,6 +109,8 @@ int main(int argc, char *argv[])
qRegisterMetaType();
#endif
qRegisterMetaType();
+ qRegisterMetaType();
+
// We statically link to the google QtLocation plugin
#ifdef Q_OS_WIN