Vehicle.h 46 KB
Newer Older
1 2 3 4 5 6 7 8
/****************************************************************************
 *
 *   (c) 2009-2016 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org>
 *
 * QGroundControl is licensed according to the terms in the file
 * COPYING.md in the root of the source code directory.
 *
 ****************************************************************************/
dogmaphobic's avatar
dogmaphobic committed
9

10 11 12 13 14 15 16 17

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

#ifndef Vehicle_H
#define Vehicle_H

#include <QObject>
18
#include <QGeoCoordinate>
19
#include <QElapsedTimer>
20

Don Gagne's avatar
Don Gagne committed
21
#include "FactGroup.h"
22 23
#include "LinkInterface.h"
#include "QGCMAVLink.h"
24
#include "QmlObjectListModel.h"
Don Gagne's avatar
Don Gagne committed
25
#include "MAVLinkProtocol.h"
dogmaphobic's avatar
dogmaphobic committed
26
#include "UASMessageHandler.h"
27
#include "SettingsFact.h"
28

29 30
class UAS;
class UASInterface;
31
class FirmwarePlugin;
32
class FirmwarePluginManager;
33
class AutoPilotPlugin;
Don Gagne's avatar
Don Gagne committed
34
class MissionManager;
35
class GeoFenceManager;
36
class RallyPointManager;
37
class ParameterManager;
38
class JoystickManager;
dogmaphobic's avatar
dogmaphobic committed
39
class UASMessage;
40 41 42

Q_DECLARE_LOGGING_CATEGORY(VehicleLog)

Don Gagne's avatar
Don Gagne committed
43 44
class Vehicle;

45 46 47 48 49 50 51 52 53 54 55 56 57 58
class VehicleVibrationFactGroup : public FactGroup
{
    Q_OBJECT

public:
    VehicleVibrationFactGroup(QObject* parent = NULL);

    Q_PROPERTY(Fact* xAxis      READ xAxis      CONSTANT)
    Q_PROPERTY(Fact* yAxis      READ yAxis      CONSTANT)
    Q_PROPERTY(Fact* zAxis      READ zAxis      CONSTANT)
    Q_PROPERTY(Fact* clipCount1 READ clipCount1 CONSTANT)
    Q_PROPERTY(Fact* clipCount2 READ clipCount2 CONSTANT)
    Q_PROPERTY(Fact* clipCount3 READ clipCount3 CONSTANT)

59 60 61 62 63 64
    Fact* xAxis         (void) { return &_xAxisFact; }
    Fact* yAxis         (void) { return &_yAxisFact; }
    Fact* zAxis         (void) { return &_zAxisFact; }
    Fact* clipCount1    (void) { return &_clipCount1Fact; }
    Fact* clipCount2    (void) { return &_clipCount2Fact; }
    Fact* clipCount3    (void) { return &_clipCount3Fact; }
65 66 67 68 69 70 71 72 73 74 75 76 77 78 79 80 81

    static const char* _xAxisFactName;
    static const char* _yAxisFactName;
    static const char* _zAxisFactName;
    static const char* _clipCount1FactName;
    static const char* _clipCount2FactName;
    static const char* _clipCount3FactName;

private:
    Fact        _xAxisFact;
    Fact        _yAxisFact;
    Fact        _zAxisFact;
    Fact        _clipCount1Fact;
    Fact        _clipCount2Fact;
    Fact        _clipCount3Fact;
};

Don Gagne's avatar
Don Gagne committed
82 83 84 85 86 87 88 89 90 91 92
class VehicleWindFactGroup : public FactGroup
{
    Q_OBJECT

public:
    VehicleWindFactGroup(QObject* parent = NULL);

    Q_PROPERTY(Fact* direction      READ direction      CONSTANT)
    Q_PROPERTY(Fact* speed          READ speed          CONSTANT)
    Q_PROPERTY(Fact* verticalSpeed  READ verticalSpeed  CONSTANT)

93 94 95
    Fact* direction     (void) { return &_directionFact; }
    Fact* speed         (void) { return &_speedFact; }
    Fact* verticalSpeed (void) { return &_verticalSpeedFact; }
Don Gagne's avatar
Don Gagne committed
96 97 98 99 100 101 102 103 104 105 106

    static const char* _directionFactName;
    static const char* _speedFactName;
    static const char* _verticalSpeedFactName;

private:
    Fact        _directionFact;
    Fact        _speedFact;
    Fact        _verticalSpeedFact;
};

Don Gagne's avatar
Don Gagne committed
107 108 109 110 111 112 113 114 115 116 117 118 119
class VehicleGPSFactGroup : public FactGroup
{
    Q_OBJECT

public:
    VehicleGPSFactGroup(QObject* parent = NULL);

    Q_PROPERTY(Fact* hdop               READ hdop               CONSTANT)
    Q_PROPERTY(Fact* vdop               READ vdop               CONSTANT)
    Q_PROPERTY(Fact* courseOverGround   READ courseOverGround   CONSTANT)
    Q_PROPERTY(Fact* count              READ count              CONSTANT)
    Q_PROPERTY(Fact* lock               READ lock               CONSTANT)

120 121 122 123 124
    Fact* hdop              (void) { return &_hdopFact; }
    Fact* vdop              (void) { return &_vdopFact; }
    Fact* courseOverGround  (void) { return &_courseOverGroundFact; }
    Fact* count             (void) { return &_countFact; }
    Fact* lock              (void) { return &_lockFact; }
Don Gagne's avatar
Don Gagne committed
125

Don Gagne's avatar
Don Gagne committed
126 127 128 129 130 131
    static const char* _hdopFactName;
    static const char* _vdopFactName;
    static const char* _courseOverGroundFactName;
    static const char* _countFactName;
    static const char* _lockFactName;

Don Gagne's avatar
Don Gagne committed
132 133 134 135 136 137
private:
    Fact        _hdopFact;
    Fact        _vdopFact;
    Fact        _courseOverGroundFact;
    Fact        _countFact;
    Fact        _lockFact;
Don Gagne's avatar
Don Gagne committed
138
};
Don Gagne's avatar
Don Gagne committed
139

Don Gagne's avatar
Don Gagne committed
140 141 142 143 144 145 146 147 148 149 150 151
class VehicleBatteryFactGroup : public FactGroup
{
    Q_OBJECT

public:
    VehicleBatteryFactGroup(QObject* parent = NULL);

    Q_PROPERTY(Fact* voltage            READ voltage            CONSTANT)
    Q_PROPERTY(Fact* percentRemaining   READ percentRemaining   CONSTANT)
    Q_PROPERTY(Fact* mahConsumed        READ mahConsumed        CONSTANT)
    Q_PROPERTY(Fact* current            READ current            CONSTANT)
    Q_PROPERTY(Fact* temperature        READ temperature        CONSTANT)
152 153 154 155 156 157 158 159
    Q_PROPERTY(Fact* cellCount          READ cellCount          CONSTANT)

    Fact* voltage                   (void) { return &_voltageFact; }
    Fact* percentRemaining          (void) { return &_percentRemainingFact; }
    Fact* mahConsumed               (void) { return &_mahConsumedFact; }
    Fact* current                   (void) { return &_currentFact; }
    Fact* temperature               (void) { return &_temperatureFact; }
    Fact* cellCount                 (void) { return &_cellCountFact; }
Don Gagne's avatar
Don Gagne committed
160 161 162 163 164 165 166 167 168


    static const char* _voltageFactName;
    static const char* _percentRemainingFactName;
    static const char* _mahConsumedFactName;
    static const char* _currentFactName;
    static const char* _temperatureFactName;
    static const char* _cellCountFactName;

169 170
    static const char* _settingsGroup;

Don Gagne's avatar
Don Gagne committed
171 172 173 174 175 176 177 178
    static const double _voltageUnavailable;
    static const int    _percentRemainingUnavailable;
    static const int    _mahConsumedUnavailable;
    static const int    _currentUnavailable;
    static const double _temperatureUnavailable;
    static const int    _cellCountUnavailable;

private:
179 180 181 182 183 184
    Fact            _voltageFact;
    Fact            _percentRemainingFact;
    Fact            _mahConsumedFact;
    Fact            _currentFact;
    Fact            _temperatureFact;
    Fact            _cellCountFact;
Don Gagne's avatar
Don Gagne committed
185 186 187
};

class Vehicle : public FactGroup
188 189
{
    Q_OBJECT
dogmaphobic's avatar
dogmaphobic committed
190

191
public:
192 193
    Vehicle(LinkInterface*          link,
            int                     vehicleId,
194
            int                     defaultComponentId,
195 196 197 198
            MAV_AUTOPILOT           firmwareType,
            MAV_TYPE                vehicleType,
            FirmwarePluginManager*  firmwarePluginManager,
            JoystickManager*        joystickManager);
199

200 201 202 203 204
    // The following is used to create a disconnected Vehicle for use while offline editing.
    Vehicle(MAV_AUTOPILOT           firmwareType,
            MAV_TYPE                vehicleType,
            FirmwarePluginManager*  firmwarePluginManager,
            QObject*                parent = NULL);
205

206
    ~Vehicle();
dogmaphobic's avatar
dogmaphobic committed
207

208 209 210 211 212 213 214 215 216 217 218 219 220 221 222 223 224 225 226 227 228 229 230 231 232 233 234 235 236
    Q_PROPERTY(int                  id                      READ id                                                     CONSTANT)
    Q_PROPERTY(AutoPilotPlugin*     autopilot               MEMBER _autopilotPlugin                                     CONSTANT)
    Q_PROPERTY(QGeoCoordinate       coordinate              READ coordinate                                             NOTIFY coordinateChanged)
    Q_PROPERTY(bool                 coordinateValid         READ coordinateValid                                        NOTIFY coordinateValidChanged)
    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(QmlObjectListModel*  trajectoryPoints        READ trajectoryPoints                                       CONSTANT)
    Q_PROPERTY(float                latitude                READ latitude                                               NOTIFY coordinateChanged)
    Q_PROPERTY(float                longitude               READ longitude                                              NOTIFY coordinateChanged)
    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)
    Q_PROPERTY(QString              formatedMessages        READ formatedMessages                                       NOTIFY formatedMessagesChanged)
    Q_PROPERTY(QString              formatedMessage         READ formatedMessage                                        NOTIFY formatedMessageChanged)
    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)
    Q_PROPERTY(bool                 active                  READ active                 WRITE setActive                 NOTIFY activeChanged)
    Q_PROPERTY(int                  flowImageIndex          READ flowImageIndex                                         NOTIFY flowImageIndexChanged)
    Q_PROPERTY(int                  rcRSSI                  READ rcRSSI                                                 NOTIFY rcRSSIChanged)
237 238
    Q_PROPERTY(bool                 px4Firmware             READ px4Firmware                                            NOTIFY firmwareTypeChanged)
    Q_PROPERTY(bool                 apmFirmware             READ apmFirmware                                            NOTIFY firmwareTypeChanged)
239 240 241 242 243 244 245
    Q_PROPERTY(bool                 soloFirmware            READ soloFirmware           WRITE setSoloFirmware           NOTIFY soloFirmwareChanged)
    Q_PROPERTY(bool                 genericFirmware         READ genericFirmware                                        CONSTANT)
    Q_PROPERTY(bool                 connectionLost          READ connectionLost                                         NOTIFY connectionLostChanged)
    Q_PROPERTY(bool                 connectionLostEnabled   READ connectionLostEnabled  WRITE setConnectionLostEnabled  NOTIFY connectionLostEnabledChanged)
    Q_PROPERTY(uint                 messagesReceived        READ messagesReceived                                       NOTIFY messagesReceivedChanged)
    Q_PROPERTY(uint                 messagesSent            READ messagesSent                                           NOTIFY messagesSentChanged)
    Q_PROPERTY(uint                 messagesLost            READ messagesLost                                           NOTIFY messagesLostChanged)
246 247 248 249 250
    Q_PROPERTY(bool                 fixedWing               READ fixedWing                                              NOTIFY vehicleTypeChanged)
    Q_PROPERTY(bool                 multiRotor              READ multiRotor                                             NOTIFY vehicleTypeChanged)
    Q_PROPERTY(bool                 vtol                    READ vtol                                                   NOTIFY vehicleTypeChanged)
    Q_PROPERTY(bool                 rover                   READ rover                                                  NOTIFY vehicleTypeChanged)
    Q_PROPERTY(bool                 sub                     READ sub                                                    NOTIFY vehicleTypeChanged)
251
    Q_PROPERTY(bool                 supportsManualControl   READ supportsManualControl                                  CONSTANT)
252
    Q_PROPERTY(bool        supportsThrottleModeCenterZero   READ supportsThrottleModeCenterZero                         CONSTANT)
253
    Q_PROPERTY(bool                 supportsJSButton        READ supportsJSButton                                       CONSTANT)
254
    Q_PROPERTY(bool                 supportsRadio           READ supportsRadio                                          CONSTANT)
255 256
    Q_PROPERTY(bool                 autoDisconnect          MEMBER _autoDisconnect                                      NOTIFY autoDisconnectChanged)
    Q_PROPERTY(QString              prearmError             READ prearmError            WRITE setPrearmError            NOTIFY prearmErrorChanged)
Don Gagne's avatar
Don Gagne committed
257 258 259
    Q_PROPERTY(int                  motorCount              READ motorCount                                             CONSTANT)
    Q_PROPERTY(bool                 coaxialMotors           READ coaxialMotors                                          CONSTANT)
    Q_PROPERTY(bool                 xConfigMotors           READ xConfigMotors                                          CONSTANT)
260
    Q_PROPERTY(bool                 isOfflineEditingVehicle READ isOfflineEditingVehicle                                CONSTANT)
261
    Q_PROPERTY(QString              brandImage              READ brandImage                                             NOTIFY firmwareTypeChanged)
262
    Q_PROPERTY(QStringList          unhealthySensors        READ unhealthySensors                                       NOTIFY unhealthySensorsChanged)
263 264 265
    Q_PROPERTY(QString              missionFlightMode       READ missionFlightMode                                      CONSTANT)
    Q_PROPERTY(QString              rtlFlightMode           READ rtlFlightMode                                          CONSTANT)
    Q_PROPERTY(QString              takeControlFlightMode   READ takeControlFlightMode                                  CONSTANT)
266 267
    Q_PROPERTY(QString              firmwareTypeString      READ firmwareTypeString                                     NOTIFY firmwareTypeChanged)
    Q_PROPERTY(QString              vehicleTypeString       READ vehicleTypeString                                      NOTIFY vehicleTypeChanged)
268 269 270
    Q_PROPERTY(QString              vehicleImageOpaque      READ vehicleImageOpaque                                     CONSTANT)
    Q_PROPERTY(QString              vehicleImageOutline     READ vehicleImageOutline                                    CONSTANT)
    Q_PROPERTY(QString              vehicleImageCompass     READ vehicleImageCompass                                    CONSTANT)
Gus Grubba's avatar
Gus Grubba committed
271 272 273 274 275 276 277
    Q_PROPERTY(int                  telemetryRRSSI          READ telemetryRRSSI                                         NOTIFY telemetryRRSSIChanged)
    Q_PROPERTY(int                  telemetryLRSSI          READ telemetryLRSSI                                         NOTIFY telemetryLRSSIChanged)
    Q_PROPERTY(unsigned int         telemetryRXErrors       READ telemetryRXErrors                                      NOTIFY telemetryRXErrorsChanged)
    Q_PROPERTY(unsigned int         telemetryFixed          READ telemetryFixed                                         NOTIFY telemetryFixedChanged)
    Q_PROPERTY(unsigned int         telemetryTXBuffer       READ telemetryTXBuffer                                      NOTIFY telemetryTXBufferChanged)
    Q_PROPERTY(unsigned int         telemetryLNoise         READ telemetryLNoise                                        NOTIFY telemetryLNoiseChanged)
    Q_PROPERTY(unsigned int         telemetryRNoise         READ telemetryRNoise                                        NOTIFY telemetryRNoiseChanged)
278

Don Gagne's avatar
Don Gagne committed
279 280 281 282 283 284 285 286 287 288 289 290
    /// true: Vehicle is flying, false: Vehicle is on ground
    Q_PROPERTY(bool flying      READ flying     WRITE setFlying     NOTIFY flyingChanged)

    /// true: Vehicle is in Guided mode and can respond to guided commands, false: vehicle cannot respond to direct control commands
    Q_PROPERTY(bool guidedMode  READ guidedMode WRITE setGuidedMode NOTIFY guidedModeChanged)

    /// true: Guided mode commands are supported by this vehicle
    Q_PROPERTY(bool guidedModeSupported READ guidedModeSupported CONSTANT)

    /// true: pauseVehicle command is supported
    Q_PROPERTY(bool pauseVehicleSupported READ pauseVehicleSupported CONSTANT)

291 292 293
    /// true: Orbit mode is supported by this vehicle
    Q_PROPERTY(bool orbitModeSupported READ orbitModeSupported CONSTANT)

294 295
    Q_PROPERTY(ParameterManager* parameterManager READ parameterManager CONSTANT)

Don Gagne's avatar
Don Gagne committed
296 297 298 299 300 301 302 303 304 305 306
    // FactGroup object model properties

    Q_PROPERTY(Fact* roll               READ roll               CONSTANT)
    Q_PROPERTY(Fact* pitch              READ pitch              CONSTANT)
    Q_PROPERTY(Fact* heading            READ heading            CONSTANT)
    Q_PROPERTY(Fact* groundSpeed        READ groundSpeed        CONSTANT)
    Q_PROPERTY(Fact* airSpeed           READ airSpeed           CONSTANT)
    Q_PROPERTY(Fact* climbRate          READ climbRate          CONSTANT)
    Q_PROPERTY(Fact* altitudeRelative   READ altitudeRelative   CONSTANT)
    Q_PROPERTY(Fact* altitudeAMSL       READ altitudeAMSL       CONSTANT)

Don Gagne's avatar
Don Gagne committed
307 308
    Q_PROPERTY(FactGroup* gps       READ gpsFactGroup       CONSTANT)
    Q_PROPERTY(FactGroup* battery   READ batteryFactGroup   CONSTANT)
309 310
    Q_PROPERTY(FactGroup* wind      READ windFactGroup      CONSTANT)
    Q_PROPERTY(FactGroup* vibration READ vibrationFactGroup CONSTANT)
Don Gagne's avatar
Don Gagne committed
311

312 313 314 315 316 317
    Q_PROPERTY(int firmwareMajorVersion READ firmwareMajorVersion NOTIFY firmwareMajorVersionChanged)
    Q_PROPERTY(int firmwareMinorVersion READ firmwareMinorVersion NOTIFY firmwareMinorVersionChanged)
    Q_PROPERTY(int firmwarePatchVersion READ firmwarePatchVersion NOTIFY firmwarePatchVersionChanged)
    Q_PROPERTY(int firmwareVersionType READ firmwareVersionType NOTIFY firmwareVersionTypeChanged)
    Q_PROPERTY(QString firmwareVersionTypeString READ firmwareVersionTypeString NOTIFY firmwareVersionTypeChanged)

318 319
    /// Resets link status counters
    Q_INVOKABLE void resetCounters  ();
320 321 322 323 324 325 326 327

    /// 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
328

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

Don Gagne's avatar
Don Gagne committed
332
    Q_INVOKABLE void virtualTabletJoystickValue(double roll, double pitch, double yaw, double thrust);
Don Gagne's avatar
Don Gagne committed
333
    Q_INVOKABLE void disconnectInactiveVehicle(void);
Don Gagne's avatar
Don Gagne committed
334

335 336
    Q_INVOKABLE void clearTrajectoryPoints(void);

Don Gagne's avatar
Don Gagne committed
337 338 339 340 341 342 343 344 345 346 347 348 349 350 351
    /// Command vehicle to return to launch
    Q_INVOKABLE void guidedModeRTL(void);

    /// Command vehicle to land at current location
    Q_INVOKABLE void guidedModeLand(void);

    /// Command vehicle to takeoff from current location
    Q_INVOKABLE void guidedModeTakeoff(double altitudeRel);

    /// Command vehicle to move to specified location (altitude is included and relative)
    Q_INVOKABLE void guidedModeGotoLocation(const QGeoCoordinate& gotoCoord);

    /// Command vehicle to change to the specified relatice altitude
    Q_INVOKABLE void guidedModeChangeAltitude(double altitudeRel);

352 353 354 355 356 357 358
    /// Command vehicle to orbit given center point
    ///     @param centerCoord Center Coordinates
    ///     @param radius Distance from vehicle to centerCoord
    ///     @param velocity Orbit velocity (positive CW, negative CCW)
    ///     @param altitude Desired Vehicle Altitude
    Q_INVOKABLE void guidedModeOrbit(const QGeoCoordinate& centerCoord = QGeoCoordinate(), double radius = NAN, double velocity = NAN, double altitude = NAN);

Don Gagne's avatar
Don Gagne committed
359 360 361 362 363 364 365
    /// Command vehicle to pause at current location. If vehicle supports guide mode, vehicle will be left
    /// in guided mode after pause.
    Q_INVOKABLE void pauseVehicle(void);

    /// Command vehicle to kill all motors no matter what state
    Q_INVOKABLE void emergencyStop(void);

366 367 368
    /// Alter the current mission item on the vehicle
    Q_INVOKABLE void setCurrentMissionSequence(int seq);

369 370 371
    /// Reboot vehicle
    Q_INVOKABLE void rebootVehicle();

dogmaphobic's avatar
dogmaphobic committed
372 373 374
    /// Clear Messages
    Q_INVOKABLE void clearMessages();

Don Gagne's avatar
Don Gagne committed
375 376
#if 0
    // Temporarily removed, waiting for new command implementation
Don Gagne's avatar
Don Gagne committed
377 378 379 380 381
    /// Test motor
    ///     @param motor Motor number, 1-based
    ///     @param percent 0-no power, 100-full power
    ///     @param timeoutSecs Number of seconds for motor to run
    Q_INVOKABLE void motorTest(int motor, int percent, int timeoutSecs);
Don Gagne's avatar
Don Gagne committed
382
#endif
Don Gagne's avatar
Don Gagne committed
383

Don Gagne's avatar
Don Gagne committed
384 385
    bool guidedModeSupported(void) const;
    bool pauseVehicleSupported(void) const;
386
    bool orbitModeSupported(void) const;
Don Gagne's avatar
Don Gagne committed
387

388
    // Property accessors
Don Gagne's avatar
Don Gagne committed
389

390 391
    QGeoCoordinate coordinate(void) { return _coordinate; }
    bool coordinateValid(void)      { return _coordinateValid; }
Don Gagne's avatar
Don Gagne committed
392
    void _setCoordinateValid(bool coordinateValid);
dogmaphobic's avatar
dogmaphobic committed
393

394
    typedef enum {
395
        JoystickModeRC,         ///< Joystick emulates an RC Transmitter
396 397 398 399 400 401
        JoystickModeAttitude,
        JoystickModePosition,
        JoystickModeForce,
        JoystickModeVelocity,
        JoystickModeMax
    } JoystickMode_t;
dogmaphobic's avatar
dogmaphobic committed
402

403 404
    int joystickMode(void);
    void setJoystickMode(int mode);
dogmaphobic's avatar
dogmaphobic committed
405

406 407
    /// List of joystick mode names
    QStringList joystickModes(void);
dogmaphobic's avatar
dogmaphobic committed
408

409 410
    bool joystickEnabled(void);
    void setJoystickEnabled(bool enabled);
dogmaphobic's avatar
dogmaphobic committed
411

412 413 414
    // Is vehicle active with respect to current active vehicle in QGC
    bool active(void);
    void setActive(bool active);
dogmaphobic's avatar
dogmaphobic committed
415

416 417
    // Property accesors
    int id(void) { return _id; }
418 419
    MAV_AUTOPILOT firmwareType(void) const { return _firmwareType; }
    MAV_TYPE vehicleType(void) const { return _vehicleType; }
420
    Q_INVOKABLE QString vehicleTypeName(void) const;
dogmaphobic's avatar
dogmaphobic committed
421

422 423 424
    /// Returns the highest quality link available to the Vehicle. If you need to hold a refernce to this link use
    /// LinkManager::sharedLinkInterfaceForGet to get QSharedPointer for link.
    LinkInterface* priorityLink(void) { return _priorityLink.data(); }
425 426 427 428 429

    /// Sends a message to the specified link
    /// @return true: message sent, false: Link no longer connected
    bool sendMessageOnLink(LinkInterface* link, mavlink_message_t message);

430 431 432
    /// 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
433

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

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

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

443
    int manualControlReservedButtonCount(void);
dogmaphobic's avatar
dogmaphobic committed
444

445 446 447
    MissionManager*     missionManager(void)    { return _missionManager; }
    GeoFenceManager*    geoFenceManager(void)   { return _geoFenceManager; }
    RallyPointManager*  rallyPointManager(void) { return _rallyPointManager; }
dogmaphobic's avatar
dogmaphobic committed
448

449 450
    bool homePositionAvailable(void);
    QGeoCoordinate homePosition(void);
dogmaphobic's avatar
dogmaphobic committed
451

Don Gagne's avatar
Don Gagne committed
452 453 454 455 456
    bool armed(void) { return _armed; }
    void setArmed(bool armed);

    bool flightModeSetAvailable(void);
    QStringList flightModes(void);
Don Gagne's avatar
Don Gagne committed
457
    QString flightMode(void) const;
Don Gagne's avatar
Don Gagne committed
458 459 460 461
    void setFlightMode(const QString& flightMode);

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

463 464
    bool fixedWing(void) const;
    bool multiRotor(void) const;
Don Gagne's avatar
Don Gagne committed
465
    bool vtol(void) const;
Don Gagne's avatar
Don Gagne committed
466
    bool rover(void) const;
467
    bool sub(void) const;
468

469
    bool supportsManualControl(void) const;
470
    bool supportsThrottleModeCenterZero(void) const;
471
    bool supportsRadio(void) const;
472
    bool supportsJSButton(void) const;
473

Don Gagne's avatar
Don Gagne committed
474 475 476
    void setFlying(bool flying);
    void setGuidedMode(bool guidedMode);

Don Gagne's avatar
Don Gagne committed
477 478 479
    QString prearmError(void) const { return _prearmError; }
    void setPrearmError(const QString& prearmError);

480
    QmlObjectListModel* trajectoryPoints(void) { return &_mapTrajectoryList; }
dogmaphobic's avatar
dogmaphobic committed
481 482 483

    int  flowImageIndex() { return _flowImageIndex; }

484 485 486 487
    //-- Mavlink Logging
    void startMavlinkLog();
    void stopMavlinkLog();

488 489 490
    /// 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
491 492
    ///     @param sendMultiple Send multiple time to guarantee Vehicle reception
    void requestDataStream(MAV_DATA_STREAM stream, uint16_t rate, bool sendMultiple = true);
dogmaphobic's avatar
dogmaphobic committed
493

494 495 496 497 498 499
    typedef enum {
        MessageNone,
        MessageNormal,
        MessageWarning,
        MessageError
    } MessageType_t;
dogmaphobic's avatar
dogmaphobic committed
500

501 502 503 504 505 506 507 508 509 510 511 512 513 514 515 516 517 518 519 520 521 522 523 524 525 526
    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; }
    QString         formatedMessages        ();
    QString         formatedMessage         () { return _formatedMessage; }
    QString         latestError             () { return _latestError; }
    float           latitude                () { return _coordinate.latitude(); }
    float           longitude               () { return _coordinate.longitude(); }
    bool            mavPresent              () { return _mav != NULL; }
    int             rcRSSI                  () { return _rcRSSI; }
    bool            px4Firmware             () const { return _firmwareType == MAV_AUTOPILOT_PX4; }
    bool            apmFirmware             () const { return _firmwareType == MAV_AUTOPILOT_ARDUPILOTMEGA; }
    bool            genericFirmware         () const { return !px4Firmware() && !apmFirmware(); }
    bool            connectionLost          () const { return _connectionLost; }
    bool            connectionLostEnabled   () const { return _connectionLostEnabled; }
    uint            messagesReceived        () { return _messagesReceived; }
    uint            messagesSent            () { return _messagesSent; }
    uint            messagesLost            () { return _messagesLost; }
    bool            flying                  () const { return _flying; }
    bool            guidedMode              () const;
    uint8_t         baseMode                () const { return _base_mode; }
    uint32_t        customMode              () const { return _custom_mode; }
    bool            isOfflineEditingVehicle () const { return _offlineEditingVehicle; }
527
    QString         brandImage              () const;
528
    QStringList     unhealthySensors        () const;
529 530 531
    QString         missionFlightMode       () const;
    QString         rtlFlightMode           () const;
    QString         takeControlFlightMode   () const;
532 533 534
    double          cruiseSpeed             () const { return _cruiseSpeed; }
    double          hoverSpeed              () const { return _hoverSpeed; }
    QString         firmwareTypeString      () const;
Gus Grubba's avatar
Gus Grubba committed
535 536 537 538 539 540 541 542
    QString         vehicleTypeString       () const;
    int             telemetryRRSSI          () { return _telemetryRRSSI; }
    int             telemetryLRSSI          () { return _telemetryLRSSI; }
    unsigned int    telemetryRXErrors       () { return _telemetryRXErrors; }
    unsigned int    telemetryFixed          () { return _telemetryFixed; }
    unsigned int    telemetryTXBuffer       () { return _telemetryTXBuffer; }
    unsigned int    telemetryLNoise         () { return _telemetryLNoise; }
    unsigned int    telemetryRNoise         () { return _telemetryRNoise; }
543

Don Gagne's avatar
Don Gagne committed
544 545 546 547 548 549 550 551 552
    Fact* roll              (void) { return &_rollFact; }
    Fact* heading           (void) { return &_headingFact; }
    Fact* pitch             (void) { return &_pitchFact; }
    Fact* airSpeed          (void) { return &_airSpeedFact; }
    Fact* groundSpeed       (void) { return &_groundSpeedFact; }
    Fact* climbRate         (void) { return &_climbRateFact; }
    Fact* altitudeRelative  (void) { return &_altitudeRelativeFact; }
    Fact* altitudeAMSL      (void) { return &_altitudeAMSLFact; }

553 554 555 556
    FactGroup* gpsFactGroup         (void) { return &_gpsFactGroup; }
    FactGroup* batteryFactGroup     (void) { return &_batteryFactGroup; }
    FactGroup* windFactGroup        (void) { return &_windFactGroup; }
    FactGroup* vibrationFactGroup   (void) { return &_vibrationFactGroup; }
Don Gagne's avatar
Don Gagne committed
557

558
    void setConnectionLostEnabled(bool connectionLostEnabled);
559

560 561
    ParameterManager* parameterManager(void) { return _parameterManager; }
    ParameterManager* parameterManager(void) const { return _parameterManager; }
dogmaphobic's avatar
dogmaphobic committed
562

Don Gagne's avatar
Don Gagne committed
563 564
    static const int cMaxRcChannels = 18;

Don Gagne's avatar
Don Gagne committed
565
    bool containsLink(LinkInterface* link) { return _links.contains(link); }
566 567 568 569 570 571 572

    /// Sends the specified MAV_CMD to the vehicle. If no Ack is received command will be retried. If a sendMavCommand is already in progress
    /// the command will be queued and sent when the previous command completes.
    ///     @param component Component to send to
    ///     @param command MAV_CMD to send
    ///     @param showError true: Display error to user if command failed, false:  no error shown
    void sendMavCommand(int component, MAV_CMD command, bool showError, float param1 = 0.0f, float param2 = 0.0f, float param3 = 0.0f, float param4 = 0.0f, float param5 = 0.0f, float param6 = 0.0f, float param7 = 0.0f);
Don Gagne's avatar
Don Gagne committed
573

Don Gagne's avatar
Don Gagne committed
574 575 576
    int firmwareMajorVersion(void) const { return _firmwareMajorVersion; }
    int firmwareMinorVersion(void) const { return _firmwareMinorVersion; }
    int firmwarePatchVersion(void) const { return _firmwarePatchVersion; }
577 578 579
    int firmwareVersionType(void) const { return _firmwareVersionType; }
    QString firmwareVersionTypeString(void) const;
    void setFirmwareVersion(int majorVersion, int minorVersion, int patchVersion, FIRMWARE_VERSION_TYPE versionType = FIRMWARE_VERSION_TYPE_OFFICIAL);
580
    static const int versionNotSetValue = -1;
Don Gagne's avatar
Don Gagne committed
581

582 583 584
    bool soloFirmware(void) const { return _soloFirmware; }
    void setSoloFirmware(bool soloFirmware);

585 586 587 588
    int defaultComponentId(void) { return _defaultComponentId; }

    /// Sets the default component id for an offline editing vehicle
    void setOfflineEditingDefaultComponentId(int defaultComponentId);
Don Gagne's avatar
Don Gagne committed
589

Don Gagne's avatar
Don Gagne committed
590 591 592 593 594 595 596 597 598
    /// @return -1 = Unknown, Number of motors on vehicle
    int motorCount(void);

    /// @return true: Motors are coaxial like an X8 config, false: Quadcopter for example
    bool coaxialMotors(void);

    /// @return true: X confiuration, false: Plus configuration
    bool xConfigMotors(void);

599 600 601 602 603 604 605
    /// @return Firmware plugin instance data associated with this Vehicle
    QObject* firmwarePluginInstanceData(void) { return _firmwarePluginInstanceData; }

    /// Sets the firmware plugin instance data associated with this Vehicle. This object will be parented to the Vehicle
    /// and destroyed when the vehicle goes away.
    void setFirmwarePluginInstanceData(QObject* firmwarePluginInstanceData);

606 607 608 609
    QString vehicleImageOpaque  () const;
    QString vehicleImageOutline () const;
    QString vehicleImageCompass () const;

610 611 612
public slots:
    void setLatitude(double latitude);
    void setLongitude(double longitude);
dogmaphobic's avatar
dogmaphobic committed
613

614
signals:
Don Gagne's avatar
Don Gagne committed
615
    void allLinksInactive(Vehicle* vehicle);
616
    void coordinateChanged(QGeoCoordinate coordinate);
617
    void coordinateValidChanged(bool coordinateValid);
618
    void joystickModeChanged(int mode);
619 620
    void joystickEnabledChanged(bool enabled);
    void activeChanged(bool active);
Don Gagne's avatar
Don Gagne committed
621
    void mavlinkMessageReceived(const mavlink_message_t& message);
622 623
    void homePositionAvailableChanged(bool homePositionAvailable);
    void homePositionChanged(const QGeoCoordinate& homePosition);
Don Gagne's avatar
Don Gagne committed
624 625 626
    void armedChanged(bool armed);
    void flightModeChanged(const QString& flightMode);
    void hilModeChanged(bool hilMode);
627 628
    /** @brief HIL actuator controls (replaces HIL controls) */
    void hilActuatorControlsChanged(quint64 time, quint64 flags, float ctl_0, float ctl_1, float ctl_2, float ctl_3, float ctl_4, float ctl_5, float ctl_6, float ctl_7, float ctl_8, float ctl_9, float ctl_10, float ctl_11, float ctl_12, float ctl_13, float ctl_14, float ctl_15, quint8 mode);
629 630
    void connectionLostChanged(bool connectionLost);
    void connectionLostEnabledChanged(bool connectionLostEnabled);
Don Gagne's avatar
Don Gagne committed
631
    void autoDisconnectChanged(bool autoDisconnectChanged);
Don Gagne's avatar
Don Gagne committed
632 633
    void flyingChanged(bool flying);
    void guidedModeChanged(bool guidedMode);
Don Gagne's avatar
Don Gagne committed
634
    void prearmErrorChanged(const QString& prearmError);
635
    void soloFirmwareChanged(bool soloFirmware);
636
    void unhealthySensorsChanged(void);
637 638 639 640
    void cruiseSpeedChanged(double cruiseSpeed);
    void hoverSpeedChanged(double hoverSpeed);
    void firmwareTypeChanged(void);
    void vehicleTypeChanged(void);
dogmaphobic's avatar
dogmaphobic committed
641

642 643 644 645
    void messagesReceivedChanged    ();
    void messagesSentChanged        ();
    void messagesLostChanged        ();

646
    /// Used internally to move sendMessage call to main thread
647
    void _sendMessageOnLinkOnThread(LinkInterface* link, mavlink_message_t message);
dogmaphobic's avatar
dogmaphobic committed
648

Gus Grubba's avatar
Gus Grubba committed
649 650 651 652 653 654 655 656 657 658 659 660 661 662 663 664 665
    void messageTypeChanged         ();
    void newMessageCountChanged     ();
    void messageCountChanged        ();
    void formatedMessagesChanged    ();
    void formatedMessageChanged     ();
    void latestErrorChanged         ();
    void longitudeChanged           ();
    void currentConfigChanged       ();
    void flowImageIndexChanged      ();
    void rcRSSIChanged              (int rcRSSI);
    void telemetryRRSSIChanged      (int value);
    void telemetryLRSSIChanged      (int value);
    void telemetryRXErrorsChanged   (unsigned int value);
    void telemetryFixedChanged      (unsigned int value);
    void telemetryTXBufferChanged   (unsigned int value);
    void telemetryLNoiseChanged     (unsigned int value);
    void telemetryRNoiseChanged     (unsigned int value);
dogmaphobic's avatar
dogmaphobic committed
666

667 668 669 670 671
    void firmwareMajorVersionChanged(int major);
    void firmwareMinorVersionChanged(int minor);
    void firmwarePatchVersionChanged(int patch);
    void firmwareVersionTypeChanged(int type);

Don Gagne's avatar
Don Gagne committed
672 673 674 675 676 677 678 679
    /// New RC channel values
    ///     @param channelCount Number of available channels, cMaxRcChannels max
    ///     @param pwmValues -1 signals channel not available
    void rcChannelsChanged(int channelCount, int pwmValues[cMaxRcChannels]);

    /// Remote control RSSI changed  (0% - 100%)
    void remoteControlRSSIChanged(uint8_t rssi);

680 681 682 683 684
    void mavlinkRawImu(mavlink_message_t message);
    void mavlinkScaledImu1(mavlink_message_t message);
    void mavlinkScaledImu2(mavlink_message_t message);
    void mavlinkScaledImu3(mavlink_message_t message);

685
    // Mavlink Log Download
Gus Grubba's avatar
Gus Grubba committed
686
    void mavlinkLogData (Vehicle* vehicle, uint8_t target_system, uint8_t target_component, uint16_t sequence, uint8_t first_message, QByteArray data, bool acked);
687

688 689 690 691 692 693
    /// Signalled in response to usage of sendMavCommand
    ///     @param vehicleId Vehicle which command was sent to
    ///     @param component Component which command was sent to
    ///     @param command MAV_CMD Command which was sent
    ///     @param result MAV_RESULT returned in ack
    ///     @param noResponseFromVehicle true: vehicle did not respond to command, false: vehicle responsed, MAV_RESULT in result
694
    void mavCommandResult(int vehicleId, int component, int command, int result, bool noReponseFromVehicle);
695

696 697
private slots:
    void _mavlinkMessageReceived(LinkInterface* link, mavlink_message_t message);
Gus Grubba's avatar
Gus Grubba committed
698
    void _telemetryChanged(LinkInterface* link, unsigned rxerrors, unsigned fixed, int rssi, int remrssi, unsigned txbuf, unsigned noise, unsigned remnoise);
Don Gagne's avatar
Don Gagne committed
699
    void _linkInactiveOrDeleted(LinkInterface* link);
700
    void _sendMessageOnLink(LinkInterface* link, mavlink_message_t message);
701
    void _sendMessageMultipleNext(void);
702
    void _addNewMapTrajectoryPoint(void);
703
    void _parametersReady(bool parametersReady);
Don Gagne's avatar
Don Gagne committed
704
    void _remoteControlRSSIChanged(uint8_t rssi);
Don Gagne's avatar
Don Gagne committed
705
    void _handleFlightModeChanged(const QString& flightMode);
706
    void _announceArmedChanged(bool armed);
707 708 709 710
    void _offlineFirmwareTypeSettingChanged(QVariant value);
    void _offlineVehicleTypeSettingChanged(QVariant value);
    void _offlineCruiseSpeedSettingChanged(QVariant value);
    void _offlineHoverSpeedSettingChanged(QVariant value);
711

712
    void _handleTextMessage                 (int newCount);
dogmaphobic's avatar
dogmaphobic committed
713
    void _handletextMessageReceived         (UASMessage* message);
714 715 716 717
    /** @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);
dogmaphobic's avatar
dogmaphobic committed
718 719
    /** @brief A new camera image has arrived */
    void _imageReady                        (UASInterface* uas);
720
    void _connectionLostTimeout(void);
Don Gagne's avatar
Don Gagne committed
721
    void _prearmErrorTimeout(void);
722
    void _newMissionItemsAvailable(void);
723
    void _newGeoFenceAvailable(void);
724
    void _sendMavCommandAgain(void);
725

Jacob Walser's avatar
Jacob Walser committed
726 727
    void _activeJoystickChanged(void);

728 729 730
private:
    bool _containsLink(LinkInterface* link);
    void _addLink(LinkInterface* link);
731 732
    void _loadSettings(void);
    void _saveSettings(void);
733
    void _startJoystick(bool start);
Don Gagne's avatar
Don Gagne committed
734 735
    void _handleHomePosition(mavlink_message_t& message);
    void _handleHeartbeat(mavlink_message_t& message);
Don Gagne's avatar
Don Gagne committed
736 737
    void _handleRCChannels(mavlink_message_t& message);
    void _handleRCChannelsRaw(mavlink_message_t& message);
Don Gagne's avatar
Don Gagne committed
738 739
    void _handleBatteryStatus(mavlink_message_t& message);
    void _handleSysStatus(mavlink_message_t& message);
740
    void _handleWindCov(mavlink_message_t& message);
Don Gagne's avatar
Don Gagne committed
741
    void _handleWind(mavlink_message_t& message);
742
    void _handleVibration(mavlink_message_t& message);
Don Gagne's avatar
Don Gagne committed
743
    void _handleExtendedSysState(mavlink_message_t& message);
744
    void _handleCommandAck(mavlink_message_t& message);
Gus Grubba's avatar
Gus Grubba committed
745
    void _handleAutopilotVersion(LinkInterface* link, mavlink_message_t& message);
746
    void _handleHilActuatorControls(mavlink_message_t& message);
747 748 749 750
    void _handleGpsRawInt(mavlink_message_t& message);
    void _handleGlobalPositionInt(mavlink_message_t& message);
    void _handleAltitude(mavlink_message_t& message);
    void _handleVfrHud(mavlink_message_t& message);
751
    void _missionManagerError(int errorCode, const QString& errorMsg);
752
    void _geoFenceManagerError(int errorCode, const QString& errorMsg);
753
    void _rallyPointManagerError(int errorCode, const QString& errorMsg);
754 755
    void _mapTrajectoryStart(void);
    void _mapTrajectoryStop(void);
756
    void _connectionActive(void);
757 758
    void _say(const QString& text);
    QString _vehicleIdSpeech(void);
759 760 761
    void _handleMavlinkLoggingData(mavlink_message_t& message);
    void _handleMavlinkLoggingDataAcked(mavlink_message_t& message);
    void _ackMavlinkLogData(uint16_t sequence);
762
    void _sendNextQueuedMavCommand(void);
763
    void _updatePriorityLink(void);
764
    void _commonInit(void);
Don Gagne's avatar
Don Gagne committed
765

766
    int     _id;                    ///< Mavlink system id
767
    int     _defaultComponentId;
768
    bool    _active;
769
    bool    _offlineEditingVehicle; ///< This Vehicle is a "disconnected" vehicle for ui use while offline editing
dogmaphobic's avatar
dogmaphobic committed
770

771
    MAV_AUTOPILOT       _firmwareType;
772
    MAV_TYPE            _vehicleType;
773
    FirmwarePlugin*     _firmwarePlugin;
774
    QObject*            _firmwarePluginInstanceData;
775
    AutoPilotPlugin*    _autopilotPlugin;
Don Gagne's avatar
Don Gagne committed
776
    MAVLinkProtocol*    _mavlink;
777
    bool                _soloFirmware;
dogmaphobic's avatar
dogmaphobic committed
778

Don Gagne's avatar
Don Gagne committed
779
    QList<LinkInterface*> _links;
dogmaphobic's avatar
dogmaphobic committed
780

781
    JoystickMode_t  _joystickMode;
782
    bool            _joystickEnabled;
dogmaphobic's avatar
dogmaphobic committed
783

784
    UAS* _uas;
dogmaphobic's avatar
dogmaphobic committed
785

786 787
    QGeoCoordinate  _coordinate;
    bool            _coordinateValid;       ///< true: vehicle has 3d lock and therefore valid location
dogmaphobic's avatar
dogmaphobic committed
788

789 790
    bool            _homePositionAvailable;
    QGeoCoordinate  _homePosition;
dogmaphobic's avatar
dogmaphobic committed
791

792 793 794 795 796 797 798 799 800
    UASInterface*   _mav;
    int             _currentMessageCount;
    int             _messageCount;
    int             _currentErrorCount;
    int             _currentWarningCount;
    int             _currentNormalCount;
    MessageType_t   _currentMessageType;
    QString         _latestError;
    int             _updateCount;
dogmaphobic's avatar
dogmaphobic committed
801
    QString         _formatedMessage;
Don Gagne's avatar
Don Gagne committed
802 803
    int             _rcRSSI;
    double          _rcRSSIstore;
Don Gagne's avatar
Don Gagne committed
804
    bool            _autoDisconnect;    ///< true: Automatically disconnect vehicle when last connection goes away or lost heartbeat
Don Gagne's avatar
Don Gagne committed
805
    bool            _flying;
806 807 808 809
    uint32_t        _onboardControlSensorsPresent;
    uint32_t        _onboardControlSensorsEnabled;
    uint32_t        _onboardControlSensorsHealth;
    uint32_t        _onboardControlSensorsUnhealthy;
810 811
    bool            _gpsRawIntMessageAvailable;
    bool            _globalPositionIntMessageAvailable;
812 813
    double          _cruiseSpeed;
    double          _hoverSpeed;
Gus Grubba's avatar
Gus Grubba committed
814 815 816 817 818 819 820
    int             _telemetryRRSSI;
    int             _telemetryLRSSI;
    uint32_t        _telemetryRXErrors;
    uint32_t        _telemetryFixed;
    uint32_t        _telemetryTXBuffer;
    uint32_t        _telemetryLNoise;
    uint32_t        _telemetryRNoise;
dogmaphobic's avatar
dogmaphobic committed
821

822 823 824 825 826 827 828 829 830 831 832
    typedef struct {
        int     component;
        MAV_CMD command;
        float   rgParam[7];
        bool    showError;
    } MavCommandQueueEntry_t;

    QList<MavCommandQueueEntry_t>   _mavCommandQueue;
    QTimer                          _mavCommandAckTimer;
    int                             _mavCommandRetryCount;
    static const int                _mavCommandMaxRetryCount = 3;
833
    static const int                _mavCommandAckTimeoutMSecs = 3000;
834

Don Gagne's avatar
Don Gagne committed
835 836 837 838
    QString             _prearmError;
    QTimer              _prearmErrorTimer;
    static const int    _prearmErrorTimeoutMSecs = 35 * 1000;   ///< Take away prearm error after 35 seconds

839 840 841 842 843 844
    // Lost connection handling
    bool                _connectionLost;
    bool                _connectionLostEnabled;
    static const int    _connectionLostTimeoutMSecs = 3500;  // Signal connection lost after 3.5 seconds of missed heartbeat
    QTimer              _connectionLostTimer;

Don Gagne's avatar
Don Gagne committed
845
    MissionManager*     _missionManager;
846
    bool                _missionManagerInitialRequestSent;
847

848
    GeoFenceManager*    _geoFenceManager;
849 850 851 852
    bool                _geoFenceManagerInitialRequestSent;

    RallyPointManager*  _rallyPointManager;
    bool                _rallyPointManagerInitialRequestSent;
853

854
    ParameterManager*    _parameterManager;
dogmaphobic's avatar
dogmaphobic committed
855

Don Gagne's avatar
Don Gagne committed
856 857 858
    bool    _armed;         ///< true: vehicle is armed
    uint8_t _base_mode;     ///< base_mode from HEARTBEAT
    uint32_t _custom_mode;  ///< custom_mode from HEARTBEAT
859 860 861 862 863 864

    /// 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
865

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

868 869
    static const int _sendMessageMultipleRetries = 5;
    static const int _sendMessageMultipleIntraMessageDelay = 500;
dogmaphobic's avatar
dogmaphobic committed
870

871 872
    QTimer  _sendMultipleTimer;
    int     _nextSendMessageMultipleIndex;
dogmaphobic's avatar
dogmaphobic committed
873

874 875 876 877 878
    QTimer              _mapTrajectoryTimer;
    QmlObjectListModel  _mapTrajectoryList;
    QGeoCoordinate      _mapTrajectoryLastCoordinate;
    bool                _mapTrajectoryHaveFirstCoordinate;
    static const int    _mapTrajectoryMsecsBetweenPoints = 1000;
879

880
    // Toolbox references
dogmaphobic's avatar
dogmaphobic committed
881 882 883 884 885
    FirmwarePluginManager*      _firmwarePluginManager;
    JoystickManager*            _joystickManager;

    int                         _flowImageIndex;

Don Gagne's avatar
Don Gagne committed
886 887
    bool _allLinksInactiveSent; ///< true: allLinkInactive signal already sent one time

888 889 890 891 892 893 894
    uint                _messagesReceived;
    uint                _messagesSent;
    uint                _messagesLost;
    uint8_t             _messageSeq;
    uint8_t             _compID;
    bool                _heardFrom;

Don Gagne's avatar
Don Gagne committed
895 896 897
    int _firmwareMajorVersion;
    int _firmwareMinorVersion;
    int _firmwarePatchVersion;
898
    FIRMWARE_VERSION_TYPE _firmwareVersionType;
Don Gagne's avatar
Don Gagne committed
899

900 901 902
    static const int    _lowBatteryAnnounceRepeatMSecs; // Amount of time in between each low battery announcement
    QElapsedTimer       _lowBatteryAnnounceTimer;

903 904
    SharedLinkInterfacePointer _priorityLink;  // We always keep a reference to the priority link to manage shutdown ordering

Don Gagne's avatar
Don Gagne committed
905 906 907 908 909 910 911 912 913 914 915
    // FactGroup facts

    Fact _rollFact;
    Fact _pitchFact;
    Fact _headingFact;
    Fact _groundSpeedFact;
    Fact _airSpeedFact;
    Fact _climbRateFact;
    Fact _altitudeRelativeFact;
    Fact _altitudeAMSLFact;

916 917 918 919
    VehicleGPSFactGroup         _gpsFactGroup;
    VehicleBatteryFactGroup     _batteryFactGroup;
    VehicleWindFactGroup        _windFactGroup;
    VehicleVibrationFactGroup   _vibrationFactGroup;
Don Gagne's avatar
Don Gagne committed
920 921 922 923 924 925 926 927 928

    static const char* _rollFactName;
    static const char* _pitchFactName;
    static const char* _headingFactName;
    static const char* _groundSpeedFactName;
    static const char* _airSpeedFactName;
    static const char* _climbRateFactName;
    static const char* _altitudeRelativeFactName;
    static const char* _altitudeAMSLFactName;
Don Gagne's avatar
Don Gagne committed
929

Don Gagne's avatar
Don Gagne committed
930
    static const char* _gpsFactGroupName;
Don Gagne's avatar
Don Gagne committed
931
    static const char* _batteryFactGroupName;
Don Gagne's avatar
Don Gagne committed
932
    static const char* _windFactGroupName;
933
    static const char* _vibrationFactGroupName;
Don Gagne's avatar
Don Gagne committed
934 935 936

    static const int _vehicleUIUpdateRateMSecs = 100;

937
    // Settings keys
938 939
    static const char* _settingsGroup;
    static const char* _joystickModeSettingsKey;
940
    static const char* _joystickEnabledSettingsKey;
Don Gagne's avatar
Don Gagne committed
941

942 943
};
#endif