Commit e28996be authored by Don Gagne's avatar Don Gagne

New Firmware Upgrade implementation

parent 5e638643
......@@ -5,57 +5,6 @@ WindowsBuild {
INCLUDEPATH += libs/lib/msinttypes
}
#
# [OPTIONAL] QUpgrade support.
#
# Allow the user to override QUpgrade compilation through a DISABLE_QUPGRADE
# define like: `qmake DEFINES=DISABLE_QUPGRADE`
contains(DEFINES, DISABLE_QUPGRADE) {
message("Skipping support for QUpgrade (manual override from command line)")
DEFINES -= DISABLE_QUPGRADE
}
# Otherwise the user can still disable this feature in the user_config.pri file.
else:exists(user_config.pri):infile(user_config.pri, DEFINES, DISABLE_QUPGRADE) {
message("Skipping support for QUpgrade (manual override from user_config.pri)")
}
# If the QUpgrade submodule has been initialized, build in support by default.
# We look for the existence of qupgrade.pro for the check. We can't look for a .git file
# because that breaks the TeamCity build process which does not use repositories.
else:exists(qupgrade/qupgrade.pro) {
message("Including support for QUpgrade")
DEFINES += QGC_QUPGRADE_ENABLED
INCLUDEPATH += qupgrade/src/apps/qupgrade
FORMS += \
qupgrade/src/apps/qupgrade/dialog_bare.ui \
qupgrade/src/apps/qupgrade/boardwidget.ui
HEADERS += \
qupgrade/src/apps/qupgrade/qgcfirmwareupgradeworker.h \
qupgrade/src/apps/qupgrade/uploader.h \
qupgrade/src/apps/qupgrade/dialog_bare.h \
qupgrade/src/apps/qupgrade/boardwidget.h
SOURCES += \
qupgrade/src/apps/qupgrade/qgcfirmwareupgradeworker.cpp \
qupgrade/src/apps/qupgrade/uploader.cpp \
qupgrade/src/apps/qupgrade/dialog_bare.cpp \
qupgrade/src/apps/qupgrade/boardwidget.cpp
RESOURCES += \
qupgrade/qupgrade.qrc
LinuxBuild:CONFIG += qesp_linux_udev
include(qupgrade/libs/qextserialport/src/qextserialport.pri)
}
# Otherwise notify the user and don't compile it.
else {
warning("Skipping support for QUpgrade (missing submodule, see README)")
}
#
# [REQUIRED] Add support for the MAVLink communications protocol.
# Some logic is involved here in selecting the proper dialect for
......
......@@ -137,6 +137,7 @@ MacBuild {
LinuxBuild {
DEFINES += __STDC_LIMIT_MACROS
CONFIG += qesp_linux_udev
}
WindowsBuild {
......@@ -245,6 +246,7 @@ INCLUDEPATH += \
src/ui/mission \
src/ui/designer \
src/ui/configuration \
src/ui/px4_configuration \
src/ui/main
FORMS += \
......@@ -358,6 +360,7 @@ FORMS += \
src/ui/px4_configuration/QGCPX4MulticopterConfig.ui \
src/ui/px4_configuration/QGCPX4SensorCalibration.ui \
src/ui/px4_configuration/PX4RCCalibration.ui \
src/ui/px4_configuration/PX4FirmwareUpgrade.ui \
src/ui/QGCUASFileView.ui
HEADERS += \
......@@ -544,6 +547,9 @@ HEADERS += \
src/ui/px4_configuration/QGCPX4MulticopterConfig.h \
src/ui/px4_configuration/QGCPX4SensorCalibration.h \
src/ui/px4_configuration/PX4RCCalibration.h \
src/ui/px4_configuration/PX4Bootloader.h \
src/ui/px4_configuration/PX4FirmwareUpgradeThread.h \
src/ui/px4_configuration/PX4FirmwareUpgrade.h \
src/ui/menuactionhelper.h \
src/uas/UASManagerInterface.h \
src/uas/QGCUASParamManagerInterface.h \
......@@ -729,6 +735,9 @@ SOURCES += \
src/ui/px4_configuration/QGCPX4MulticopterConfig.cc \
src/ui/px4_configuration/QGCPX4SensorCalibration.cc \
src/ui/px4_configuration/PX4RCCalibration.cc \
src/ui/px4_configuration/PX4Bootloader.cc \
src/ui/px4_configuration/PX4FirmwareUpgradeThread.cc \
src/ui/px4_configuration/PX4FirmwareUpgrade.cc \
src/ui/menuactionhelper.cpp \
src/uas/QGCUASFileManager.cc \
src/ui/QGCUASFileView.cc \
......
......@@ -199,6 +199,9 @@
<file>files/images/px4/calibration/3dr_gps/gps_24.png</file>
<file>files/images/px4/calibration/3dr_gps/gps_00.png</file>
<file>files/images/px4/menu/toggle_switch.png</file>
<file>files/images/px4/boards/px4flow_1.x.png</file>
<file>files/images/px4/boards/px4fmu_1.x.png</file>
<file>files/images/px4/boards/px4fmu_2.x.png</file>
</qresource>
<qresource prefix="/general">
<file alias="vera.ttf">files/styles/Vera.ttf</file>
......
......@@ -25,9 +25,7 @@
#include "px4_configuration/QGCPX4SensorCalibration.h"
#include "px4_configuration/PX4RCCalibration.h"
#ifdef QGC_QUPGRADE_ENABLED
#include <dialog_bare.h>
#endif
#include "PX4FirmwareUpgrade.h"
#define WIDGET_INDEX_FIRMWARE 0
#define WIDGET_INDEX_RC 1
......@@ -67,18 +65,8 @@ QGCPX4VehicleConfig::QGCPX4VehicleConfig(QWidget *parent) :
px4RCCalibration = new PX4RCCalibration(this);
ui->rcLayout->addWidget(px4RCCalibration);
#ifdef QGC_QUPGRADE_ENABLED
DialogBare *firmwareDialog = new DialogBare(this);
ui->firmwareLayout->addWidget(firmwareDialog);
connect(firmwareDialog, SIGNAL(connectLinks()), LinkManager::instance(), SLOT(connectAll()));
connect(firmwareDialog, SIGNAL(disconnectLinks()), LinkManager::instance(), SLOT(disconnectAll()));
#else
QLabel* label = new QLabel(this);
label->setText("THIS VERSION OF QGROUNDCONTROL WAS BUILT WITHOUT QUPGRADE. To enable firmware upload support, checkout QUpgrade WITHIN the QGroundControl folder");
ui->firmwareLayout->addWidget(label);
#endif
PX4FirmwareUpgrade* firmwareUpgrade = new PX4FirmwareUpgrade(this);
ui->firmwareLayout->addWidget(firmwareUpgrade);
connect(ui->rcMenuButton,SIGNAL(clicked()),
this,SLOT(rcMenuButtonClicked()));
......@@ -278,10 +266,6 @@ void QGCPX4VehicleConfig::setActiveUAS(UASInterface* active)
qDebug() << "CALIBRATION!! System Type Name:" << mav->getSystemTypeName();
//Load configuration after 1ms. This allows it to go into the event loop, and prevents application hangups due to the
//amount of time it actually takes to load the configuration windows.
QTimer::singleShot(1,this,SLOT(loadConfig()));
updateStatus(QString("Reading from system %1").arg(mav->getUASName()));
// Since a system is now connected, enable the VehicleConfig UI.
......
This diff is collapsed.
/*=====================================================================
QGroundControl Open Source Ground Control Station
(c) 2009, 2014 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org>
This file is part of the QGROUNDCONTROL project
QGROUNDCONTROL is free software: you can redistribute it and/or modify
it under the terms of the GNU General Public License as published by
the Free Software Foundation, either version 3 of the License, or
(at your option) any later version.
QGROUNDCONTROL is distributed in the hope that it will be useful,
but WITHOUT ANY WARRANTY; without even the implied warranty of
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
GNU General Public License for more details.
You should have received a copy of the GNU General Public License
along with QGROUNDCONTROL. If not, see <http://www.gnu.org/licenses/>.
======================================================================*/
/// @file
/// @brief PX4 Bootloader Utility routines
/// @author Don Gagne <don@thegagnes.com>
#ifndef PX4Bootloader_H
#define PX4Bootloader_H
#include <QSerialPort>
#include <stdint.h>
/// @brief This class is used to communicate with the Bootloader.
class PX4Bootloader : public QObject
{
Q_OBJECT
public:
explicit PX4Bootloader(QObject *parent = 0);
/// @brief Returns the error message associated with the last failed call to one of the bootloader
/// utility routine below.
QString errorString(void) { return _errorString; }
static const bool warnOnError = true; ///< call qWarning to log error message on error
static const bool noWarnOnError = false; ///< Don't call qWarning on error
/// @brief Write a byte to the port
/// @param port Port to write to
/// @param data Bytes to write
/// @param maxSize Number of bytes to write
/// @return true: success
bool write(QSerialPort* port, const uint8_t* data, qint64 maxSize);
bool write(QSerialPort* port, const uint8_t byte);
/// @brief Read a set of bytes from the port
/// @param data Read bytes into this buffer
/// @param maxSize Number of bytes to read
/// @param warnOnError true: Log error using qWarning
/// @param readTimeout Msecs to wait for bytes to become available on port
bool read(QSerialPort* port, uint8_t* data, qint64 maxSize, bool warnOnError, int readTimeout = _readTimout);
/// @brief Read a PROTO_SYNC command response from the bootloader
/// @param responseTimeout Msecs to wait for response bytes to become available on port
bool getCommandResponse(QSerialPort* port, bool warnOnError, const int responseTimeout = _responseTimeout);
/// @brief Send a PROTO_GET_DEVICE command to retrieve a value from the bootloader
/// @param param Value to retrieve using INFO_BOARD_* enums
/// @param value Returned value
bool getBoardInfo(QSerialPort* port, uint8_t param, uint32_t& value);
/// @brief Send a command to the bootloader
/// @param cmd Command to send using PROTO_* enums
/// @return true: Command sent and valid sync response returned
bool sendCommand(QSerialPort* port, uint8_t cmd, bool warnOnError, int responseTimeout = _responseTimeout);
/// @brief Program the board with the specified firmware
bool program(QSerialPort* port, const QString& firmwareFilename);
/// @brief Verify the board flash. How it works depend on bootloader rev
/// Rev 2: Read the flash back and compare it against the firmware file
/// Rev 3: Compare CRCs for flash and file
bool verify(QSerialPort* port, const QString firmwareFilename);
/// @brief Read a PROTO_SYNC response from the bootloader
/// @return true: Valid sync response was received
bool sync(QSerialPort* port);
/// @brief Retrieve a set of board info from the bootloader
/// @param bootloaderVersion Returned INFO_BL_REV
/// @param boardID Returned INFO_BOARD_ID
/// @param flashSize Returned INFO_FLASH_SIZE
bool getBoardInfo(QSerialPort* port, uint32_t& bootloaderVersion, uint32_t& boardID, uint32_t& flashSize);
/// @brief Opens a port to the bootloader
bool open(QSerialPort* port, const QString portName);
/// @brief Sends a PROTO_REBOOT command to the bootloader
bool sendBootloaderReboot(QSerialPort* port);
/// @brief Sends a PROTO_ERASE command to the bootlader
bool erase(QSerialPort* port);
signals:
/// @brief Signals progress indicator for long running bootloader utility routines
void updateProgramProgress(int curr, int total);
private:
enum {
// protocol bytes
PROTO_INSYNC = 0x12, ///< 'in sync' byte sent before status
PROTO_EOC = 0x20, ///< end of command
// Reply bytes
PROTO_OK = 0x10, ///< INSYNC/OK - 'ok' response
PROTO_FAILED = 0x11, ///< INSYNC/FAILED - 'fail' response
PROTO_INVALID = 0x13, ///< INSYNC/INVALID - 'invalid' response for bad commands
// Command bytes
PROTO_GET_SYNC = 0x21, ///< NOP for re-establishing sync
PROTO_GET_DEVICE = 0x22, ///< get device ID bytes
PROTO_CHIP_ERASE = 0x23, ///< erase program area and reset program address
PROTO_PROG_MULTI = 0x27, ///< write bytes at program address and increment
PROTO_GET_CRC = 0x29, ///< compute & return a CRC
PROTO_BOOT = 0x30, ///< boot the application
// Command bytes - Rev 2 boootloader only
PROTO_CHIP_VERIFY = 0x24, ///< begin verify mode
PROTO_READ_MULTI = 0x28, ///< read bytes at programm address and increment
INFO_BL_REV = 1, ///< bootloader protocol revision
BL_REV_MIN = 2, ///< Minimum supported bootlader protocol
BL_REV_MAX = 4, ///< Maximum supported bootloader protocol
INFO_BOARD_ID = 2, ///< board type
INFO_BOARD_REV = 3, ///< board revision
INFO_FLASH_SIZE = 4, ///< max firmware size in bytes
PROG_MULTI_MAX = 32, ///< write size for PROTO_PROG_MULTI, must be multiple of 4
READ_MULTI_MAX = 64 ///< read size for PROTO_READ_MULTI, must be multiple of 4
};
struct serialPortErrorString {
int error;
const char* errorString;
};
bool _findBootloader(void);
bool _downloadFirmware(void);
bool _bootloaderVerifyRev2(QSerialPort* port, const QString firmwareFilename);
bool _bootloaderVerifyRev3(QSerialPort* port);
const char* _serialPortErrorString(int error);
static const int _boardIDPX4FMUV1 = 5; ///< Board ID for PX4 V1 board
static const int _boardIDPX4FMUV2 = 9; ///< Board ID for PX4 V2 board
static const int _boardIDPX4Flow = 6; ///< Board ID for PX4 Floaw board
uint32_t _boardID; ///< board id for currently connected board
uint32_t _boardFlashSize; ///< flash size for currently connected board
uint32_t _imageCRC; ///< CRC for image in currently selected firmware file
uint32_t _bootloaderVersion; ///< Bootloader version
QString _firmwareFilename; ///< Currently selected firmware file to flash
QString _errorString; ///< Last error
static const struct serialPortErrorString _rgSerialPortErrors[14]; ///< Translation of QSerialPort::SerialPortError into string
static const int _eraseTimeout = 20000; ///< Msecs to wait for response from erase command
static const int _rebootTimeout = 10000; ///< Msecs to wait for reboot command to cause serial port to disconnect
static const int _verifyTimeout = 5000; ///< Msecs to wait for response to PROTO_GET_CRC command
static const int _readTimout = 2000; ///< Msecs to wait for read bytes to become avilable
static const int _responseTimeout = 2000; ///< Msecs to wait for command response bytes
};
#endif // PX4FirmwareUpgrade_H
This diff is collapsed.
/*=====================================================================
QGroundControl Open Source Ground Control Station
(c) 2009, 2014 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org>
This file is part of the QGROUNDCONTROL project
QGROUNDCONTROL is free software: you can redistribute it and/or modify
it under the terms of the GNU General Public License as published by
the Free Software Foundation, either version 3 of the License, or
(at your option) any later version.
QGROUNDCONTROL is distributed in the hope that it will be useful,
but WITHOUT ANY WARRANTY; without even the implied warranty of
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
GNU General Public License for more details.
You should have received a copy of the GNU General Public License
along with QGROUNDCONTROL. If not, see <http://www.gnu.org/licenses/>.
======================================================================*/
/// @file
/// @brief PX4 Firmware Upgrade UI
/// @author Don Gagne <don@thegagnes.com>
#ifndef PX4FirmwareUpgrade_H
#define PX4FirmwareUpgrade_H
#include <QWidget>
#include <QUrl>
#include <QSerialPort>
#include <QTimer>
#include <QNetworkAccessManager>
#include <QNetworkReply>
#include <stdint.h>
#include "PX4FirmwareUpgradeThread.h"
#include "ui_PX4FirmwareUpgrade.h"
namespace Ui {
class PX4RCCalibration;
}
class PX4FirmwareUpgrade : public QWidget
{
Q_OBJECT
public:
explicit PX4FirmwareUpgrade(QWidget *parent = 0);
~PX4FirmwareUpgrade();
private slots:
void _tryAgainButton(void);
void _cancelButton(void);
void _nextButton(void);
void _firmwareSelected(int index);
void _downloadProgress(qint64 curr, qint64 total);
void _downloadFinished(void);
void _downloadError(QNetworkReply::NetworkError code);
void _foundBoard(const QString portname, QString portDescription);
void _foundBootloader(int bootloaderVersion, int boardID, int flashSize);
void _error(const int command, const QString errorString);
void _bootloaderSyncFailed(void);
void _findTimeout(void);
void _complete(const int command);
void _updateProgress(int curr, int total);
void _restart(void);
void _eraseProgressTick(void);
private:
/// @brief The various states that the upgrade process progresses through.
enum upgradeStates {
upgradeStateBegin,
upgradeStateBoardSearch,
upgradeStateBoardNotFound,
upgradeStateBootloaderSearch,
upgradeStateBootloaderNotFound,
upgradeStateBootloaderError,
upgradeStateFirmwareSelect,
upgradeStateFirmwareDownloading,
upgradeStateDownloadFailed,
upgradeStateErasing,
upgradeStateEraseError,
upgradeStateFlashing,
upgradeStateFlashError,
upgradeStateVerifying,
upgradeStateVerifyError,
upgradeStateBoardUpgraded,
upgradeStateMax
};
void _setupState(enum upgradeStates state);
void _updateIndicatorUI(void);
void _findBoard(void);
void _findBootloader(void);
void _cancel(void);
void _cancelFind(void);
void _getFirmwareFile(void);
void _setBoardIcon(int boardID);
void _setFirmwareCombo(int boardID);
void _downloadFirmware(void);
void _cancelDownload(void);
void _erase(void);
typedef void (PX4FirmwareUpgrade::*stateFunc)(void);
struct stateMachineEntry {
enum upgradeStates state; ///< State machine state, used to verify correctness of entry
stateFunc next; ///< Method to call when Next is clicked, NULL for Next not available
stateFunc cancel; ///< Method to call when Cancel is clicked, NULL for Cancel not available
stateFunc tryAgain; ///< Method to call when Try Again is clicked, NULL for Try Again not available
const char* msg; ///< Text message to display to user for this state
};
const struct stateMachineEntry* _getStateMachineEntry(enum upgradeStates state);
enum upgradeStates _upgradeState; ///< Current state of the upgrade state machines
QString _portName;
QString _portDescription;
uint32_t _bootloaderVersion;
static const int _boardIDPX4FMUV1 = 5; ///< Board ID for PX4 V1 board
static const int _boardIDPX4FMUV2 = 9; ///< Board ID for PX4 V2 board
static const int _boardIDPX4Flow = 6; ///< Board ID for PX4 Flow board
uint32_t _boardID; ///< Board ID
uint32_t _boardFlashSize; ///< Flash size in bytes of board
uint32_t _imageSize; ///< Image size of firmware being flashed
QPixmap _boardIcon; ///< Icon used to display image of board
QString _firmwareFilename; ///< Image which we are going to flash to the board
QNetworkAccessManager* _downloadManager; ///< Used for firmware file downloading across the internet
QNetworkReply* _downloadNetworkReply; ///< Used for firmware file downloading across the internet
/// @brief Thread controller which is used to run bootloader commands on seperate thread
PX4FirmwareUpgradeThreadController* _threadController;
static const int _eraseTickMsec = 500; ///< Progress bar update tick time for erase
static const int _eraseTotalMsec = 15000; ///< Estimated amount of time erase takes
int _eraseTickCount; ///< Number of ticks for erase progress update
QTimer _eraseTimer; ///< Timer used to update progress bar for erase
static const int _findBoardTimeoutMsec = 30000; ///< Amount of time for user to plug in USB
static const int _findBootloaderTimeoutMsec = 5000; ///< Amount time to look for bootloader
Ui::PX4FirmwareUpgrade* _ui;
};
#endif // PX4FirmwareUpgrade_H
<?xml version="1.0" encoding="UTF-8"?>
<ui version="4.0">
<class>PX4FirmwareUpgrade</class>
<widget class="QWidget" name="PX4FirmwareUpgrade">
<property name="geometry">
<rect>
<x>0</x>
<y>0</y>
<width>1562</width>
<height>1286</height>
</rect>
</property>
<property name="windowTitle">
<string>Form</string>
</property>
<widget class="QWidget" name="layoutWidget">
<property name="geometry">
<rect>
<x>0</x>
<y>0</y>
<width>726</width>
<height>525</height>
</rect>
</property>
<layout class="QGridLayout" name="gridLayout" rowstretch="0" columnstretch="0,0">
<item row="0" column="1">
<layout class="QVBoxLayout" name="verticalLayout">
<item>
<widget class="QCheckBox" name="boardFoundCheck">
<property name="text">
<string>Board found</string>
</property>
</widget>
</item>
<item>
<widget class="QLabel" name="port">
<property name="text">
<string>Port</string>
</property>
<property name="alignment">
<set>Qt::AlignLeading|Qt::AlignLeft|Qt::AlignVCenter</set>
</property>
</widget>
</item>
<item>
<widget class="QLabel" name="description">
<property name="text">
<string>Description</string>
</property>
<property name="alignment">
<set>Qt::AlignLeading|Qt::AlignLeft|Qt::AlignVCenter</set>
</property>
</widget>
</item>
<item>
<widget class="QCheckBox" name="bootloaderFoundCheck">
<property name="text">
<string>Bootloader found</string>
</property>
</widget>
</item>
<item>
<widget class="QLabel" name="bootloaderVersion">
<property name="text">
<string>Bootloader Version</string>
</property>
<property name="alignment">
<set>Qt::AlignLeading|Qt::AlignLeft|Qt::AlignVCenter</set>
</property>
</widget>
</item>
<item>
<widget class="QLabel" name="boardID">
<property name="text">
<string>Board ID</string>
</property>
<property name="alignment">
<set>Qt::AlignLeading|Qt::AlignLeft|Qt::AlignVCenter</set>
</property>
</widget>
</item>
<item>
<widget class="QLabel" name="icon">
<property name="minimumSize">
<size>
<width>200</width>
<height>100</height>
</size>
</property>
<property name="text">
<string>Icon</string>
</property>
</widget>
</item>
<item>
<widget class="QCheckBox" name="selectFirmwareCheck">
<property name="text">
<string>Select Firmware</string>
</property>
</widget>
</item>
<item>
<widget class="QComboBox" name="firmwareCombo"/>
</item>
<item>
<widget class="QCheckBox" name="firmwareDownloadedCheck">
<property name="text">
<string>Firmware downloaded</string>
</property>
</widget>
</item>
<item>
<widget class="QCheckBox" name="boardUpgradedCheck">
<property name="text">
<string>Board upgraded</string>
</property>
</widget>
</item>
<item>
<spacer name="verticalSpacer">
<property name="orientation">
<enum>Qt::Vertical</enum>
</property>
<property name="sizeHint" stdset="0">
<size>
<width>20</width>
<height>40</height>
</size>
</property>
</spacer>
</item>
</layout>
</item>
<item row="0" column="0">
<layout class="QVBoxLayout" name="verticalLayout_9">
<item>
<widget class="QLabel" name="statusLog">
<property name="sizePolicy">
<sizepolicy hsizetype="Expanding" vsizetype="Expanding">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="minimumSize">
<size>
<width>400</width>
<height>180</height>
</size>
</property>
<property name="text">
<string>Status log</string>
</property>
<property name="alignment">
<set>Qt::AlignLeading|Qt::AlignLeft|Qt::AlignTop</set>
</property>
<property name="wordWrap">
<bool>true</bool>
</property>
</widget>
</item>
<item>
<widget class="QLabel" name="statusLabel">
<property name="sizePolicy">
<sizepolicy hsizetype="Expanding" vsizetype="Preferred">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="minimumSize">
<size>
<width>400</width>
<height>16</height>
</size>
</property>
<property name="text">
<string>TextLabel</string>
</property>
<property name="alignment">
<set>Qt::AlignLeading|Qt::AlignLeft|Qt::AlignTop</set>
</property>
<property name="wordWrap">
<bool>true</bool>
</property>
</widget>
</item>
<item>
<layout class="QHBoxLayout" name="horizontalLayout">
<item>
<widget class="QPushButton" name="tryAgain">
<property name="text">
<string>Try Again</string>
</property>
</widget>
</item>
<item>
<widget class="QPushButton" name="skip">
<property name="text">
<string>Skip</string>
</property>
</widget>
</item>
<item>
<widget class="QPushButton" name="cancel">
<property name="text">
<string>Cancel</string>
</property>
</widget>
</item>
<item>
<widget class="QPushButton" name="next">
<property name="text">
<string>Next</string>
</property>
</widget>
</item>
</layout>
</item>
<item>
<widget class="QProgressBar" name="progressBar">
<property name="value">
<number>24</number>
</property>
</widget>
</item>
<item>
<spacer name="verticalSpacer_3">
<property name="orientation">
<enum>Qt::Vertical</enum>
</property>
<property name="sizeHint" stdset="0">
<size>
<width>20</width>
<height>60</height>
</size>
</property>
</spacer>
</item>
</layout>
</item>
</layout>
</widget>
</widget>
<resources/>
<connections/>
</ui>
This diff is collapsed.
/*=====================================================================
QGroundControl Open Source Ground Control Station
(c) 2009, 2014 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org>
This file is part of the QGROUNDCONTROL project
QGROUNDCONTROL is free software: you can redistribute it and/or modify
it under the terms of the GNU General Public License as published by
the Free Software Foundation, either version 3 of the License, or
(at your option) any later version.
QGROUNDCONTROL is distributed in the hope that it will be useful,
but WITHOUT ANY WARRANTY; without even the implied warranty of
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
GNU General Public License for more details.
You should have received a copy of the GNU General Public License
along with QGROUNDCONTROL. If not, see <http://www.gnu.org/licenses/>.
======================================================================*/
/// @file
/// @brief PX4 Firmware Upgrade operations which occur on a seperate thread.
/// @author Don Gagne <don@thegagnes.com>
#ifndef PX4FirmwareUpgradeThread_H
#define PX4FirmwareUpgradeThread_H
#include <QObject>
#include <QSerialPort>
#include <QThread>
#include <QTimer>
#include <QTime>
#include <stdint.h>
#include "PX4Bootloader.h"
/// @brief Used to run bootloader commands on a seperate thread. These routines are mainly meant to to be called
/// internally by the PX4FirmwareUpgradeThreadController. Clients should call the various public methods
/// exposed by PX4FirmwareUpgradeThreadController.
class PX4FirmwareUpgradeThreadWorker : public QObject
{
Q_OBJECT
public:
PX4FirmwareUpgradeThreadWorker(QObject* parent = NULL);
~PX4FirmwareUpgradeThreadWorker();
enum {
commandBootloader,
commandProgram,
commandVerify,
commandErase,
commandCancel
};
public slots:
void init(void);
void findBoard(int msecTimeout);
void findBootloader(const QString portName, int msecTimeout);
void timeout(void);
void cancelFind(void);
void sendBootloaderReboot(void);
void program(const QString firmwareFilename);
void verify(const QString firmwareFilename);
void erase(void);
signals:
void foundBoard(const QString portname, QString portDescription);
void foundBootloader(int bootloaderVersion, int boardID, int flashSize);
void bootloaderSyncFailed(void);
void error(const int command, const QString errorString);
void complete(const int command);
void findTimeout(void);
void updateProgress(int curr, int total);
private slots:
void _findBoardOnce(void);
void _findBootloaderOnce(void);
void _updateProgramProgress(int curr, int total) { emit updateProgress(curr, total); }
void _closeFind(void);
private:
PX4Bootloader* _bootloader;
QSerialPort* _bootloaderPort;
QTimer* _timerTimeout;
QTimer* _timerRetry;
QTime _elapsed;
QString _portName;
static const int _retryTimeout = 1000;
};
/// @brief Provides methods to interact with the bootloader. The commands themselves are signalled
/// across to PX4FirmwareUpgradeThreadWorker so that they run on the seperate thread.
class PX4FirmwareUpgradeThreadController : public QObject
{
Q_OBJECT
public:
PX4FirmwareUpgradeThreadController(QObject* parent = NULL);
~PX4FirmwareUpgradeThreadController(void);
/// @brief Begins the process of searching for a PX4 board connected to any serial port.
/// @param msecTimeout Numbers of msecs to continue looking for a board to become available.
void findBoard(int msecTimeout);
/// @brief Begins the process of attempting to communicate with the bootloader on the specified port.
/// @param portName Name of port to attempt a bootloader connection on.
/// @param msecTimeout Number of msecs to continue to wait for a bootloader to appear on the port.
void findBootloader(const QString& portName, int msecTimeout);
/// @brief Cancel an in progress findBoard or FindBootloader
void cancelFind(void) { emit _cancelFindOnThread(); }
/// @brief Sends a reboot command to the bootloader
void sendBootloaderReboot(void) { emit _sendBootloaderRebootOnThread(); }
/// @brief Flash the specified firmware onto the board
void program(const QString firmwareFilename) { emit _programOnThread(firmwareFilename); }
/// @brief Verify the board flash with respect to the specified firmware image
void verify(const QString firmwareFilename) { emit _verifyOnThread(firmwareFilename); }
/// @brief Send and erase command to the bootloader
void erase(void) { emit _eraseOnThread(); }
signals:
/// @brief Emitted by the findBoard process when it finds the board.
/// @param portName Port that board is on
/// @param portDescription User friendly port description
void foundBoard(const QString portname, QString portDescription);
/// @brief Emitted by the findBootloader process when has a connection to the bootloader
void foundBootloader(int bootloaderVersion, int boardID, int flashSize);
/// @brief Emitted by the bootloader commands when an error occurs.
/// @param errorCommand Command which caused the error, using PX4FirmwareUpgradeThreadWorker command* enum values
void error(const int errorCommand, const QString errorString);
/// @brief Signalled when the findBootloader process connects to the port, but cannot sync to the
/// bootloader.
void bootloaderSyncFailed(void);
/// @brief Signalled when the findBoard or findBootloader process times out before success
void findTimeout(void);
/// @brief Signalled by the bootloader commands other than find* that they have complete successfully.
/// @param command Command which completed, using PX4FirmwareUpgradeThreadWorker command* enum values
void complete(const int command);
/// @brief Signalled to update progress for long running bootloader commands
void updateProgress(int curr, int total);
void _initThreadWorker(void);
void _findBoardOnThread(int msecTimeout);
void _findBootloaderOnThread(const QString& portName, int msecTimeout);
void _sendBootloaderRebootOnThread(void);
void _programOnThread(const QString firmwareFilename);
void _verifyOnThread(const QString firmwareFilename);
void _eraseOnThread(void);
void _cancelFindOnThread(void);
private slots:
void _foundBoard(const QString portname, QString portDescription);
void _foundBootloader(int bootloaderVersion, int boardID, int flashSize);
void _bootloaderSyncFailed(void);
void _error(const int errorCommand, const QString errorString) { emit error(errorCommand, errorString); }
void _complete(const int command) { emit complete(command); }
void _findTimeout(void);
void _updateProgress(int curr, int total) { emit updateProgress(curr, total); }
private:
PX4FirmwareUpgradeThreadWorker* _worker;
QThread* _workerThread; ///< Thread which PX4FirmwareUpgradeThreadWorker runs on
};
#endif
Markdown is supported
0% or
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment