Vehicle.h 21.6 KB
Newer Older
1
/*=====================================================================
dogmaphobic's avatar
dogmaphobic committed
2

3
 QGroundControl Open Source Ground Control Station
dogmaphobic's avatar
dogmaphobic committed
4

5
 (c) 2009 - 2014 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org>
dogmaphobic's avatar
dogmaphobic committed
6

7
 This file is part of the QGROUNDCONTROL project
dogmaphobic's avatar
dogmaphobic committed
8

9 10 11 12
 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.
dogmaphobic's avatar
dogmaphobic committed
13

14 15 16 17
 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.
dogmaphobic's avatar
dogmaphobic committed
18

19 20
 You should have received a copy of the GNU General Public License
 along with QGROUNDCONTROL. If not, see <http://www.gnu.org/licenses/>.
dogmaphobic's avatar
dogmaphobic committed
21

22 23 24 25 26 27 28 29 30
 ======================================================================*/

/// @file
///     @author Don Gagne <don@thegagnes.com>

#ifndef Vehicle_H
#define Vehicle_H

#include <QObject>
31
#include <QGeoCoordinate>
32 33 34

#include "LinkInterface.h"
#include "QGCMAVLink.h"
35
#include "MissionItem.h"
36
#include "QmlObjectListModel.h"
Don Gagne's avatar
Don Gagne committed
37
#include "MAVLinkProtocol.h"
dogmaphobic's avatar
dogmaphobic committed
38
#include "UASMessageHandler.h"
39

40 41
class UAS;
class UASInterface;
42
class FirmwarePlugin;
43
class FirmwarePluginManager;
44
class AutoPilotPlugin;
45
class AutoPilotPluginManager;
Don Gagne's avatar
Don Gagne committed
46
class MissionManager;
47
class ParameterLoader;
48
class JoystickManager;
dogmaphobic's avatar
dogmaphobic committed
49
class UASMessage;
50 51 52 53 54 55

Q_DECLARE_LOGGING_CATEGORY(VehicleLog)

class Vehicle : public QObject
{
    Q_OBJECT
dogmaphobic's avatar
dogmaphobic committed
56

57
public:
58 59 60 61 62 63 64
    Vehicle(LinkInterface*          link,
            int                     vehicleId,
            MAV_AUTOPILOT           firmwareType,
            MAV_TYPE                vehicleType,
            FirmwarePluginManager*  firmwarePluginManager,
            AutoPilotPluginManager* autopilotPluginManager,
            JoystickManager*        joystickManager);
65
    ~Vehicle();
dogmaphobic's avatar
dogmaphobic committed
66

67 68
    Q_PROPERTY(int                  id                      READ id                                     CONSTANT)
    Q_PROPERTY(AutoPilotPlugin*     autopilot               MEMBER _autopilotPlugin                     CONSTANT)
69 70 71 72 73 74 75 76 77 78 79 80
    Q_PROPERTY(QGeoCoordinate       coordinate              READ coordinate                             NOTIFY coordinateChanged)
    Q_PROPERTY(bool                 coordinateValid         READ coordinateValid                        NOTIFY coordinateValidChanged)
    Q_PROPERTY(MissionManager*      missionManager          MEMBER _missionManager                      CONSTANT)
    Q_PROPERTY(bool                 homePositionAvailable   READ homePositionAvailable                  NOTIFY homePositionAvailableChanged)
    Q_PROPERTY(QGeoCoordinate       homePosition            READ homePosition                           NOTIFY homePositionChanged)
    Q_PROPERTY(bool                 armed                   READ armed              WRITE setArmed      NOTIFY armedChanged)
    Q_PROPERTY(bool                 flightModeSetAvailable  READ flightModeSetAvailable                 CONSTANT)
    Q_PROPERTY(QStringList          flightModes             READ flightModes                            CONSTANT)
    Q_PROPERTY(QString              flightMode              READ flightMode         WRITE setFlightMode NOTIFY flightModeChanged)
    Q_PROPERTY(bool                 hilMode                 READ hilMode            WRITE setHilMode    NOTIFY hilModeChanged)
    Q_PROPERTY(bool                 missingParameters       READ missingParameters                      NOTIFY missingParametersChanged)
    Q_PROPERTY(QmlObjectListModel*  trajectoryPoints        READ trajectoryPoints                       CONSTANT)
81 82 83 84 85 86 87 88 89 90 91 92 93 94 95 96 97 98 99 100 101 102 103 104 105
    Q_PROPERTY(float                roll                    READ roll                                   NOTIFY rollChanged)
    Q_PROPERTY(float                pitch                   READ pitch                                  NOTIFY pitchChanged)
    Q_PROPERTY(float                heading                 READ heading                                NOTIFY headingChanged)
    Q_PROPERTY(float                groundSpeed             READ groundSpeed                            NOTIFY groundSpeedChanged)
    Q_PROPERTY(float                airSpeed                READ airSpeed                               NOTIFY airSpeedChanged)
    Q_PROPERTY(float                climbRate               READ climbRate                              NOTIFY climbRateChanged)
    Q_PROPERTY(float                altitudeRelative        READ altitudeRelative                       NOTIFY altitudeRelativeChanged)
    Q_PROPERTY(float                altitudeWGS84           READ altitudeWGS84                          NOTIFY altitudeWGS84Changed)
    Q_PROPERTY(float                altitudeAMSL            READ altitudeAMSL                           NOTIFY altitudeAMSLChanged)
    Q_PROPERTY(float                latitude                READ latitude                               NOTIFY coordinateChanged)
    Q_PROPERTY(float                longitude               READ longitude                              NOTIFY coordinateChanged)
    Q_PROPERTY(double               batteryVoltage          READ batteryVoltage                         NOTIFY batteryVoltageChanged)
    Q_PROPERTY(double               batteryPercent          READ batteryPercent                         NOTIFY batteryPercentChanged)
    Q_PROPERTY(double               batteryConsumed         READ batteryConsumed                        NOTIFY batteryConsumedChanged)
    Q_PROPERTY(int                  satelliteCount          READ satelliteCount                         NOTIFY satelliteCountChanged)
    Q_PROPERTY(QString              currentState            READ currentState                           NOTIFY currentStateChanged)
    Q_PROPERTY(int                  satelliteLock           READ satelliteLock                          NOTIFY satelliteLockChanged)
    Q_PROPERTY(unsigned int         heartbeatTimeout        READ heartbeatTimeout                       NOTIFY heartbeatTimeoutChanged)
    Q_PROPERTY(QmlObjectListModel*  missionItems            READ missionItemsModel                      CONSTANT)
    Q_PROPERTY(bool                 messageTypeNone         READ messageTypeNone                        NOTIFY messageTypeChanged)
    Q_PROPERTY(bool                 messageTypeNormal       READ messageTypeNormal                      NOTIFY messageTypeChanged)
    Q_PROPERTY(bool                 messageTypeWarning      READ messageTypeWarning                     NOTIFY messageTypeChanged)
    Q_PROPERTY(bool                 messageTypeError        READ messageTypeError                       NOTIFY messageTypeChanged)
    Q_PROPERTY(int                  newMessageCount         READ newMessageCount                        NOTIFY newMessageCountChanged)
    Q_PROPERTY(int                  messageCount            READ messageCount                           NOTIFY messageCountChanged)
dogmaphobic's avatar
dogmaphobic committed
106 107
    Q_PROPERTY(QString              formatedMessages        READ formatedMessages                       NOTIFY formatedMessagesChanged)
    Q_PROPERTY(QString              formatedMessage         READ formatedMessage                        NOTIFY formatedMessageChanged)
108 109 110 111
    Q_PROPERTY(QString              latestError             READ latestError                            NOTIFY latestErrorChanged)
    Q_PROPERTY(int                  joystickMode            READ joystickMode       WRITE setJoystickMode NOTIFY joystickModeChanged)
    Q_PROPERTY(QStringList          joystickModes           READ joystickModes                          CONSTANT)
    Q_PROPERTY(bool                 joystickEnabled         READ joystickEnabled    WRITE setJoystickEnabled NOTIFY joystickEnabledChanged)
dogmaphobic's avatar
dogmaphobic committed
112 113
    Q_PROPERTY(bool                 active                  READ active             WRITE setActive     NOTIFY activeChanged)
    Q_PROPERTY(int                  flowImageIndex          READ flowImageIndex                         NOTIFY flowImageIndexChanged)
114 115 116 117 118 119 120 121

    /// Returns the number of buttons which are reserved for firmware use in the MANUAL_CONTROL mavlink
    /// message. For example PX4 Flight Stack reserves the first 8 buttons to simulate rc switches.
    /// The remainder can be assigned to Vehicle actions.
    /// @return -1: reserver all buttons, >0 number of buttons to reserve
    Q_PROPERTY(int manualControlReservedButtonCount READ manualControlReservedButtonCount CONSTANT)

    Q_INVOKABLE QString     getMavIconColor();
Don Gagne's avatar
Don Gagne committed
122

dogmaphobic's avatar
dogmaphobic committed
123 124 125
    // Called when the message drop-down is invoked to clear current count
    Q_INVOKABLE void        resetMessages();

126
    // Property accessors
Don Gagne's avatar
Don Gagne committed
127

128 129
    QGeoCoordinate coordinate(void) { return _coordinate; }
    bool coordinateValid(void)      { return _coordinateValid; }
130
    QmlObjectListModel* missionItemsModel(void);
dogmaphobic's avatar
dogmaphobic committed
131 132


133
    typedef enum {
134
        JoystickModeRC,         ///< Joystick emulates an RC Transmitter
135 136 137 138 139 140
        JoystickModeAttitude,
        JoystickModePosition,
        JoystickModeForce,
        JoystickModeVelocity,
        JoystickModeMax
    } JoystickMode_t;
dogmaphobic's avatar
dogmaphobic committed
141

142 143
    int joystickMode(void);
    void setJoystickMode(int mode);
dogmaphobic's avatar
dogmaphobic committed
144

145 146
    /// List of joystick mode names
    QStringList joystickModes(void);
dogmaphobic's avatar
dogmaphobic committed
147

148 149
    bool joystickEnabled(void);
    void setJoystickEnabled(bool enabled);
dogmaphobic's avatar
dogmaphobic committed
150

151 152 153
    // Is vehicle active with respect to current active vehicle in QGC
    bool active(void);
    void setActive(bool active);
dogmaphobic's avatar
dogmaphobic committed
154

155 156 157
    // Property accesors
    int id(void) { return _id; }
    MAV_AUTOPILOT firmwareType(void) { return _firmwareType; }
158
    MAV_TYPE vehicleType(void) { return _vehicleType; }
dogmaphobic's avatar
dogmaphobic committed
159

160 161
    /// Sends this specified message to all links accociated with this vehicle
    void sendMessage(mavlink_message_t message);
dogmaphobic's avatar
dogmaphobic committed
162

163 164 165
    /// Sends the specified messages multiple times to the vehicle in order to attempt to
    /// guarantee that it makes it to the vehicle.
    void sendMessageMultiple(mavlink_message_t message);
dogmaphobic's avatar
dogmaphobic committed
166

167 168
    /// Provides access to uas from vehicle. Temporary workaround until UAS is fully phased out.
    UAS* uas(void) { return _uas; }
dogmaphobic's avatar
dogmaphobic committed
169

170 171
    /// Provides access to uas from vehicle. Temporary workaround until AutoPilotPlugin is fully phased out.
    AutoPilotPlugin* autopilotPlugin(void) { return _autopilotPlugin; }
dogmaphobic's avatar
dogmaphobic committed
172

Don Gagne's avatar
Don Gagne committed
173 174
    /// Provides access to the Firmware Plugin for this Vehicle
    FirmwarePlugin* firmwarePlugin(void) { return _firmwarePlugin; }
dogmaphobic's avatar
dogmaphobic committed
175

176
    QList<LinkInterface*> links(void);
dogmaphobic's avatar
dogmaphobic committed
177

178
    int manualControlReservedButtonCount(void);
dogmaphobic's avatar
dogmaphobic committed
179

Don Gagne's avatar
Don Gagne committed
180
    MissionManager* missionManager(void) { return _missionManager; }
dogmaphobic's avatar
dogmaphobic committed
181

182 183
    bool homePositionAvailable(void);
    QGeoCoordinate homePosition(void);
dogmaphobic's avatar
dogmaphobic committed
184

Don Gagne's avatar
Don Gagne committed
185 186 187 188 189 190 191 192 193 194
    bool armed(void) { return _armed; }
    void setArmed(bool armed);

    bool flightModeSetAvailable(void);
    QStringList flightModes(void);
    QString flightMode(void);
    void setFlightMode(const QString& flightMode);

    bool hilMode(void);
    void setHilMode(bool hilMode);
dogmaphobic's avatar
dogmaphobic committed
195

196
    QmlObjectListModel* trajectoryPoints(void) { return &_mapTrajectoryList; }
dogmaphobic's avatar
dogmaphobic committed
197 198 199

    int  flowImageIndex() { return _flowImageIndex; }

200 201 202 203
    /// Requests the specified data stream from the vehicle
    ///     @param stream Stream which is being requested
    ///     @param rate Rate at which to send stream in Hz
    void requestDataStream(MAV_DATA_STREAM stream, uint16_t rate);
dogmaphobic's avatar
dogmaphobic committed
204

205
    bool missingParameters(void);
dogmaphobic's avatar
dogmaphobic committed
206

207 208 209 210 211 212
    typedef enum {
        MessageNone,
        MessageNormal,
        MessageWarning,
        MessageError
    } MessageType_t;
dogmaphobic's avatar
dogmaphobic committed
213

214 215 216 217 218 219 220 221 222 223 224
    enum {
        ROLL_CHANGED,
        PITCH_CHANGED,
        HEADING_CHANGED,
        GROUNDSPEED_CHANGED,
        AIRSPEED_CHANGED,
        CLIMBRATE_CHANGED,
        ALTITUDERELATIVE_CHANGED,
        ALTITUDEWGS84_CHANGED,
        ALTITUDEAMSL_CHANGED
    };
dogmaphobic's avatar
dogmaphobic committed
225

226 227 228 229 230 231
    bool            messageTypeNone     () { return _currentMessageType == MessageNone; }
    bool            messageTypeNormal   () { return _currentMessageType == MessageNormal; }
    bool            messageTypeWarning  () { return _currentMessageType == MessageWarning; }
    bool            messageTypeError    () { return _currentMessageType == MessageError; }
    int             newMessageCount     () { return _currentMessageCount; }
    int             messageCount        () { return _messageCount; }
dogmaphobic's avatar
dogmaphobic committed
232 233
    QString         formatedMessages    ();
    QString         formatedMessage     () { return _formatedMessage; }
234 235 236 237 238 239 240 241 242 243
    QString         latestError         () { return _latestError; }
    float           roll                () { return _roll; }
    float           pitch               () { return _pitch; }
    float           heading             () { return _heading; }
    float           groundSpeed         () { return _groundSpeed; }
    float           airSpeed            () { return _airSpeed; }
    float           climbRate           () { return _climbRate; }
    float           altitudeRelative    () { return _altitudeRelative; }
    float           altitudeWGS84       () { return _altitudeWGS84; }
    float           altitudeAMSL        () { return _altitudeAMSL; }
244 245
    float           latitude            () { return _coordinate.latitude(); }
    float           longitude           () { return _coordinate.longitude(); }
246 247 248 249 250 251 252 253
    bool            mavPresent          () { return _mav != NULL; }
    int             satelliteCount      () { return _satelliteCount; }
    double          batteryVoltage      () { return _batteryVoltage; }
    double          batteryPercent      () { return _batteryPercent; }
    double          batteryConsumed     () { return _batteryConsumed; }
    QString         currentState        () { return _currentState; }
    int             satelliteLock       () { return _satelliteLock; }
    unsigned int    heartbeatTimeout    () { return _currentHeartbeatTimeout; }
254 255

    ParameterLoader* getParameterLoader(void);
dogmaphobic's avatar
dogmaphobic committed
256

257 258 259
public slots:
    void setLatitude(double latitude);
    void setLongitude(double longitude);
dogmaphobic's avatar
dogmaphobic committed
260

261
signals:
262
    void allLinksDisconnected(Vehicle* vehicle);
263
    void coordinateChanged(QGeoCoordinate coordinate);
264
    void coordinateValidChanged(bool coordinateValid);
265
    void joystickModeChanged(int mode);
266 267
    void joystickEnabledChanged(bool enabled);
    void activeChanged(bool active);
Don Gagne's avatar
Don Gagne committed
268
    void mavlinkMessageReceived(const mavlink_message_t& message);
269 270
    void homePositionAvailableChanged(bool homePositionAvailable);
    void homePositionChanged(const QGeoCoordinate& homePosition);
Don Gagne's avatar
Don Gagne committed
271 272 273
    void armedChanged(bool armed);
    void flightModeChanged(const QString& flightMode);
    void hilModeChanged(bool hilMode);
274
    void missingParametersChanged(bool missingParameters);
dogmaphobic's avatar
dogmaphobic committed
275

276 277
    /// Used internally to move sendMessage call to main thread
    void _sendMessageOnThread(mavlink_message_t message);
dogmaphobic's avatar
dogmaphobic committed
278

279 280 281
    void messageTypeChanged     ();
    void newMessageCountChanged ();
    void messageCountChanged    ();
dogmaphobic's avatar
dogmaphobic committed
282 283
    void formatedMessagesChanged();
    void formatedMessageChanged ();
284 285 286 287 288 289 290 291 292 293 294 295 296 297 298 299 300 301 302
    void latestErrorChanged     ();
    void rollChanged            ();
    void pitchChanged           ();
    void headingChanged         ();
    void groundSpeedChanged     ();
    void airSpeedChanged        ();
    void climbRateChanged       ();
    void altitudeRelativeChanged();
    void altitudeWGS84Changed   ();
    void altitudeAMSLChanged    ();
    void longitudeChanged       ();
    void batteryVoltageChanged  ();
    void batteryPercentChanged  ();
    void batteryConsumedChanged ();
    void heartbeatTimeoutChanged();
    void currentConfigChanged   ();
    void satelliteCountChanged  ();
    void currentStateChanged    ();
    void satelliteLockChanged   ();
dogmaphobic's avatar
dogmaphobic committed
303 304
    void flowImageIndexChanged  ();

305 306 307 308
private slots:
    void _mavlinkMessageReceived(LinkInterface* link, mavlink_message_t message);
    void _linkDisconnected(LinkInterface* link);
    void _sendMessage(mavlink_message_t message);
309
    void _sendMessageMultipleNext(void);
310
    void _addNewMapTrajectoryPoint(void);
311
    void _parametersReady(bool parametersReady);
312
    void _communicationInactivityTimedOut(void);
313

314
    void _handleTextMessage                 (int newCount);
dogmaphobic's avatar
dogmaphobic committed
315
    void _handletextMessageReceived         (UASMessage* message);
316 317 318 319 320 321 322 323 324 325 326 327 328 329 330
    /** @brief Attitude from main autopilot / system state */
    void _updateAttitude                    (UASInterface* uas, double roll, double pitch, double yaw, quint64 timestamp);
    /** @brief Attitude from one specific component / redundant autopilot */
    void _updateAttitude                    (UASInterface* uas, int component, double roll, double pitch, double yaw, quint64 timestamp);
    void _updateSpeed                       (UASInterface* uas, double _groundSpeed, double _airSpeed, quint64 timestamp);
    void _updateAltitude                    (UASInterface* uas, double _altitudeAMSL, double _altitudeWGS84, double _altitudeRelative, double _climbRate, quint64 timestamp);
    void _updateNavigationControllerErrors  (UASInterface* uas, double altitudeError, double speedError, double xtrackError);
    void _updateNavigationControllerData    (UASInterface *uas, float navRoll, float navPitch, float navBearing, float targetBearing, float targetDistance);
    void _checkUpdate                       ();
    void _updateBatteryRemaining            (UASInterface*, double voltage, double, double percent, int);
    void _updateBatteryConsumedChanged      (UASInterface*, double current_consumed);
    void _updateState                       (UASInterface* system, QString name, QString description);
    void _heartbeatTimeout                  (bool timeout, unsigned int ms);
    void _setSatelliteCount                 (double val, QString name);
    void _setSatLoc                         (UASInterface* uas, int fix);
dogmaphobic's avatar
dogmaphobic committed
331 332
    /** @brief A new camera image has arrived */
    void _imageReady                        (UASInterface* uas);
333

334 335 336
private:
    bool _containsLink(LinkInterface* link);
    void _addLink(LinkInterface* link);
337 338
    void _loadSettings(void);
    void _saveSettings(void);
339
    void _startJoystick(bool start);
Don Gagne's avatar
Don Gagne committed
340 341
    void _handleHomePosition(mavlink_message_t& message);
    void _handleHeartbeat(mavlink_message_t& message);
342
    void _missionManagerError(int errorCode, const QString& errorMsg);
343 344
    void _mapTrajectoryStart(void);
    void _mapTrajectoryStop(void);
Don Gagne's avatar
Don Gagne committed
345

346 347
    void    _addChange                      (int id);
    float   _oneDecimal                     (float value);
348

349
private:
350 351
    int     _id;            ///< Mavlink system id
    bool    _active;
dogmaphobic's avatar
dogmaphobic committed
352

353
    MAV_AUTOPILOT       _firmwareType;
354
    MAV_TYPE            _vehicleType;
355 356
    FirmwarePlugin*     _firmwarePlugin;
    AutoPilotPlugin*    _autopilotPlugin;
Don Gagne's avatar
Don Gagne committed
357
    MAVLinkProtocol*    _mavlink;
dogmaphobic's avatar
dogmaphobic committed
358

359 360 361 362
    /// List of all links associated with this vehicle. We keep SharedLinkInterface objects
    /// which are QSharedPointer's in order to maintain reference counts across threads.
    /// This way Link deletion works correctly.
    QList<SharedLinkInterface> _links;
dogmaphobic's avatar
dogmaphobic committed
363

364
    JoystickMode_t  _joystickMode;
365
    bool            _joystickEnabled;
dogmaphobic's avatar
dogmaphobic committed
366

367
    UAS* _uas;
dogmaphobic's avatar
dogmaphobic committed
368

369 370
    QGeoCoordinate  _coordinate;
    bool            _coordinateValid;       ///< true: vehicle has 3d lock and therefore valid location
dogmaphobic's avatar
dogmaphobic committed
371

372 373
    bool            _homePositionAvailable;
    QGeoCoordinate  _homePosition;
dogmaphobic's avatar
dogmaphobic committed
374

375 376 377 378 379 380 381 382 383 384 385 386 387 388 389 390 391 392 393 394 395 396 397 398 399 400 401 402 403 404 405
    UASInterface*   _mav;
    int             _currentMessageCount;
    int             _messageCount;
    int             _currentErrorCount;
    int             _currentWarningCount;
    int             _currentNormalCount;
    MessageType_t   _currentMessageType;
    QString         _latestError;
    float           _roll;
    float           _pitch;
    float           _heading;
    float           _altitudeAMSL;
    float           _altitudeWGS84;
    float           _altitudeRelative;
    float           _groundSpeed;
    float           _airSpeed;
    float           _climbRate;
    float           _navigationAltitudeError;
    float           _navigationSpeedError;
    float           _navigationCrosstrackError;
    float           _navigationTargetBearing;
    QTimer*         _refreshTimer;
    QList<int>      _changes;
    double          _batteryVoltage;
    double          _batteryPercent;
    double          _batteryConsumed;
    QString         _currentState;
    unsigned int    _currentHeartbeatTimeout;
    int             _satelliteCount;
    int             _satelliteLock;
    int             _updateCount;
dogmaphobic's avatar
dogmaphobic committed
406
    QString         _formatedMessage;
dogmaphobic's avatar
dogmaphobic committed
407

Don Gagne's avatar
Don Gagne committed
408
    MissionManager*     _missionManager;
409
    bool                _missionManagerInitialRequestComplete;
410 411

    ParameterLoader*    _parameterLoader;
dogmaphobic's avatar
dogmaphobic committed
412

Don Gagne's avatar
Don Gagne committed
413 414 415
    bool    _armed;         ///< true: vehicle is armed
    uint8_t _base_mode;     ///< base_mode from HEARTBEAT
    uint32_t _custom_mode;  ///< custom_mode from HEARTBEAT
416 417 418 419 420 421

    /// Used to store a message being sent by sendMessageMultiple
    typedef struct {
        mavlink_message_t   message;    ///< Message to send multiple times
        int                 retryCount; ///< Number of retries left
    } SendMessageMultipleInfo_t;
dogmaphobic's avatar
dogmaphobic committed
422

423
    QList<SendMessageMultipleInfo_t> _sendMessageMultipleList;    ///< List of messages being sent multiple times
dogmaphobic's avatar
dogmaphobic committed
424

425 426
    static const int _sendMessageMultipleRetries = 5;
    static const int _sendMessageMultipleIntraMessageDelay = 500;
dogmaphobic's avatar
dogmaphobic committed
427

428 429
    QTimer  _sendMultipleTimer;
    int     _nextSendMessageMultipleIndex;
dogmaphobic's avatar
dogmaphobic committed
430

431 432 433 434 435
    QTimer              _mapTrajectoryTimer;
    QmlObjectListModel  _mapTrajectoryList;
    QGeoCoordinate      _mapTrajectoryLastCoordinate;
    bool                _mapTrajectoryHaveFirstCoordinate;
    static const int    _mapTrajectoryMsecsBetweenPoints = 1000;
436 437 438 439

    QTimer              _communicationInactivityTimer;
    int                 _communicationInactivityTimeoutMSecs;
    static const int    _communicationInactivityTimeoutMSecsDefault = 30 * 1000;
440

dogmaphobic's avatar
dogmaphobic committed
441 442 443 444 445 446
    FirmwarePluginManager*      _firmwarePluginManager;
    AutoPilotPluginManager*     _autopilotPluginManager;
    JoystickManager*            _joystickManager;

    int                         _flowImageIndex;

447
    // Settings keys
448 449
    static const char* _settingsGroup;
    static const char* _joystickModeSettingsKey;
450
    static const char* _joystickEnabledSettingsKey;
451
    static const char* _communicationInactivityKey;
452 453
};
#endif