PX4FirmwareUpgradeThread.h 7.12 KB
Newer Older
1 2 3 4 5 6 7 8 9 10 11 12 13 14 15 16 17 18 19 20 21 22 23 24 25 26 27 28 29 30
/*=====================================================================
 
 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

31 32 33
#include "Bootloader.h"
#include "FirmwareImage.h"

34 35 36 37
#include <QObject>
#include <QThread>
#include <QTimer>
#include <QTime>
38
#include <QSerialPortInfo>
39

40 41
#include "qextserialport.h"

42 43
#include <stdint.h>

44 45 46 47 48 49 50 51
typedef enum {
    FoundBoardPX4FMUV1,
    FoundBoardPX4FMUV2,
    FoundBoardPX4Flow,
    FoundBoard3drRadio
} PX4FirmwareUpgradeFoundBoardType_t;

class PX4FirmwareUpgradeThreadController;
52 53 54 55 56 57 58 59 60

/// @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:
61
    PX4FirmwareUpgradeThreadWorker(PX4FirmwareUpgradeThreadController* controller);
62 63 64
    ~PX4FirmwareUpgradeThreadWorker();
    
signals:
65 66 67 68
    void updateProgress(int curr, int total);
    void foundBoard(bool firstAttempt, const QSerialPortInfo& portInfo, int type);
    void noBoardFound(void);
    void boardGone(void);
69 70
    void foundBootloader(int bootloaderVersion, int boardID, int flashSize);
    void bootloaderSyncFailed(void);
71 72 73 74 75
    void error(const QString& errorString);
    void status(const QString& statusText);
    void eraseStarted(void);
    void eraseComplete(void);
    void flashComplete(void);
76 77
    
private slots:
78 79 80 81
    void _init(void);
    void _startFindBoardLoop(void);
    void _reboot(void);
    void _flash(void);
82
    void _findBoardOnce(void);
83 84
    void _updateProgress(int curr, int total) { emit updateProgress(curr, total); }
    void _cancel(void);
85 86
    
private:
87 88 89 90 91 92 93 94
    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;
95
    QextSerialPort*     _bootloaderPort;
96 97 98
    QTimer*             _timerRetry;
    QTime               _elapsed;
    static const int    _retryTimeout = 1000;
99 100 101 102 103 104 105 106 107 108 109 110 111 112 113
    
    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;
114 115 116 117 118 119 120 121 122 123 124 125
};

/// @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);
    
126 127 128
    /// @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);
129
    
130
    void cancel(void);
131 132
    
    /// @brief Sends a reboot command to the bootloader
133
    void reboot(void) { emit _rebootOnThread(); }
134
    
135
    void flash(const FirmwareImage* image);
136
    
137
    const FirmwareImage* image(void) { return _image; }
138 139
    
signals:
140 141 142 143 144 145 146
    /// @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);
147 148 149 150 151
    
    /// @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.
152 153 154
    void error(const QString& errorString);
    
    void status(const QString& status);
155 156 157 158 159
    
    /// @brief Signalled when the findBootloader process connects to the port, but cannot sync to the
    ///         bootloader.
    void bootloaderSyncFailed(void);
    
160 161
    void eraseStarted(void);
    void eraseComplete(void);
162
    
163
    void flashComplete(void);
164 165 166 167
    
    /// @brief Signalled to update progress for long running bootloader commands
    void updateProgress(int curr, int total);
    
168
    // Internal signals to communicate with thread worker
169
    void _initThreadWorker(void);
170 171 172 173
    void _startFindBoardLoopOnThread(void);
    void _rebootOnThread(void);
    void _flashOnThread(void);
    void _cancel(void);
174 175
    
private slots:
176 177 178 179 180 181 182 183 184 185
    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(); }
186 187
    
private:
188 189
    void _updateProgress(int curr, int total) { emit updateProgress(curr, total); }
    
190 191
    PX4FirmwareUpgradeThreadWorker* _worker;
    QThread*                        _workerThread;  ///< Thread which PX4FirmwareUpgradeThreadWorker runs on
192 193
    
    const FirmwareImage* _image;
194 195 196
};

#endif