Vehicle.h 48.6 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
class SettingsManager;
41 42 43

Q_DECLARE_LOGGING_CATEGORY(VehicleLog)

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

46 47 48 49 50 51 52 53 54 55 56 57 58 59
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)

60 61 62 63 64 65
    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; }
66 67 68 69 70 71 72 73 74 75 76 77 78 79 80 81 82

    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
83 84 85 86 87 88 89 90 91 92 93
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)

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

    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
108 109 110 111 112 113 114 115 116 117 118 119 120
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)

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

Don Gagne's avatar
Don Gagne committed
127 128 129 130 131 132
    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
133 134 135 136 137 138
private:
    Fact        _hdopFact;
    Fact        _vdopFact;
    Fact        _courseOverGroundFact;
    Fact        _countFact;
    Fact        _lockFact;
Don Gagne's avatar
Don Gagne committed
139
};
Don Gagne's avatar
Don Gagne committed
140

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


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

170 171
    static const char* _settingsGroup;

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

188 189 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
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
217
class Vehicle : public FactGroup
218 219
{
    Q_OBJECT
dogmaphobic's avatar
dogmaphobic committed
220

221
public:
222 223
    Vehicle(LinkInterface*          link,
            int                     vehicleId,
224
            int                     defaultComponentId,
225 226 227 228
            MAV_AUTOPILOT           firmwareType,
            MAV_TYPE                vehicleType,
            FirmwarePluginManager*  firmwarePluginManager,
            JoystickManager*        joystickManager);
229

230 231 232 233 234
    // 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);
235

236
    ~Vehicle();
dogmaphobic's avatar
dogmaphobic committed
237

238 239 240 241 242 243 244 245 246 247 248 249 250 251 252 253 254 255 256 257 258 259 260 261 262 263 264 265 266
    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)
267 268
    Q_PROPERTY(bool                 px4Firmware             READ px4Firmware                                            NOTIFY firmwareTypeChanged)
    Q_PROPERTY(bool                 apmFirmware             READ apmFirmware                                            NOTIFY firmwareTypeChanged)
269 270 271 272 273 274 275
    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)
276 277 278 279 280
    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)
281
    Q_PROPERTY(bool                 supportsManualControl   READ supportsManualControl                                  CONSTANT)
282
    Q_PROPERTY(bool        supportsThrottleModeCenterZero   READ supportsThrottleModeCenterZero                         CONSTANT)
283
    Q_PROPERTY(bool                 supportsJSButton        READ supportsJSButton                                       CONSTANT)
284
    Q_PROPERTY(bool                 supportsRadio           READ supportsRadio                                          CONSTANT)
285 286
    Q_PROPERTY(bool               supportsCalibratePressure READ supportsCalibratePressure                              CONSTANT)
    Q_PROPERTY(bool               supportsMotorInterference READ supportsMotorInterference                              CONSTANT)
287 288
    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
289 290 291
    Q_PROPERTY(int                  motorCount              READ motorCount                                             CONSTANT)
    Q_PROPERTY(bool                 coaxialMotors           READ coaxialMotors                                          CONSTANT)
    Q_PROPERTY(bool                 xConfigMotors           READ xConfigMotors                                          CONSTANT)
292
    Q_PROPERTY(bool                 isOfflineEditingVehicle READ isOfflineEditingVehicle                                CONSTANT)
293
    Q_PROPERTY(QString              brandImage              READ brandImage                                             NOTIFY firmwareTypeChanged)
294
    Q_PROPERTY(QStringList          unhealthySensors        READ unhealthySensors                                       NOTIFY unhealthySensorsChanged)
295 296 297
    Q_PROPERTY(QString              missionFlightMode       READ missionFlightMode                                      CONSTANT)
    Q_PROPERTY(QString              rtlFlightMode           READ rtlFlightMode                                          CONSTANT)
    Q_PROPERTY(QString              takeControlFlightMode   READ takeControlFlightMode                                  CONSTANT)
298 299
    Q_PROPERTY(QString              firmwareTypeString      READ firmwareTypeString                                     NOTIFY firmwareTypeChanged)
    Q_PROPERTY(QString              vehicleTypeString       READ vehicleTypeString                                      NOTIFY vehicleTypeChanged)
300 301 302
    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
303 304 305 306 307 308 309
    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)
310
    Q_PROPERTY(QVariantList         toolBarIndicators       READ toolBarIndicators                                      CONSTANT)
311
    Q_PROPERTY(QVariantList         cameraList              READ cameraList                                             CONSTANT)
312

Don Gagne's avatar
Don Gagne committed
313 314 315 316 317 318 319 320 321 322 323 324
    /// 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)

325 326 327
    /// true: Orbit mode is supported by this vehicle
    Q_PROPERTY(bool orbitModeSupported READ orbitModeSupported CONSTANT)

328 329
    Q_PROPERTY(ParameterManager* parameterManager READ parameterManager CONSTANT)

Don Gagne's avatar
Don Gagne committed
330 331 332 333 334 335 336 337 338 339 340
    // 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)

341 342 343 344 345
    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
346

347 348 349 350 351
    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)
352
    Q_PROPERTY(QString gitHash READ gitHash NOTIFY gitHashChanged)
353

354 355
    /// Resets link status counters
    Q_INVOKABLE void resetCounters  ();
356 357 358 359 360 361 362 363

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

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

Don Gagne's avatar
Don Gagne committed
368
    Q_INVOKABLE void virtualTabletJoystickValue(double roll, double pitch, double yaw, double thrust);
Don Gagne's avatar
Don Gagne committed
369
    Q_INVOKABLE void disconnectInactiveVehicle(void);
Don Gagne's avatar
Don Gagne committed
370

371 372
    Q_INVOKABLE void clearTrajectoryPoints(void);

Don Gagne's avatar
Don Gagne committed
373 374 375 376 377 378 379 380 381 382 383 384 385 386 387
    /// 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);

388 389 390 391 392 393 394
    /// 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
395 396 397 398 399 400 401
    /// 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);

402
    /// Command vehicle to abort landing
403
    Q_INVOKABLE void abortLanding(double climbOutAltitude);
404

405 406 407
    /// Alter the current mission item on the vehicle
    Q_INVOKABLE void setCurrentMissionSequence(int seq);

408 409 410
    /// Reboot vehicle
    Q_INVOKABLE void rebootVehicle();

dogmaphobic's avatar
dogmaphobic committed
411 412 413
    /// Clear Messages
    Q_INVOKABLE void clearMessages();

Don Gagne's avatar
Don Gagne committed
414 415
    Q_INVOKABLE void triggerCamera(void);

Don Gagne's avatar
Don Gagne committed
416 417
#if 0
    // Temporarily removed, waiting for new command implementation
Don Gagne's avatar
Don Gagne committed
418 419 420 421 422
    /// 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
423
#endif
Don Gagne's avatar
Don Gagne committed
424

Don Gagne's avatar
Don Gagne committed
425 426
    bool guidedModeSupported(void) const;
    bool pauseVehicleSupported(void) const;
427
    bool orbitModeSupported(void) const;
Don Gagne's avatar
Don Gagne committed
428

429
    // Property accessors
Don Gagne's avatar
Don Gagne committed
430

431 432
    QGeoCoordinate coordinate(void) { return _coordinate; }
    bool coordinateValid(void)      { return _coordinateValid; }
Don Gagne's avatar
Don Gagne committed
433
    void _setCoordinateValid(bool coordinateValid);
dogmaphobic's avatar
dogmaphobic committed
434

435
    typedef enum {
436
        JoystickModeRC,         ///< Joystick emulates an RC Transmitter
437 438 439 440 441 442
        JoystickModeAttitude,
        JoystickModePosition,
        JoystickModeForce,
        JoystickModeVelocity,
        JoystickModeMax
    } JoystickMode_t;
dogmaphobic's avatar
dogmaphobic committed
443

444 445
    int joystickMode(void);
    void setJoystickMode(int mode);
dogmaphobic's avatar
dogmaphobic committed
446

447 448
    /// List of joystick mode names
    QStringList joystickModes(void);
dogmaphobic's avatar
dogmaphobic committed
449

450 451
    bool joystickEnabled(void);
    void setJoystickEnabled(bool enabled);
dogmaphobic's avatar
dogmaphobic committed
452

453 454 455
    // Is vehicle active with respect to current active vehicle in QGC
    bool active(void);
    void setActive(bool active);
dogmaphobic's avatar
dogmaphobic committed
456

457 458
    // Property accesors
    int id(void) { return _id; }
459 460
    MAV_AUTOPILOT firmwareType(void) const { return _firmwareType; }
    MAV_TYPE vehicleType(void) const { return _vehicleType; }
461
    Q_INVOKABLE QString vehicleTypeName(void) const;
dogmaphobic's avatar
dogmaphobic committed
462

463 464 465
    /// 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(); }
466 467 468 469 470

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

471 472 473
    /// 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
474

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

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

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

484
    int manualControlReservedButtonCount(void);
dogmaphobic's avatar
dogmaphobic committed
485

486 487 488
    MissionManager*     missionManager(void)    { return _missionManager; }
    GeoFenceManager*    geoFenceManager(void)   { return _geoFenceManager; }
    RallyPointManager*  rallyPointManager(void) { return _rallyPointManager; }
dogmaphobic's avatar
dogmaphobic committed
489

490 491
    bool homePositionAvailable(void);
    QGeoCoordinate homePosition(void);
dogmaphobic's avatar
dogmaphobic committed
492

Don Gagne's avatar
Don Gagne committed
493 494 495 496 497
    bool armed(void) { return _armed; }
    void setArmed(bool armed);

    bool flightModeSetAvailable(void);
    QStringList flightModes(void);
Don Gagne's avatar
Don Gagne committed
498
    QString flightMode(void) const;
Don Gagne's avatar
Don Gagne committed
499 500 501 502
    void setFlightMode(const QString& flightMode);

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

504 505
    bool fixedWing(void) const;
    bool multiRotor(void) const;
Don Gagne's avatar
Don Gagne committed
506
    bool vtol(void) const;
Don Gagne's avatar
Don Gagne committed
507
    bool rover(void) const;
508
    bool sub(void) const;
509

510
    bool supportsManualControl(void) const;
511
    bool supportsThrottleModeCenterZero(void) const;
512
    bool supportsRadio(void) const;
513
    bool supportsJSButton(void) const;
514
    bool supportsCalibratePressure(void) const;
515
    bool supportsMotorInterference(void) const;
516

Don Gagne's avatar
Don Gagne committed
517 518 519
    void setFlying(bool flying);
    void setGuidedMode(bool guidedMode);

Don Gagne's avatar
Don Gagne committed
520 521 522
    QString prearmError(void) const { return _prearmError; }
    void setPrearmError(const QString& prearmError);

523
    QmlObjectListModel* trajectoryPoints(void) { return &_mapTrajectoryList; }
dogmaphobic's avatar
dogmaphobic committed
524 525 526

    int  flowImageIndex() { return _flowImageIndex; }

527 528 529 530
    //-- Mavlink Logging
    void startMavlinkLog();
    void stopMavlinkLog();

531 532 533
    /// 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
534 535
    ///     @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
536

537 538 539 540 541 542
    typedef enum {
        MessageNone,
        MessageNormal,
        MessageWarning,
        MessageError
    } MessageType_t;
dogmaphobic's avatar
dogmaphobic committed
543

544 545 546 547 548 549 550 551 552 553 554 555 556 557 558 559 560 561 562 563 564 565 566 567 568 569
    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; }
570
    QString         brandImage              () const;
571
    QStringList     unhealthySensors        () const;
572 573 574
    QString         missionFlightMode       () const;
    QString         rtlFlightMode           () const;
    QString         takeControlFlightMode   () const;
575 576 577
    double          cruiseSpeed             () const { return _cruiseSpeed; }
    double          hoverSpeed              () const { return _hoverSpeed; }
    QString         firmwareTypeString      () const;
Gus Grubba's avatar
Gus Grubba committed
578 579 580 581 582 583 584 585
    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; }
586

Don Gagne's avatar
Don Gagne committed
587 588 589 590 591 592 593 594 595
    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; }

596 597 598 599
    FactGroup* gpsFactGroup         (void) { return &_gpsFactGroup; }
    FactGroup* batteryFactGroup     (void) { return &_batteryFactGroup; }
    FactGroup* windFactGroup        (void) { return &_windFactGroup; }
    FactGroup* vibrationFactGroup   (void) { return &_vibrationFactGroup; }
600
    FactGroup* temperatureFactGroup (void) { return &_temperatureFactGroup; }
Don Gagne's avatar
Don Gagne committed
601

602
    void setConnectionLostEnabled(bool connectionLostEnabled);
603

604 605
    ParameterManager* parameterManager(void) { return _parameterManager; }
    ParameterManager* parameterManager(void) const { return _parameterManager; }
dogmaphobic's avatar
dogmaphobic committed
606

Don Gagne's avatar
Don Gagne committed
607 608
    static const int cMaxRcChannels = 18;

Don Gagne's avatar
Don Gagne committed
609
    bool containsLink(LinkInterface* link) { return _links.contains(link); }
610 611 612 613 614 615 616

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

Don Gagne's avatar
Don Gagne committed
618 619 620
    int firmwareMajorVersion(void) const { return _firmwareMajorVersion; }
    int firmwareMinorVersion(void) const { return _firmwareMinorVersion; }
    int firmwarePatchVersion(void) const { return _firmwarePatchVersion; }
621 622 623
    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);
624
    static const int versionNotSetValue = -1;
Don Gagne's avatar
Don Gagne committed
625

626 627
    QString gitHash(void) const { return _gitHash; }

628 629 630
    bool soloFirmware(void) const { return _soloFirmware; }
    void setSoloFirmware(bool soloFirmware);

631 632 633 634
    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
635

Don Gagne's avatar
Don Gagne committed
636 637 638 639 640 641 642 643 644
    /// @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);

645 646 647 648 649 650 651
    /// @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);

652 653 654 655
    QString vehicleImageOpaque  () const;
    QString vehicleImageOutline () const;
    QString vehicleImageCompass () const;

656 657
    const QVariantList& toolBarIndicators   ();
    const QVariantList& cameraList          (void) const;
658

659

660
public slots:
661 662 663 664 665
    /// 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 setLatitude    (double latitude);
    void setLongitude   (double longitude);
    void setAltitude    (double altitude);
dogmaphobic's avatar
dogmaphobic committed
666

667
signals:
Don Gagne's avatar
Don Gagne committed
668
    void allLinksInactive(Vehicle* vehicle);
669
    void coordinateChanged(QGeoCoordinate coordinate);
670
    void coordinateValidChanged(bool coordinateValid);
671
    void joystickModeChanged(int mode);
672 673
    void joystickEnabledChanged(bool enabled);
    void activeChanged(bool active);
Don Gagne's avatar
Don Gagne committed
674
    void mavlinkMessageReceived(const mavlink_message_t& message);
675 676
    void homePositionAvailableChanged(bool homePositionAvailable);
    void homePositionChanged(const QGeoCoordinate& homePosition);
Don Gagne's avatar
Don Gagne committed
677 678 679
    void armedChanged(bool armed);
    void flightModeChanged(const QString& flightMode);
    void hilModeChanged(bool hilMode);
680 681
    /** @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);
682 683
    void connectionLostChanged(bool connectionLost);
    void connectionLostEnabledChanged(bool connectionLostEnabled);
Don Gagne's avatar
Don Gagne committed
684
    void autoDisconnectChanged(bool autoDisconnectChanged);
Don Gagne's avatar
Don Gagne committed
685 686
    void flyingChanged(bool flying);
    void guidedModeChanged(bool guidedMode);
Don Gagne's avatar
Don Gagne committed
687
    void prearmErrorChanged(const QString& prearmError);
688
    void soloFirmwareChanged(bool soloFirmware);
689
    void unhealthySensorsChanged(void);
690 691 692 693
    void cruiseSpeedChanged(double cruiseSpeed);
    void hoverSpeedChanged(double hoverSpeed);
    void firmwareTypeChanged(void);
    void vehicleTypeChanged(void);
dogmaphobic's avatar
dogmaphobic committed
694

695 696 697 698
    void messagesReceivedChanged    ();
    void messagesSentChanged        ();
    void messagesLostChanged        ();

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

Gus Grubba's avatar
Gus Grubba committed
702 703 704 705 706 707 708 709 710 711 712 713 714 715 716 717 718
    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
719

720 721 722 723 724
    void firmwareMajorVersionChanged(int major);
    void firmwareMinorVersionChanged(int minor);
    void firmwarePatchVersionChanged(int patch);
    void firmwareVersionTypeChanged(int type);

725 726
    void gitHashChanged(QString hash);

Don Gagne's avatar
Don Gagne committed
727 728 729 730 731 732 733 734
    /// 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);

735 736 737 738 739
    void mavlinkRawImu(mavlink_message_t message);
    void mavlinkScaledImu1(mavlink_message_t message);
    void mavlinkScaledImu2(mavlink_message_t message);
    void mavlinkScaledImu3(mavlink_message_t message);

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

743 744 745 746 747 748
    /// 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
749
    void mavCommandResult(int vehicleId, int component, int command, int result, bool noReponseFromVehicle);
750

751 752
private slots:
    void _mavlinkMessageReceived(LinkInterface* link, mavlink_message_t message);
Gus Grubba's avatar
Gus Grubba committed
753
    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
754
    void _linkInactiveOrDeleted(LinkInterface* link);
755
    void _sendMessageOnLink(LinkInterface* link, mavlink_message_t message);
756
    void _sendMessageMultipleNext(void);
757
    void _addNewMapTrajectoryPoint(void);
758
    void _parametersReady(bool parametersReady);
Don Gagne's avatar
Don Gagne committed
759
    void _remoteControlRSSIChanged(uint8_t rssi);
Don Gagne's avatar
Don Gagne committed
760
    void _handleFlightModeChanged(const QString& flightMode);
761
    void _announceArmedChanged(bool armed);
762 763 764 765
    void _offlineFirmwareTypeSettingChanged(QVariant value);
    void _offlineVehicleTypeSettingChanged(QVariant value);
    void _offlineCruiseSpeedSettingChanged(QVariant value);
    void _offlineHoverSpeedSettingChanged(QVariant value);
766

767
    void _handleTextMessage                 (int newCount);
dogmaphobic's avatar
dogmaphobic committed
768
    void _handletextMessageReceived         (UASMessage* message);
769 770 771 772
    /** @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
773 774
    /** @brief A new camera image has arrived */
    void _imageReady                        (UASInterface* uas);
775
    void _connectionLostTimeout(void);
Don Gagne's avatar
Don Gagne committed
776
    void _prearmErrorTimeout(void);
777
    void _newMissionItemsAvailable(void);
778
    void _newGeoFenceAvailable(void);
779
    void _sendMavCommandAgain(void);
780

Jacob Walser's avatar
Jacob Walser committed
781 782
    void _activeJoystickChanged(void);

783 784 785
private:
    bool _containsLink(LinkInterface* link);
    void _addLink(LinkInterface* link);
786 787
    void _loadSettings(void);
    void _saveSettings(void);
788
    void _startJoystick(bool start);
Don Gagne's avatar
Don Gagne committed
789 790
    void _handleHomePosition(mavlink_message_t& message);
    void _handleHeartbeat(mavlink_message_t& message);
Don Gagne's avatar
Don Gagne committed
791 792
    void _handleRCChannels(mavlink_message_t& message);
    void _handleRCChannelsRaw(mavlink_message_t& message);
Don Gagne's avatar
Don Gagne committed
793 794
    void _handleBatteryStatus(mavlink_message_t& message);
    void _handleSysStatus(mavlink_message_t& message);
795
    void _handleWindCov(mavlink_message_t& message);
Don Gagne's avatar
Don Gagne committed
796
    void _handleWind(mavlink_message_t& message);
797
    void _handleVibration(mavlink_message_t& message);
Don Gagne's avatar
Don Gagne committed
798
    void _handleExtendedSysState(mavlink_message_t& message);
799
    void _handleCommandAck(mavlink_message_t& message);
Gus Grubba's avatar
Gus Grubba committed
800
    void _handleAutopilotVersion(LinkInterface* link, mavlink_message_t& message);
801
    void _handleHilActuatorControls(mavlink_message_t& message);
802 803 804 805
    void _handleGpsRawInt(mavlink_message_t& message);
    void _handleGlobalPositionInt(mavlink_message_t& message);
    void _handleAltitude(mavlink_message_t& message);
    void _handleVfrHud(mavlink_message_t& message);
806 807 808
    void _handleScaledPressure(mavlink_message_t& message);
    void _handleScaledPressure2(mavlink_message_t& message);
    void _handleScaledPressure3(mavlink_message_t& message);
809
    void _missionManagerError(int errorCode, const QString& errorMsg);
810
    void _geoFenceManagerError(int errorCode, const QString& errorMsg);
811
    void _rallyPointManagerError(int errorCode, const QString& errorMsg);
812 813
    void _mapTrajectoryStart(void);
    void _mapTrajectoryStop(void);
814
    void _connectionActive(void);
815 816
    void _say(const QString& text);
    QString _vehicleIdSpeech(void);
817 818 819
    void _handleMavlinkLoggingData(mavlink_message_t& message);
    void _handleMavlinkLoggingDataAcked(mavlink_message_t& message);
    void _ackMavlinkLogData(uint16_t sequence);
820
    void _sendNextQueuedMavCommand(void);
821
    void _updatePriorityLink(void);
822
    void _commonInit(void);
Don Gagne's avatar
Don Gagne committed
823

824
    int     _id;                    ///< Mavlink system id
825
    int     _defaultComponentId;
826
    bool    _active;
827
    bool    _offlineEditingVehicle; ///< This Vehicle is a "disconnected" vehicle for ui use while offline editing
dogmaphobic's avatar
dogmaphobic committed
828

829
    MAV_AUTOPILOT       _firmwareType;
830
    MAV_TYPE            _vehicleType;
831
    FirmwarePlugin*     _firmwarePlugin;
832
    QObject*            _firmwarePluginInstanceData;
833
    AutoPilotPlugin*    _autopilotPlugin;
Don Gagne's avatar
Don Gagne committed
834
    MAVLinkProtocol*    _mavlink;
835
    bool                _soloFirmware;
836
    SettingsManager*    _settingsManager;
dogmaphobic's avatar
dogmaphobic committed
837

Don Gagne's avatar
Don Gagne committed
838
    QList<LinkInterface*> _links;
dogmaphobic's avatar
dogmaphobic committed
839

840
    JoystickMode_t  _joystickMode;
841
    bool            _joystickEnabled;
dogmaphobic's avatar
dogmaphobic committed
842

843
    UAS* _uas;
dogmaphobic's avatar
dogmaphobic committed
844

845 846
    QGeoCoordinate  _coordinate;
    bool            _coordinateValid;       ///< true: vehicle has 3d lock and therefore valid location
dogmaphobic's avatar
dogmaphobic committed
847

848 849
    bool            _homePositionAvailable;
    QGeoCoordinate  _homePosition;
dogmaphobic's avatar
dogmaphobic committed
850

851 852 853 854 855 856 857 858 859
    UASInterface*   _mav;
    int             _currentMessageCount;
    int             _messageCount;
    int             _currentErrorCount;
    int             _currentWarningCount;
    int             _currentNormalCount;
    MessageType_t   _currentMessageType;
    QString         _latestError;
    int             _updateCount;
dogmaphobic's avatar
dogmaphobic committed
860
    QString         _formatedMessage;
Don Gagne's avatar
Don Gagne committed
861 862
    int             _rcRSSI;
    double          _rcRSSIstore;
Don Gagne's avatar
Don Gagne committed
863
    bool            _autoDisconnect;    ///< true: Automatically disconnect vehicle when last connection goes away or lost heartbeat
Don Gagne's avatar
Don Gagne committed
864
    bool            _flying;
865 866 867 868
    uint32_t        _onboardControlSensorsPresent;
    uint32_t        _onboardControlSensorsEnabled;
    uint32_t        _onboardControlSensorsHealth;
    uint32_t        _onboardControlSensorsUnhealthy;
869 870
    bool            _gpsRawIntMessageAvailable;
    bool            _globalPositionIntMessageAvailable;
871 872
    double          _cruiseSpeed;
    double          _hoverSpeed;
Gus Grubba's avatar
Gus Grubba committed
873 874 875 876 877 878 879
    int             _telemetryRRSSI;
    int             _telemetryLRSSI;
    uint32_t        _telemetryRXErrors;
    uint32_t        _telemetryFixed;
    uint32_t        _telemetryTXBuffer;
    uint32_t        _telemetryLNoise;
    uint32_t        _telemetryRNoise;
dogmaphobic's avatar
dogmaphobic committed
880

881 882 883 884 885 886 887 888 889 890 891
    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;
892
    static const int                _mavCommandAckTimeoutMSecs = 3000;
893

Don Gagne's avatar
Don Gagne committed
894 895 896 897
    QString             _prearmError;
    QTimer              _prearmErrorTimer;
    static const int    _prearmErrorTimeoutMSecs = 35 * 1000;   ///< Take away prearm error after 35 seconds

898 899 900 901 902 903
    // 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
904
    MissionManager*     _missionManager;
905
    bool                _missionManagerInitialRequestSent;
906

907
    GeoFenceManager*    _geoFenceManager;
908 909 910 911
    bool                _geoFenceManagerInitialRequestSent;

    RallyPointManager*  _rallyPointManager;
    bool                _rallyPointManagerInitialRequestSent;
912

913
    ParameterManager*    _parameterManager;
dogmaphobic's avatar
dogmaphobic committed
914

Don Gagne's avatar
Don Gagne committed
915 916 917
    bool    _armed;         ///< true: vehicle is armed
    uint8_t _base_mode;     ///< base_mode from HEARTBEAT
    uint32_t _custom_mode;  ///< custom_mode from HEARTBEAT
918 919 920 921 922 923

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

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

927 928
    static const int _sendMessageMultipleRetries = 5;
    static const int _sendMessageMultipleIntraMessageDelay = 500;
dogmaphobic's avatar
dogmaphobic committed
929

930 931
    QTimer  _sendMultipleTimer;
    int     _nextSendMessageMultipleIndex;
dogmaphobic's avatar
dogmaphobic committed
932

933 934 935 936 937
    QTimer              _mapTrajectoryTimer;
    QmlObjectListModel  _mapTrajectoryList;
    QGeoCoordinate      _mapTrajectoryLastCoordinate;
    bool                _mapTrajectoryHaveFirstCoordinate;
    static const int    _mapTrajectoryMsecsBetweenPoints = 1000;
938

939
    // Toolbox references
dogmaphobic's avatar
dogmaphobic committed
940 941 942 943 944
    FirmwarePluginManager*      _firmwarePluginManager;
    JoystickManager*            _joystickManager;

    int                         _flowImageIndex;

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

947 948 949 950 951 952 953
    uint                _messagesReceived;
    uint                _messagesSent;
    uint                _messagesLost;
    uint8_t             _messageSeq;
    uint8_t             _compID;
    bool                _heardFrom;

Don Gagne's avatar
Don Gagne committed
954 955 956
    int _firmwareMajorVersion;
    int _firmwareMinorVersion;
    int _firmwarePatchVersion;
957
    FIRMWARE_VERSION_TYPE _firmwareVersionType;
Don Gagne's avatar
Don Gagne committed
958

959 960
    QString _gitHash;

961 962 963
    static const int    _lowBatteryAnnounceRepeatMSecs; // Amount of time in between each low battery announcement
    QElapsedTimer       _lowBatteryAnnounceTimer;

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

Don Gagne's avatar
Don Gagne committed
966 967 968 969 970 971 972 973 974 975 976
    // FactGroup facts

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

977 978 979 980
    VehicleGPSFactGroup         _gpsFactGroup;
    VehicleBatteryFactGroup     _batteryFactGroup;
    VehicleWindFactGroup        _windFactGroup;
    VehicleVibrationFactGroup   _vibrationFactGroup;
981
    VehicleTemperatureFactGroup _temperatureFactGroup;
Don Gagne's avatar
Don Gagne committed
982 983 984 985 986 987 988 989 990

    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
991

Don Gagne's avatar
Don Gagne committed
992
    static const char* _gpsFactGroupName;
Don Gagne's avatar
Don Gagne committed
993
    static const char* _batteryFactGroupName;
Don Gagne's avatar
Don Gagne committed
994
    static const char* _windFactGroupName;
995
    static const char* _vibrationFactGroupName;
996
    static const char* _temperatureFactGroupName;
Don Gagne's avatar
Don Gagne committed
997 998 999

    static const int _vehicleUIUpdateRateMSecs = 100;

1000
    // Settings keys
1001 1002
    static const char* _settingsGroup;
    static const char* _joystickModeSettingsKey;
1003
    static const char* _joystickEnabledSettingsKey;
Don Gagne's avatar
Don Gagne committed
1004

1005 1006
};
#endif