Vehicle.h 52.5 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
#pragma once
11 12

#include <QObject>
13
#include <QGeoCoordinate>
14
#include <QElapsedTimer>
15

Don Gagne's avatar
Don Gagne committed
16
#include "FactGroup.h"
17 18
#include "LinkInterface.h"
#include "QGCMAVLink.h"
19
#include "QmlObjectListModel.h"
Don Gagne's avatar
Don Gagne committed
20
#include "MAVLinkProtocol.h"
dogmaphobic's avatar
dogmaphobic committed
21
#include "UASMessageHandler.h"
22
#include "SettingsFact.h"
23

24 25
class UAS;
class UASInterface;
26
class FirmwarePlugin;
27
class FirmwarePluginManager;
28
class AutoPilotPlugin;
Don Gagne's avatar
Don Gagne committed
29
class MissionManager;
30
class GeoFenceManager;
31
class RallyPointManager;
32
class ParameterManager;
33
class JoystickManager;
dogmaphobic's avatar
dogmaphobic committed
34
class UASMessage;
35
class SettingsManager;
36
class ADSBVehicle;
37 38 39

Q_DECLARE_LOGGING_CATEGORY(VehicleLog)

Don Gagne's avatar
Don Gagne committed
40 41
class Vehicle;

42 43 44 45 46 47 48 49 50 51 52 53 54 55
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)

56 57 58 59 60 61
    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; }
62 63 64 65 66 67 68 69 70 71 72 73 74 75 76 77 78

    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
79 80 81 82 83 84 85 86 87 88 89
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)

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

    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
104 105 106 107 108 109 110
class VehicleGPSFactGroup : public FactGroup
{
    Q_OBJECT

public:
    VehicleGPSFactGroup(QObject* parent = NULL);

111 112
    Q_PROPERTY(Fact* lat                READ lat                CONSTANT)
    Q_PROPERTY(Fact* lon                READ lon                CONSTANT)
Don Gagne's avatar
Don Gagne committed
113 114 115 116 117 118
    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)

119 120
    Fact* lat               (void) { return &_latFact; }
    Fact* lon               (void) { return &_lonFact; }
121 122 123 124 125
    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
126

127 128
    static const char* _latFactName;
    static const char* _lonFactName;
Don Gagne's avatar
Don Gagne committed
129 130 131 132 133 134
    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
135
private:
136 137
    Fact        _latFact;
    Fact        _lonFact;
Don Gagne's avatar
Don Gagne committed
138 139 140 141 142
    Fact        _hdopFact;
    Fact        _vdopFact;
    Fact        _courseOverGroundFact;
    Fact        _countFact;
    Fact        _lockFact;
Don Gagne's avatar
Don Gagne committed
143
};
Don Gagne's avatar
Don Gagne committed
144

Don Gagne's avatar
Don Gagne committed
145 146 147 148 149 150 151 152 153 154 155 156
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)
157 158 159 160 161 162 163 164
    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
165 166 167 168 169 170 171 172 173


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

174 175
    static const char* _settingsGroup;

Don Gagne's avatar
Don Gagne committed
176 177 178 179 180 181 182 183
    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:
184 185 186 187 188 189
    Fact            _voltageFact;
    Fact            _percentRemainingFact;
    Fact            _mahConsumedFact;
    Fact            _currentFact;
    Fact            _temperatureFact;
    Fact            _cellCountFact;
Don Gagne's avatar
Don Gagne committed
190 191
};

192 193 194 195 196 197 198 199 200 201 202 203 204 205 206 207 208 209 210 211 212 213 214 215 216 217 218 219 220
class VehicleTemperatureFactGroup : public FactGroup
{
    Q_OBJECT

public:
    VehicleTemperatureFactGroup(QObject* parent = NULL);

    Q_PROPERTY(Fact* temperature1       READ temperature1       CONSTANT)
    Q_PROPERTY(Fact* temperature2       READ temperature2       CONSTANT)
    Q_PROPERTY(Fact* temperature3       READ temperature3       CONSTANT)

    Fact* temperature1 (void) { return &_temperature1Fact; }
    Fact* temperature2 (void) { return &_temperature2Fact; }
    Fact* temperature3 (void) { return &_temperature3Fact; }

    static const char* _temperature1FactName;
    static const char* _temperature2FactName;
    static const char* _temperature3FactName;

    static const char* _settingsGroup;

    static const double _temperatureUnavailable;

private:
    Fact            _temperature1Fact;
    Fact            _temperature2Fact;
    Fact            _temperature3Fact;
};

Don Gagne's avatar
Don Gagne committed
221
class Vehicle : public FactGroup
222 223
{
    Q_OBJECT
dogmaphobic's avatar
dogmaphobic committed
224

225
public:
226 227
    Vehicle(LinkInterface*          link,
            int                     vehicleId,
228
            int                     defaultComponentId,
229 230 231 232
            MAV_AUTOPILOT           firmwareType,
            MAV_TYPE                vehicleType,
            FirmwarePluginManager*  firmwarePluginManager,
            JoystickManager*        joystickManager);
233

234 235 236 237 238
    // 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);
239

240
    ~Vehicle();
dogmaphobic's avatar
dogmaphobic committed
241

242 243 244 245 246
    Q_PROPERTY(int                  id                      READ id                                                     CONSTANT)
    Q_PROPERTY(AutoPilotPlugin*     autopilot               MEMBER _autopilotPlugin                                     CONSTANT)
    Q_PROPERTY(QGeoCoordinate       coordinate              READ coordinate                                             NOTIFY coordinateChanged)
    Q_PROPERTY(QGeoCoordinate       homePosition            READ homePosition                                           NOTIFY homePositionChanged)
    Q_PROPERTY(bool                 armed                   READ armed                  WRITE setArmed                  NOTIFY armedChanged)
247
    Q_PROPERTY(bool                 autoDisarm              READ autoDisarm                                             NOTIFY autoDisarmChanged)
248 249 250 251 252
    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)
253
    Q_PROPERTY(QmlObjectListModel*  cameraTriggerPoints     READ cameraTriggerPoints                                    CONSTANT)
254 255 256 257 258 259 260 261 262 263 264 265 266 267 268 269 270
    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)
271 272
    Q_PROPERTY(bool                 px4Firmware             READ px4Firmware                                            NOTIFY firmwareTypeChanged)
    Q_PROPERTY(bool                 apmFirmware             READ apmFirmware                                            NOTIFY firmwareTypeChanged)
273 274 275 276 277 278 279
    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)
280 281 282 283 284
    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)
285
    Q_PROPERTY(bool                 supportsManualControl   READ supportsManualControl                                  CONSTANT)
286
    Q_PROPERTY(bool        supportsThrottleModeCenterZero   READ supportsThrottleModeCenterZero                         CONSTANT)
287
    Q_PROPERTY(bool                 supportsJSButton        READ supportsJSButton                                       CONSTANT)
288
    Q_PROPERTY(bool                 supportsRadio           READ supportsRadio                                          CONSTANT)
289
    Q_PROPERTY(bool               supportsMotorInterference READ supportsMotorInterference                              CONSTANT)
290 291
    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
292 293 294
    Q_PROPERTY(int                  motorCount              READ motorCount                                             CONSTANT)
    Q_PROPERTY(bool                 coaxialMotors           READ coaxialMotors                                          CONSTANT)
    Q_PROPERTY(bool                 xConfigMotors           READ xConfigMotors                                          CONSTANT)
295
    Q_PROPERTY(bool                 isOfflineEditingVehicle READ isOfflineEditingVehicle                                CONSTANT)
296 297
    Q_PROPERTY(QString              brandImageIndoor        READ brandImageIndoor                                       NOTIFY firmwareTypeChanged)
    Q_PROPERTY(QString              brandImageOutdoor       READ brandImageOutdoor                                      NOTIFY firmwareTypeChanged)
298
    Q_PROPERTY(QStringList          unhealthySensors        READ unhealthySensors                                       NOTIFY unhealthySensorsChanged)
299
    Q_PROPERTY(QString              missionFlightMode       READ missionFlightMode                                      CONSTANT)
300
    Q_PROPERTY(QString              pauseFlightMode         READ pauseFlightMode                                        CONSTANT)
301
    Q_PROPERTY(QString              rtlFlightMode           READ rtlFlightMode                                          CONSTANT)
302
    Q_PROPERTY(QString              landFlightMode          READ landFlightMode                                         CONSTANT)
303
    Q_PROPERTY(QString              takeControlFlightMode   READ takeControlFlightMode                                  CONSTANT)
304 305
    Q_PROPERTY(QString              firmwareTypeString      READ firmwareTypeString                                     NOTIFY firmwareTypeChanged)
    Q_PROPERTY(QString              vehicleTypeString       READ vehicleTypeString                                      NOTIFY vehicleTypeChanged)
306 307 308
    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
309 310 311 312 313
    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)
314 315
    Q_PROPERTY(int                  telemetryLNoise         READ telemetryLNoise                                        NOTIFY telemetryLNoiseChanged)
    Q_PROPERTY(int                  telemetryRNoise         READ telemetryRNoise                                        NOTIFY telemetryRNoiseChanged)
316
    Q_PROPERTY(QVariantList         toolBarIndicators       READ toolBarIndicators                                      CONSTANT)
317
    Q_PROPERTY(QVariantList         cameraList              READ cameraList                                             CONSTANT)
318
    Q_PROPERTY(QmlObjectListModel*  adsbVehicles            READ adsbVehicles                                           CONSTANT)
319

Don Gagne's avatar
Don Gagne committed
320
    /// true: Vehicle is flying, false: Vehicle is on ground
321 322 323 324
    Q_PROPERTY(bool flying READ flying NOTIFY flyingChanged)

    /// true: Vehicle is flying, false: Vehicle is on ground
    Q_PROPERTY(bool landing READ landing NOTIFY landingChanged)
Don Gagne's avatar
Don Gagne committed
325 326

    /// true: Vehicle is in Guided mode and can respond to guided commands, false: vehicle cannot respond to direct control commands
327
    Q_PROPERTY(bool guidedMode READ guidedMode WRITE setGuidedMode NOTIFY guidedModeChanged)
Don Gagne's avatar
Don Gagne committed
328 329 330 331 332 333 334

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

335 336 337
    /// true: Orbit mode is supported by this vehicle
    Q_PROPERTY(bool orbitModeSupported READ orbitModeSupported CONSTANT)

338 339
    Q_PROPERTY(ParameterManager* parameterManager READ parameterManager CONSTANT)

Don Gagne's avatar
Don Gagne committed
340 341 342 343 344 345 346 347 348 349
    // 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)
350
    Q_PROPERTY(Fact* flightDistance     READ flightDistance     CONSTANT)
Don Gagne's avatar
Don Gagne committed
351

352 353 354 355 356
    Q_PROPERTY(FactGroup* gps         READ gpsFactGroup         CONSTANT)
    Q_PROPERTY(FactGroup* battery     READ batteryFactGroup     CONSTANT)
    Q_PROPERTY(FactGroup* wind        READ windFactGroup        CONSTANT)
    Q_PROPERTY(FactGroup* vibration   READ vibrationFactGroup   CONSTANT)
    Q_PROPERTY(FactGroup* temperature READ temperatureFactGroup CONSTANT)
Don Gagne's avatar
Don Gagne committed
357

358 359 360 361 362 363 364 365 366
    Q_PROPERTY(int      firmwareMajorVersion        READ firmwareMajorVersion       NOTIFY firmwareVersionChanged)
    Q_PROPERTY(int      firmwareMinorVersion        READ firmwareMinorVersion       NOTIFY firmwareVersionChanged)
    Q_PROPERTY(int      firmwarePatchVersion        READ firmwarePatchVersion       NOTIFY firmwareVersionChanged)
    Q_PROPERTY(int      firmwareVersionType         READ firmwareVersionType        NOTIFY firmwareVersionChanged)
    Q_PROPERTY(QString  firmwareVersionTypeString   READ firmwareVersionTypeString  NOTIFY firmwareVersionChanged)
    Q_PROPERTY(int      firmwareCustomMajorVersion  READ firmwareCustomMajorVersion NOTIFY firmwareCustomVersionChanged)
    Q_PROPERTY(int      firmwareCustomMinorVersion  READ firmwareCustomMinorVersion NOTIFY firmwareCustomVersionChanged)
    Q_PROPERTY(int      firmwareCustomPatchVersion  READ firmwareCustomPatchVersion NOTIFY firmwareCustomVersionChanged)
    Q_PROPERTY(QString  gitHash                     READ gitHash                    NOTIFY gitHashChanged)
367

368 369
    /// Resets link status counters
    Q_INVOKABLE void resetCounters  ();
370 371 372 373 374 375 376 377

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

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

Don Gagne's avatar
Don Gagne committed
382
    Q_INVOKABLE void virtualTabletJoystickValue(double roll, double pitch, double yaw, double thrust);
Don Gagne's avatar
Don Gagne committed
383
    Q_INVOKABLE void disconnectInactiveVehicle(void);
Don Gagne's avatar
Don Gagne committed
384

Don Gagne's avatar
Don Gagne committed
385 386 387 388 389 390 391
    /// 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
392
    Q_INVOKABLE void guidedModeTakeoff(void);
Don Gagne's avatar
Don Gagne committed
393 394 395 396

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

397 398 399
    /// Command vehicle to change altitude
    ///     @param altitudeChange If > 0, go up by amount specified, if < 0, go down by amount specified
    Q_INVOKABLE void guidedModeChangeAltitude(double altitudeChange);
Don Gagne's avatar
Don Gagne committed
400

401 402 403 404 405 406 407
    /// 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
408 409 410 411 412 413 414
    /// 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);

415
    /// Command vehicle to abort landing
416
    Q_INVOKABLE void abortLanding(double climbOutAltitude);
417

418 419
    Q_INVOKABLE void startMission(void);

420 421 422
    /// Alter the current mission item on the vehicle
    Q_INVOKABLE void setCurrentMissionSequence(int seq);

423 424 425
    /// Reboot vehicle
    Q_INVOKABLE void rebootVehicle();

dogmaphobic's avatar
dogmaphobic committed
426 427 428
    /// Clear Messages
    Q_INVOKABLE void clearMessages();

Don Gagne's avatar
Don Gagne committed
429 430
    Q_INVOKABLE void triggerCamera(void);

Don Gagne's avatar
Don Gagne committed
431 432
#if 0
    // Temporarily removed, waiting for new command implementation
Don Gagne's avatar
Don Gagne committed
433 434 435 436 437
    /// 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
438
#endif
Don Gagne's avatar
Don Gagne committed
439

Don Gagne's avatar
Don Gagne committed
440 441
    bool guidedModeSupported(void) const;
    bool pauseVehicleSupported(void) const;
442
    bool orbitModeSupported(void) const;
Don Gagne's avatar
Don Gagne committed
443

444
    // Property accessors
Don Gagne's avatar
Don Gagne committed
445

446
    QGeoCoordinate coordinate(void) { return _coordinate; }
dogmaphobic's avatar
dogmaphobic committed
447

448
    typedef enum {
449
        JoystickModeRC,         ///< Joystick emulates an RC Transmitter
450 451 452 453 454 455
        JoystickModeAttitude,
        JoystickModePosition,
        JoystickModeForce,
        JoystickModeVelocity,
        JoystickModeMax
    } JoystickMode_t;
dogmaphobic's avatar
dogmaphobic committed
456

457 458
    int joystickMode(void);
    void setJoystickMode(int mode);
dogmaphobic's avatar
dogmaphobic committed
459

460 461
    /// List of joystick mode names
    QStringList joystickModes(void);
dogmaphobic's avatar
dogmaphobic committed
462

463 464
    bool joystickEnabled(void);
    void setJoystickEnabled(bool enabled);
dogmaphobic's avatar
dogmaphobic committed
465

466 467 468
    // Is vehicle active with respect to current active vehicle in QGC
    bool active(void);
    void setActive(bool active);
dogmaphobic's avatar
dogmaphobic committed
469

470 471
    // Property accesors
    int id(void) { return _id; }
472 473
    MAV_AUTOPILOT firmwareType(void) const { return _firmwareType; }
    MAV_TYPE vehicleType(void) const { return _vehicleType; }
474
    Q_INVOKABLE QString vehicleTypeName(void) const;
dogmaphobic's avatar
dogmaphobic committed
475

Patrick José Pereira's avatar
Patrick José Pereira committed
476
    /// Returns the highest quality link available to the Vehicle. If you need to hold a reference to this link use
477 478
    /// LinkManager::sharedLinkInterfaceForGet to get QSharedPointer for link.
    LinkInterface* priorityLink(void) { return _priorityLink.data(); }
479 480 481 482 483

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

484 485 486
    /// 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
487

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

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

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

497
    int manualControlReservedButtonCount(void);
dogmaphobic's avatar
dogmaphobic committed
498

499 500 501
    MissionManager*     missionManager(void)    { return _missionManager; }
    GeoFenceManager*    geoFenceManager(void)   { return _geoFenceManager; }
    RallyPointManager*  rallyPointManager(void) { return _rallyPointManager; }
dogmaphobic's avatar
dogmaphobic committed
502

503
    QGeoCoordinate homePosition(void);
dogmaphobic's avatar
dogmaphobic committed
504

Don Gagne's avatar
Don Gagne committed
505 506 507 508 509
    bool armed(void) { return _armed; }
    void setArmed(bool armed);

    bool flightModeSetAvailable(void);
    QStringList flightModes(void);
Don Gagne's avatar
Don Gagne committed
510
    QString flightMode(void) const;
Don Gagne's avatar
Don Gagne committed
511 512 513 514
    void setFlightMode(const QString& flightMode);

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

516 517
    bool fixedWing(void) const;
    bool multiRotor(void) const;
Don Gagne's avatar
Don Gagne committed
518
    bool vtol(void) const;
Don Gagne's avatar
Don Gagne committed
519
    bool rover(void) const;
520
    bool sub(void) const;
521

522
    bool supportsManualControl(void) const;
523
    bool supportsThrottleModeCenterZero(void) const;
524
    bool supportsRadio(void) const;
525
    bool supportsJSButton(void) const;
526
    bool supportsMotorInterference(void) const;
527

Don Gagne's avatar
Don Gagne committed
528 529
    void setGuidedMode(bool guidedMode);

Don Gagne's avatar
Don Gagne committed
530 531 532
    QString prearmError(void) const { return _prearmError; }
    void setPrearmError(const QString& prearmError);

533
    QmlObjectListModel* trajectoryPoints(void) { return &_mapTrajectoryList; }
534
    QmlObjectListModel* cameraTriggerPoints(void) { return &_cameraTriggerPoints; }
535
    QmlObjectListModel* adsbVehicles(void) { return &_adsbVehicles; }
dogmaphobic's avatar
dogmaphobic committed
536 537 538

    int  flowImageIndex() { return _flowImageIndex; }

539 540 541 542
    //-- Mavlink Logging
    void startMavlinkLog();
    void stopMavlinkLog();

543 544 545
    /// 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
546 547
    ///     @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
548

549 550 551 552 553 554
    typedef enum {
        MessageNone,
        MessageNormal,
        MessageWarning,
        MessageError
    } MessageType_t;
dogmaphobic's avatar
dogmaphobic committed
555

556 557 558 559 560 561 562 563 564 565 566 567 568 569 570 571 572 573 574 575 576 577
    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; }
578
    bool            landing                 () const { return _landing; }
579 580 581 582
    bool            guidedMode              () const;
    uint8_t         baseMode                () const { return _base_mode; }
    uint32_t        customMode              () const { return _custom_mode; }
    bool            isOfflineEditingVehicle () const { return _offlineEditingVehicle; }
583 584
    QString         brandImageIndoor        () const;
    QString         brandImageOutdoor       () const;
585
    QStringList     unhealthySensors        () const;
586
    QString         missionFlightMode       () const;
587
    QString         pauseFlightMode         () const;
588
    QString         rtlFlightMode           () const;
589
    QString         landFlightMode          () const;
590
    QString         takeControlFlightMode   () const;
DonLakeFlyer's avatar
DonLakeFlyer committed
591 592
    double          defaultCruiseSpeed      () const { return _defaultCruiseSpeed; }
    double          defaultHoverSpeed       () const { return _defaultHoverSpeed; }
593
    QString         firmwareTypeString      () const;
Gus Grubba's avatar
Gus Grubba committed
594 595 596 597 598 599
    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; }
600 601
    int             telemetryLNoise         () { return _telemetryLNoise; }
    int             telemetryRNoise         () { return _telemetryRNoise; }
602
    bool            autoDisarm              ();
603 604 605
    /// Get the maximum MAVLink protocol version supported
    /// @return the maximum version
    unsigned        maxProtoVersion         () const { return _maxProtoVersion; }
606

Don Gagne's avatar
Don Gagne committed
607 608 609 610 611 612 613 614
    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; }
615
    Fact* flightDistance    (void) { return &_flightDistanceFact; }
Don Gagne's avatar
Don Gagne committed
616

617 618 619 620
    FactGroup* gpsFactGroup         (void) { return &_gpsFactGroup; }
    FactGroup* batteryFactGroup     (void) { return &_batteryFactGroup; }
    FactGroup* windFactGroup        (void) { return &_windFactGroup; }
    FactGroup* vibrationFactGroup   (void) { return &_vibrationFactGroup; }
621
    FactGroup* temperatureFactGroup (void) { return &_temperatureFactGroup; }
Don Gagne's avatar
Don Gagne committed
622

623
    void setConnectionLostEnabled(bool connectionLostEnabled);
624

625 626
    ParameterManager* parameterManager(void) { return _parameterManager; }
    ParameterManager* parameterManager(void) const { return _parameterManager; }
dogmaphobic's avatar
dogmaphobic committed
627

Don Gagne's avatar
Don Gagne committed
628 629
    static const int cMaxRcChannels = 18;

Don Gagne's avatar
Don Gagne committed
630
    bool containsLink(LinkInterface* link) { return _links.contains(link); }
631 632 633 634 635 636

    /// 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
DonLakeFlyer's avatar
DonLakeFlyer committed
637
    /// Signals: mavCommandResult on success or failure
638
    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
639

Don Gagne's avatar
Don Gagne committed
640 641 642
    int firmwareMajorVersion(void) const { return _firmwareMajorVersion; }
    int firmwareMinorVersion(void) const { return _firmwareMinorVersion; }
    int firmwarePatchVersion(void) const { return _firmwarePatchVersion; }
643
    int firmwareVersionType(void) const { return _firmwareVersionType; }
644 645 646
    int firmwareCustomMajorVersion(void) const { return _firmwareCustomMajorVersion; }
    int firmwareCustomMinorVersion(void) const { return _firmwareCustomMinorVersion; }
    int firmwareCustomPatchVersion(void) const { return _firmwareCustomPatchVersion; }
647 648
    QString firmwareVersionTypeString(void) const;
    void setFirmwareVersion(int majorVersion, int minorVersion, int patchVersion, FIRMWARE_VERSION_TYPE versionType = FIRMWARE_VERSION_TYPE_OFFICIAL);
649
    void setFirmwareCustomVersion(int majorVersion, int minorVersion, int patchVersion);
650
    static const int versionNotSetValue = -1;
Don Gagne's avatar
Don Gagne committed
651

652 653
    QString gitHash(void) const { return _gitHash; }

654 655 656
    bool soloFirmware(void) const { return _soloFirmware; }
    void setSoloFirmware(bool soloFirmware);

657 658 659 660
    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
661

Don Gagne's avatar
Don Gagne committed
662 663 664 665 666 667 668 669 670
    /// @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);

671 672 673 674 675 676 677
    /// @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);

678 679 680 681
    QString vehicleImageOpaque  () const;
    QString vehicleImageOutline () const;
    QString vehicleImageCompass () const;

682 683
    const QVariantList& toolBarIndicators   ();
    const QVariantList& cameraList          (void) const;
684

685 686
    bool capabilitiesKnown      (void) const { return _vehicleCapabilitiesKnown; }
    uint64_t capabilityBits     (void) const { return _capabilityBits; }    // Change signalled by capabilityBitsChanged
687

688 689 690
    /// @true: When flying a mission the vehicle is always facing towards the next waypoint
    bool vehicleYawsToNextWaypointInMission(void) const;

DonLakeFlyer's avatar
DonLakeFlyer committed
691 692 693 694
    /// The vehicle is responsible for making the initial request for the Plan.
    /// @return: true: initial request is complete, false: initial request is still in progress;
    bool initialPlanRequestComplete(void) const { return _initialPlanRequestComplete; }

695 696
    void forceInitialPlanRequestComplete(void) { _initialPlanRequestComplete = true; }

697 698
    void _setFlying(bool flying);
    void _setLanding(bool landing);
DonLakeFlyer's avatar
DonLakeFlyer committed
699
    void _setHomePosition(QGeoCoordinate& homeCoord);
700
    void _setMaxProtoVersion (unsigned version);
DonLakeFlyer's avatar
DonLakeFlyer committed
701

702
signals:
Don Gagne's avatar
Don Gagne committed
703
    void allLinksInactive(Vehicle* vehicle);
704
    void coordinateChanged(QGeoCoordinate coordinate);
705
    void joystickModeChanged(int mode);
706 707
    void joystickEnabledChanged(bool enabled);
    void activeChanged(bool active);
Don Gagne's avatar
Don Gagne committed
708
    void mavlinkMessageReceived(const mavlink_message_t& message);
709
    void homePositionChanged(const QGeoCoordinate& homePosition);
Don Gagne's avatar
Don Gagne committed
710 711 712
    void armedChanged(bool armed);
    void flightModeChanged(const QString& flightMode);
    void hilModeChanged(bool hilMode);
713 714
    /** @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);
715 716
    void connectionLostChanged(bool connectionLost);
    void connectionLostEnabledChanged(bool connectionLostEnabled);
Don Gagne's avatar
Don Gagne committed
717
    void autoDisconnectChanged(bool autoDisconnectChanged);
Don Gagne's avatar
Don Gagne committed
718
    void flyingChanged(bool flying);
719
    void landingChanged(bool landing);
Don Gagne's avatar
Don Gagne committed
720
    void guidedModeChanged(bool guidedMode);
Don Gagne's avatar
Don Gagne committed
721
    void prearmErrorChanged(const QString& prearmError);
722
    void soloFirmwareChanged(bool soloFirmware);
723
    void unhealthySensorsChanged(void);
DonLakeFlyer's avatar
DonLakeFlyer committed
724 725
    void defaultCruiseSpeedChanged(double cruiseSpeed);
    void defaultHoverSpeedChanged(double hoverSpeed);
726 727
    void firmwareTypeChanged(void);
    void vehicleTypeChanged(void);
728
    void capabilitiesKnownChanged(bool capabilitiesKnown);
729 730
    void initialPlanRequestCompleted(void);
    void capabilityBitsChanged(uint64_t capabilityBits);
dogmaphobic's avatar
dogmaphobic committed
731

732 733 734 735
    void messagesReceivedChanged    ();
    void messagesSentChanged        ();
    void messagesLostChanged        ();

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

Gus Grubba's avatar
Gus Grubba committed
739 740 741 742 743 744 745 746 747 748 749 750 751 752 753
    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);
754 755
    void telemetryLNoiseChanged     (int value);
    void telemetryRNoiseChanged     (int value);
756
    void autoDisarmChanged          (void);
dogmaphobic's avatar
dogmaphobic committed
757

758 759
    void firmwareVersionChanged(void);
    void firmwareCustomVersionChanged(void);
760 761
    void gitHashChanged(QString hash);

Don Gagne's avatar
Don Gagne committed
762 763 764 765 766 767 768 769
    /// 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);

770 771 772 773 774
    void mavlinkRawImu(mavlink_message_t message);
    void mavlinkScaledImu1(mavlink_message_t message);
    void mavlinkScaledImu2(mavlink_message_t message);
    void mavlinkScaledImu3(mavlink_message_t message);

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

778 779 780 781 782 783
    /// 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
784
    void mavCommandResult(int vehicleId, int component, int command, int result, bool noReponseFromVehicle);
785

786
    // MAVlink Serial Data
787 788
    void mavlinkSerialControl(uint8_t device, uint8_t flags, uint16_t timeout, uint32_t baudrate, QByteArray data);

789 790 791
    // MAVLink protocol version
    void requestProtocolVersion(unsigned version);

792 793
private slots:
    void _mavlinkMessageReceived(LinkInterface* link, mavlink_message_t message);
Don Gagne's avatar
Don Gagne committed
794
    void _linkInactiveOrDeleted(LinkInterface* link);
795
    void _sendMessageOnLink(LinkInterface* link, mavlink_message_t message);
796
    void _sendMessageMultipleNext(void);
797
    void _addNewMapTrajectoryPoint(void);
798
    void _parametersReady(bool parametersReady);
Don Gagne's avatar
Don Gagne committed
799
    void _remoteControlRSSIChanged(uint8_t rssi);
Don Gagne's avatar
Don Gagne committed
800
    void _handleFlightModeChanged(const QString& flightMode);
801
    void _announceArmedChanged(bool armed);
802 803 804 805
    void _offlineFirmwareTypeSettingChanged(QVariant value);
    void _offlineVehicleTypeSettingChanged(QVariant value);
    void _offlineCruiseSpeedSettingChanged(QVariant value);
    void _offlineHoverSpeedSettingChanged(QVariant value);
806

807
    void _handleTextMessage                 (int newCount);
dogmaphobic's avatar
dogmaphobic committed
808
    void _handletextMessageReceived         (UASMessage* message);
809 810 811 812
    /** @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
813 814
    /** @brief A new camera image has arrived */
    void _imageReady                        (UASInterface* uas);
815
    void _connectionLostTimeout(void);
Don Gagne's avatar
Don Gagne committed
816
    void _prearmErrorTimeout(void);
DonLakeFlyer's avatar
DonLakeFlyer committed
817 818 819
    void _missionLoadComplete(void);
    void _geoFenceLoadComplete(void);
    void _rallyPointLoadComplete(void);
820
    void _sendMavCommandAgain(void);
Jacob Walser's avatar
Jacob Walser committed
821
    void _activeJoystickChanged(void);
822 823
    void _clearTrajectoryPoints(void);
    void _clearCameraTriggerPoints(void);
Jacob Walser's avatar
Jacob Walser committed
824

825 826 827
private:
    bool _containsLink(LinkInterface* link);
    void _addLink(LinkInterface* link);
828 829
    void _loadSettings(void);
    void _saveSettings(void);
830
    void _startJoystick(bool start);
Don Gagne's avatar
Don Gagne committed
831 832
    void _handleHomePosition(mavlink_message_t& message);
    void _handleHeartbeat(mavlink_message_t& message);
833
    void _handleRadioStatus(mavlink_message_t& message);
Don Gagne's avatar
Don Gagne committed
834 835
    void _handleRCChannels(mavlink_message_t& message);
    void _handleRCChannelsRaw(mavlink_message_t& message);
Don Gagne's avatar
Don Gagne committed
836 837
    void _handleBatteryStatus(mavlink_message_t& message);
    void _handleSysStatus(mavlink_message_t& message);
838
    void _handleWindCov(mavlink_message_t& message);
Don Gagne's avatar
Don Gagne committed
839
    void _handleWind(mavlink_message_t& message);
840
    void _handleVibration(mavlink_message_t& message);
Don Gagne's avatar
Don Gagne committed
841
    void _handleExtendedSysState(mavlink_message_t& message);
842
    void _handleCommandAck(mavlink_message_t& message);
843
    void _handleCommandLong(mavlink_message_t& message);
Gus Grubba's avatar
Gus Grubba committed
844
    void _handleAutopilotVersion(LinkInterface* link, mavlink_message_t& message);
845
    void _handleProtocolVersion(LinkInterface* link, mavlink_message_t& message);
846
    void _handleHilActuatorControls(mavlink_message_t& message);
847 848 849 850
    void _handleGpsRawInt(mavlink_message_t& message);
    void _handleGlobalPositionInt(mavlink_message_t& message);
    void _handleAltitude(mavlink_message_t& message);
    void _handleVfrHud(mavlink_message_t& message);
851 852 853
    void _handleScaledPressure(mavlink_message_t& message);
    void _handleScaledPressure2(mavlink_message_t& message);
    void _handleScaledPressure3(mavlink_message_t& message);
854 855
    void _handleCameraFeedback(const mavlink_message_t& message);
    void _handleCameraImageCaptured(const mavlink_message_t& message);
856
    void _handleADSBVehicle(const mavlink_message_t& message);
857
    void _missionManagerError(int errorCode, const QString& errorMsg);
858
    void _geoFenceManagerError(int errorCode, const QString& errorMsg);
859
    void _rallyPointManagerError(int errorCode, const QString& errorMsg);
860 861
    void _mapTrajectoryStart(void);
    void _mapTrajectoryStop(void);
862
    void _connectionActive(void);
863 864
    void _say(const QString& text);
    QString _vehicleIdSpeech(void);
865 866 867
    void _handleMavlinkLoggingData(mavlink_message_t& message);
    void _handleMavlinkLoggingDataAcked(mavlink_message_t& message);
    void _ackMavlinkLogData(uint16_t sequence);
868
    void _sendNextQueuedMavCommand(void);
869
    void _updatePriorityLink(void);
870
    void _commonInit(void);
DonLakeFlyer's avatar
DonLakeFlyer committed
871
    void _startPlanRequest(void);
872
    void _setupAutoDisarmSignalling(void);
DonLakeFlyer's avatar
DonLakeFlyer committed
873
    void _setCapabilities(uint64_t capabilityBits);
Don Gagne's avatar
Don Gagne committed
874

875
    int     _id;                    ///< Mavlink system id
876
    int     _defaultComponentId;
877
    bool    _active;
878
    bool    _offlineEditingVehicle; ///< This Vehicle is a "disconnected" vehicle for ui use while offline editing
dogmaphobic's avatar
dogmaphobic committed
879

880
    MAV_AUTOPILOT       _firmwareType;
881
    MAV_TYPE            _vehicleType;
882
    FirmwarePlugin*     _firmwarePlugin;
883
    QObject*            _firmwarePluginInstanceData;
884
    AutoPilotPlugin*    _autopilotPlugin;
Don Gagne's avatar
Don Gagne committed
885
    MAVLinkProtocol*    _mavlink;
886
    bool                _soloFirmware;
887
    QGCToolbox*         _toolbox;
888
    SettingsManager*    _settingsManager;
dogmaphobic's avatar
dogmaphobic committed
889

Don Gagne's avatar
Don Gagne committed
890
    QList<LinkInterface*> _links;
dogmaphobic's avatar
dogmaphobic committed
891

892
    JoystickMode_t  _joystickMode;
893
    bool            _joystickEnabled;
dogmaphobic's avatar
dogmaphobic committed
894

895
    UAS* _uas;
dogmaphobic's avatar
dogmaphobic committed
896

897
    QGeoCoordinate  _coordinate;
898
    QGeoCoordinate  _homePosition;
dogmaphobic's avatar
dogmaphobic committed
899

900 901 902 903 904 905 906 907 908
    UASInterface*   _mav;
    int             _currentMessageCount;
    int             _messageCount;
    int             _currentErrorCount;
    int             _currentWarningCount;
    int             _currentNormalCount;
    MessageType_t   _currentMessageType;
    QString         _latestError;
    int             _updateCount;
dogmaphobic's avatar
dogmaphobic committed
909
    QString         _formatedMessage;
Don Gagne's avatar
Don Gagne committed
910 911
    int             _rcRSSI;
    double          _rcRSSIstore;
Don Gagne's avatar
Don Gagne committed
912
    bool            _autoDisconnect;    ///< true: Automatically disconnect vehicle when last connection goes away or lost heartbeat
Don Gagne's avatar
Don Gagne committed
913
    bool            _flying;
914
    bool            _landing;
915 916 917 918
    uint32_t        _onboardControlSensorsPresent;
    uint32_t        _onboardControlSensorsEnabled;
    uint32_t        _onboardControlSensorsHealth;
    uint32_t        _onboardControlSensorsUnhealthy;
919 920
    bool            _gpsRawIntMessageAvailable;
    bool            _globalPositionIntMessageAvailable;
DonLakeFlyer's avatar
DonLakeFlyer committed
921 922
    double          _defaultCruiseSpeed;
    double          _defaultHoverSpeed;
Gus Grubba's avatar
Gus Grubba committed
923 924 925 926 927
    int             _telemetryRRSSI;
    int             _telemetryLRSSI;
    uint32_t        _telemetryRXErrors;
    uint32_t        _telemetryFixed;
    uint32_t        _telemetryTXBuffer;
928 929
    int             _telemetryLNoise;
    int             _telemetryRNoise;
930
    unsigned        _maxProtoVersion;
931
    bool            _vehicleCapabilitiesKnown;
932
    uint64_t        _capabilityBits;
dogmaphobic's avatar
dogmaphobic committed
933

934 935 936 937 938 939 940 941 942 943 944
    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;
945
    static const int                _mavCommandAckTimeoutMSecs = 3000;
946

Don Gagne's avatar
Don Gagne committed
947 948 949 950
    QString             _prearmError;
    QTimer              _prearmErrorTimer;
    static const int    _prearmErrorTimeoutMSecs = 35 * 1000;   ///< Take away prearm error after 35 seconds

951 952 953 954 955 956
    // Lost connection handling
    bool                _connectionLost;
    bool                _connectionLostEnabled;
    static const int    _connectionLostTimeoutMSecs = 3500;  // Signal connection lost after 3.5 seconds of missed heartbeat
    QTimer              _connectionLostTimer;

DonLakeFlyer's avatar
DonLakeFlyer committed
957 958
    bool                _initialPlanRequestComplete;

Don Gagne's avatar
Don Gagne committed
959
    MissionManager*     _missionManager;
960
    bool                _missionManagerInitialRequestSent;
961

962
    GeoFenceManager*    _geoFenceManager;
963 964 965 966
    bool                _geoFenceManagerInitialRequestSent;

    RallyPointManager*  _rallyPointManager;
    bool                _rallyPointManagerInitialRequestSent;
967

968
    ParameterManager*    _parameterManager;
dogmaphobic's avatar
dogmaphobic committed
969

Don Gagne's avatar
Don Gagne committed
970 971 972
    bool    _armed;         ///< true: vehicle is armed
    uint8_t _base_mode;     ///< base_mode from HEARTBEAT
    uint32_t _custom_mode;  ///< custom_mode from HEARTBEAT
973 974 975 976 977 978

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

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

982 983
    static const int _sendMessageMultipleRetries = 5;
    static const int _sendMessageMultipleIntraMessageDelay = 500;
dogmaphobic's avatar
dogmaphobic committed
984

985 986
    QTimer  _sendMultipleTimer;
    int     _nextSendMessageMultipleIndex;
dogmaphobic's avatar
dogmaphobic committed
987

988
    QTime               _flightTimer;
989 990 991 992 993
    QTimer              _mapTrajectoryTimer;
    QmlObjectListModel  _mapTrajectoryList;
    QGeoCoordinate      _mapTrajectoryLastCoordinate;
    bool                _mapTrajectoryHaveFirstCoordinate;
    static const int    _mapTrajectoryMsecsBetweenPoints = 1000;
994

995 996
    QmlObjectListModel  _cameraTriggerPoints;

997 998 999
    QmlObjectListModel              _adsbVehicles;
    QMap<uint32_t, ADSBVehicle*>    _adsbICAOMap;

1000
    // Toolbox references
dogmaphobic's avatar
dogmaphobic committed
1001 1002 1003 1004 1005
    FirmwarePluginManager*      _firmwarePluginManager;
    JoystickManager*            _joystickManager;

    int                         _flowImageIndex;

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

1008 1009 1010 1011 1012 1013 1014
    uint                _messagesReceived;
    uint                _messagesSent;
    uint                _messagesLost;
    uint8_t             _messageSeq;
    uint8_t             _compID;
    bool                _heardFrom;

Don Gagne's avatar
Don Gagne committed
1015 1016 1017
    int _firmwareMajorVersion;
    int _firmwareMinorVersion;
    int _firmwarePatchVersion;
1018 1019 1020
    int _firmwareCustomMajorVersion;
    int _firmwareCustomMinorVersion;
    int _firmwareCustomPatchVersion;
1021
    FIRMWARE_VERSION_TYPE _firmwareVersionType;
Don Gagne's avatar
Don Gagne committed
1022

1023 1024
    QString _gitHash;

1025
    int _lastAnnouncedLowBatteryPercent;
1026

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

Don Gagne's avatar
Don Gagne committed
1029 1030 1031 1032 1033 1034 1035 1036 1037 1038
    // FactGroup facts

    Fact _rollFact;
    Fact _pitchFact;
    Fact _headingFact;
    Fact _groundSpeedFact;
    Fact _airSpeedFact;
    Fact _climbRateFact;
    Fact _altitudeRelativeFact;
    Fact _altitudeAMSLFact;
1039
    Fact _flightDistanceFact;
1040
    Fact _flightTimeFact;
Don Gagne's avatar
Don Gagne committed
1041

1042 1043 1044 1045
    VehicleGPSFactGroup         _gpsFactGroup;
    VehicleBatteryFactGroup     _batteryFactGroup;
    VehicleWindFactGroup        _windFactGroup;
    VehicleVibrationFactGroup   _vibrationFactGroup;
1046
    VehicleTemperatureFactGroup _temperatureFactGroup;
Don Gagne's avatar
Don Gagne committed
1047 1048 1049 1050 1051 1052 1053 1054 1055

    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;
1056
    static const char* _flightDistanceFactName;
1057
    static const char* _flightTimeFactName;
Don Gagne's avatar
Don Gagne committed
1058

Don Gagne's avatar
Don Gagne committed
1059
    static const char* _gpsFactGroupName;
Don Gagne's avatar
Don Gagne committed
1060
    static const char* _batteryFactGroupName;
Don Gagne's avatar
Don Gagne committed
1061
    static const char* _windFactGroupName;
1062
    static const char* _vibrationFactGroupName;
1063
    static const char* _temperatureFactGroupName;
Don Gagne's avatar
Don Gagne committed
1064 1065 1066

    static const int _vehicleUIUpdateRateMSecs = 100;

1067
    // Settings keys
1068 1069
    static const char* _settingsGroup;
    static const char* _joystickModeSettingsKey;
1070
    static const char* _joystickEnabledSettingsKey;
Don Gagne's avatar
Don Gagne committed
1071

1072
};