Vehicle.h 57.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
class QGCCameraManager;
38 39 40
#if defined(QGC_AIRMAP_ENABLED)
class AirspaceVehicleManager;
#endif
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
class VehicleGPSFactGroup : public FactGroup
{
    Q_OBJECT

public:
    VehicleGPSFactGroup(QObject* parent = NULL);

115 116
    Q_PROPERTY(Fact* lat                READ lat                CONSTANT)
    Q_PROPERTY(Fact* lon                READ lon                CONSTANT)
Don Gagne's avatar
Don Gagne committed
117 118 119 120 121 122
    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)

123 124
    Fact* lat               (void) { return &_latFact; }
    Fact* lon               (void) { return &_lonFact; }
125 126 127 128 129
    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
130

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

Don Gagne's avatar
Don Gagne committed
149 150 151 152 153 154 155 156 157 158 159 160
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)
161
    Q_PROPERTY(Fact* cellCount          READ cellCount          CONSTANT)
162
    Q_PROPERTY(Fact* instantPower       READ instantPower       CONSTANT)
163 164 165 166 167 168 169

    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; }
170
    Fact* instantPower              (void) { return &_instantPowerFact; }
Don Gagne's avatar
Don Gagne committed
171 172 173 174 175 176 177 178


    static const char* _voltageFactName;
    static const char* _percentRemainingFactName;
    static const char* _mahConsumedFactName;
    static const char* _currentFactName;
    static const char* _temperatureFactName;
    static const char* _cellCountFactName;
179
    static const char* _instantPowerFactName;
Don Gagne's avatar
Don Gagne committed
180

181 182
    static const char* _settingsGroup;

Don Gagne's avatar
Don Gagne committed
183 184 185 186 187 188
    static const double _voltageUnavailable;
    static const int    _percentRemainingUnavailable;
    static const int    _mahConsumedUnavailable;
    static const int    _currentUnavailable;
    static const double _temperatureUnavailable;
    static const int    _cellCountUnavailable;
189
    static const double _instantPowerUnavailable;
Don Gagne's avatar
Don Gagne committed
190 191

private:
192 193 194 195 196 197
    Fact            _voltageFact;
    Fact            _percentRemainingFact;
    Fact            _mahConsumedFact;
    Fact            _currentFact;
    Fact            _temperatureFact;
    Fact            _cellCountFact;
198
    Fact            _instantPowerFact;
Don Gagne's avatar
Don Gagne committed
199 200
};

201 202 203 204 205 206 207 208 209 210 211 212 213 214 215 216 217 218 219 220 221 222 223 224 225 226 227 228 229
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;
};

dheideman's avatar
dheideman committed
230 231 232 233 234 235 236 237 238 239 240 241 242 243 244 245 246 247 248 249 250 251 252 253 254 255
class VehicleClockFactGroup : public FactGroup
{
    Q_OBJECT

public:
    VehicleClockFactGroup(QObject* parent = NULL);

    Q_PROPERTY(Fact* currentTime        READ currentTime        CONSTANT)
    Q_PROPERTY(Fact* currentDate        READ currentDate        CONSTANT)

    Fact* currentTime (void) { return &_currentTimeFact; }
    Fact* currentDate (void) { return &_currentDateFact; }

    static const char* _currentTimeFactName;
    static const char* _currentDateFactName;

    static const char* _settingsGroup;

private slots:
    void _updateAllValues(void) override;

private:
    Fact            _currentTimeFact;
    Fact            _currentDateFact;
};

Don Gagne's avatar
Don Gagne committed
256
class Vehicle : public FactGroup
257 258
{
    Q_OBJECT
dogmaphobic's avatar
dogmaphobic committed
259

260
public:
261 262
    Vehicle(LinkInterface*          link,
            int                     vehicleId,
263
            int                     defaultComponentId,
264 265 266 267
            MAV_AUTOPILOT           firmwareType,
            MAV_TYPE                vehicleType,
            FirmwarePluginManager*  firmwarePluginManager,
            JoystickManager*        joystickManager);
268

269 270 271 272 273
    // 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);
274

275
    ~Vehicle();
dogmaphobic's avatar
dogmaphobic committed
276

277 278 279 280 281
    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)
282
    Q_PROPERTY(bool                 autoDisarm              READ autoDisarm                                             NOTIFY autoDisarmChanged)
283 284 285 286 287
    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)
288
    Q_PROPERTY(QmlObjectListModel*  cameraTriggerPoints     READ cameraTriggerPoints                                    CONSTANT)
289 290 291 292 293 294 295 296 297 298 299 300 301 302 303 304 305
    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)
306 307
    Q_PROPERTY(bool                 px4Firmware             READ px4Firmware                                            NOTIFY firmwareTypeChanged)
    Q_PROPERTY(bool                 apmFirmware             READ apmFirmware                                            NOTIFY firmwareTypeChanged)
308 309 310 311 312 313 314
    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)
315 316 317 318 319
    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)
320
    Q_PROPERTY(bool        supportsThrottleModeCenterZero   READ supportsThrottleModeCenterZero                         CONSTANT)
321
    Q_PROPERTY(bool                supportsNegativeThrust   READ supportsNegativeThrust                                 CONSTANT)
322
    Q_PROPERTY(bool                 supportsJSButton        READ supportsJSButton                                       CONSTANT)
323
    Q_PROPERTY(bool                 supportsRadio           READ supportsRadio                                          CONSTANT)
324
    Q_PROPERTY(bool               supportsMotorInterference READ supportsMotorInterference                              CONSTANT)
325 326
    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
327 328 329
    Q_PROPERTY(int                  motorCount              READ motorCount                                             CONSTANT)
    Q_PROPERTY(bool                 coaxialMotors           READ coaxialMotors                                          CONSTANT)
    Q_PROPERTY(bool                 xConfigMotors           READ xConfigMotors                                          CONSTANT)
330
    Q_PROPERTY(bool                 isOfflineEditingVehicle READ isOfflineEditingVehicle                                CONSTANT)
331 332
    Q_PROPERTY(QString              brandImageIndoor        READ brandImageIndoor                                       NOTIFY firmwareTypeChanged)
    Q_PROPERTY(QString              brandImageOutdoor       READ brandImageOutdoor                                      NOTIFY firmwareTypeChanged)
333
    Q_PROPERTY(QStringList          unhealthySensors        READ unhealthySensors                                       NOTIFY unhealthySensorsChanged)
334
    Q_PROPERTY(QString              missionFlightMode       READ missionFlightMode                                      CONSTANT)
335
    Q_PROPERTY(QString              pauseFlightMode         READ pauseFlightMode                                        CONSTANT)
336
    Q_PROPERTY(QString              rtlFlightMode           READ rtlFlightMode                                          CONSTANT)
337
    Q_PROPERTY(QString              landFlightMode          READ landFlightMode                                         CONSTANT)
338
    Q_PROPERTY(QString              takeControlFlightMode   READ takeControlFlightMode                                  CONSTANT)
339 340
    Q_PROPERTY(QString              firmwareTypeString      READ firmwareTypeString                                     NOTIFY firmwareTypeChanged)
    Q_PROPERTY(QString              vehicleTypeString       READ vehicleTypeString                                      NOTIFY vehicleTypeChanged)
341 342 343
    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
344 345 346 347 348
    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)
349 350
    Q_PROPERTY(int                  telemetryLNoise         READ telemetryLNoise                                        NOTIFY telemetryLNoiseChanged)
    Q_PROPERTY(int                  telemetryRNoise         READ telemetryRNoise                                        NOTIFY telemetryRNoiseChanged)
351
    Q_PROPERTY(QVariantList         toolBarIndicators       READ toolBarIndicators                                      NOTIFY toolBarIndicatorsChanged)
352
    Q_PROPERTY(QmlObjectListModel*  adsbVehicles            READ adsbVehicles                                           CONSTANT)
Don Gagne's avatar
Don Gagne committed
353
    Q_PROPERTY(bool              initialPlanRequestComplete READ initialPlanRequestComplete                             NOTIFY initialPlanRequestCompleteChanged)
Gus Grubba's avatar
Gus Grubba committed
354
    Q_PROPERTY(QVariantList         staticCameraList        READ staticCameraList                                       CONSTANT)
355
    Q_PROPERTY(QGCCameraManager*    dynamicCameras          READ dynamicCameras                                         NOTIFY dynamicCamerasChanged)
356
    Q_PROPERTY(QString              hobbsMeter              READ hobbsMeter                                             NOTIFY hobbsMeterChanged)
357
    Q_PROPERTY(bool                 vtolInFwdFlight         READ vtolInFwdFlight        WRITE setVtolInFwdFlight        NOTIFY vtolInFwdFlightChanged)
358
    Q_PROPERTY(bool                 highLatencyLink         READ highLatencyLink                                        NOTIFY highLatencyLinkChanged)
359 360 361 362 363 364 365
    // Vehicle state used for guided control
    Q_PROPERTY(bool flying                  READ flying NOTIFY flyingChanged)                               ///< Vehicle is flying
    Q_PROPERTY(bool landing                 READ landing NOTIFY landingChanged)                             ///< Vehicle is in landing pattern (DO_LAND_START)
    Q_PROPERTY(bool guidedMode              READ guidedMode WRITE setGuidedMode NOTIFY guidedModeChanged)   ///< Vehicle is in Guided mode and can respond to guided commands
    Q_PROPERTY(bool guidedModeSupported     READ guidedModeSupported CONSTANT)                              ///< Guided mode commands are supported by this vehicle
    Q_PROPERTY(bool pauseVehicleSupported   READ pauseVehicleSupported CONSTANT)                            ///< Pause vehicle command is supported
    Q_PROPERTY(bool orbitModeSupported      READ orbitModeSupported CONSTANT)                               ///< Orbit mode is supported by this vehicle
366
    Q_PROPERTY(bool takeoffVehicleSupported READ takeoffVehicleSupported CONSTANT)                          ///< Guided takeoff supported    
367

368 369
    Q_PROPERTY(ParameterManager* parameterManager READ parameterManager CONSTANT)

Don Gagne's avatar
Don Gagne committed
370 371 372 373 374 375 376 377 378 379
    // 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)
380
    Q_PROPERTY(Fact* flightDistance     READ flightDistance     CONSTANT)
381
    Q_PROPERTY(Fact* distanceToHome     READ distanceToHome     CONSTANT)
382
    Q_PROPERTY(Fact* hobbs              READ hobbs              CONSTANT)
Don Gagne's avatar
Don Gagne committed
383

384 385 386 387 388
    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)
dheideman's avatar
dheideman committed
389
    Q_PROPERTY(FactGroup* clock       READ clockFactGroup       CONSTANT)
Don Gagne's avatar
Don Gagne committed
390

391 392 393 394 395 396 397 398 399
    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)
Gus Grubba's avatar
Gus Grubba committed
400 401
    Q_PROPERTY(quint64  vehicleUID                  READ vehicleUID                 NOTIFY vehicleUIDChanged)
    Q_PROPERTY(QString  vehicleUIDStr               READ vehicleUIDStr              NOTIFY vehicleUIDChanged)
402

403 404
    /// Resets link status counters
    Q_INVOKABLE void resetCounters  ();
405 406 407 408 409 410 411 412

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

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

Don Gagne's avatar
Don Gagne committed
417
    Q_INVOKABLE void virtualTabletJoystickValue(double roll, double pitch, double yaw, double thrust);
Don Gagne's avatar
Don Gagne committed
418
    Q_INVOKABLE void disconnectInactiveVehicle(void);
Don Gagne's avatar
Don Gagne committed
419

Don Gagne's avatar
Don Gagne committed
420 421 422 423 424 425 426
    /// 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
427
    Q_INVOKABLE void guidedModeTakeoff(double altitudeRelative);
Don Gagne's avatar
Don Gagne committed
428

429 430 431
    /// @return The minimum takeoff altitude (relative) for guided takeoff.
    Q_INVOKABLE double minimumTakeoffAltitude(void);

Don Gagne's avatar
Don Gagne committed
432 433 434
    /// Command vehicle to move to specified location (altitude is included and relative)
    Q_INVOKABLE void guidedModeGotoLocation(const QGeoCoordinate& gotoCoord);

435 436 437
    /// 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
438

439 440 441 442 443 444 445
    /// 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
446 447 448 449 450 451 452
    /// 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);

453
    /// Command vehicle to abort landing
454
    Q_INVOKABLE void abortLanding(double climbOutAltitude);
455

456 457
    Q_INVOKABLE void startMission(void);

458 459 460
    /// Alter the current mission item on the vehicle
    Q_INVOKABLE void setCurrentMissionSequence(int seq);

461 462 463
    /// Reboot vehicle
    Q_INVOKABLE void rebootVehicle();

dogmaphobic's avatar
dogmaphobic committed
464 465 466
    /// Clear Messages
    Q_INVOKABLE void clearMessages();

Don Gagne's avatar
Don Gagne committed
467
    Q_INVOKABLE void triggerCamera(void);
Don Gagne's avatar
Don Gagne committed
468
    Q_INVOKABLE void sendPlan(QString planFile);
Don Gagne's avatar
Don Gagne committed
469

Don Gagne's avatar
Don Gagne committed
470 471
#if 0
    // Temporarily removed, waiting for new command implementation
Don Gagne's avatar
Don Gagne committed
472 473 474 475 476
    /// 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
477
#endif
Don Gagne's avatar
Don Gagne committed
478

479 480 481 482
    bool guidedModeSupported    (void) const;
    bool pauseVehicleSupported  (void) const;
    bool orbitModeSupported     (void) const;
    bool takeoffVehicleSupported(void) const;
Don Gagne's avatar
Don Gagne committed
483

484
    // Property accessors
Don Gagne's avatar
Don Gagne committed
485

486
    QGeoCoordinate coordinate(void) { return _coordinate; }
dogmaphobic's avatar
dogmaphobic committed
487

488
    typedef enum {
489
        JoystickModeRC,         ///< Joystick emulates an RC Transmitter
490 491 492 493 494 495
        JoystickModeAttitude,
        JoystickModePosition,
        JoystickModeForce,
        JoystickModeVelocity,
        JoystickModeMax
    } JoystickMode_t;
dogmaphobic's avatar
dogmaphobic committed
496

497 498
    int joystickMode(void);
    void setJoystickMode(int mode);
dogmaphobic's avatar
dogmaphobic committed
499

500 501
    /// List of joystick mode names
    QStringList joystickModes(void);
dogmaphobic's avatar
dogmaphobic committed
502

503 504
    bool joystickEnabled(void);
    void setJoystickEnabled(bool enabled);
dogmaphobic's avatar
dogmaphobic committed
505

506 507 508
    // Is vehicle active with respect to current active vehicle in QGC
    bool active(void);
    void setActive(bool active);
dogmaphobic's avatar
dogmaphobic committed
509

510 511
    // Property accesors
    int id(void) { return _id; }
512 513
    MAV_AUTOPILOT firmwareType(void) const { return _firmwareType; }
    MAV_TYPE vehicleType(void) const { return _vehicleType; }
514
    Q_INVOKABLE QString vehicleTypeName(void) const;
dogmaphobic's avatar
dogmaphobic committed
515

Patrick José Pereira's avatar
Patrick José Pereira committed
516
    /// Returns the highest quality link available to the Vehicle. If you need to hold a reference to this link use
517 518
    /// LinkManager::sharedLinkInterfaceForGet to get QSharedPointer for link.
    LinkInterface* priorityLink(void) { return _priorityLink.data(); }
519 520 521 522 523

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

524 525 526
    /// 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
527

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

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

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

537
    int manualControlReservedButtonCount(void);
dogmaphobic's avatar
dogmaphobic committed
538

539 540 541
    MissionManager*     missionManager(void)    { return _missionManager; }
    GeoFenceManager*    geoFenceManager(void)   { return _geoFenceManager; }
    RallyPointManager*  rallyPointManager(void) { return _rallyPointManager; }
dogmaphobic's avatar
dogmaphobic committed
542

543
    QGeoCoordinate homePosition(void);
dogmaphobic's avatar
dogmaphobic committed
544

Don Gagne's avatar
Don Gagne committed
545 546 547 548 549
    bool armed(void) { return _armed; }
    void setArmed(bool armed);

    bool flightModeSetAvailable(void);
    QStringList flightModes(void);
Don Gagne's avatar
Don Gagne committed
550
    QString flightMode(void) const;
Don Gagne's avatar
Don Gagne committed
551 552 553 554
    void setFlightMode(const QString& flightMode);

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

556 557
    bool fixedWing(void) const;
    bool multiRotor(void) const;
Don Gagne's avatar
Don Gagne committed
558
    bool vtol(void) const;
Don Gagne's avatar
Don Gagne committed
559
    bool rover(void) const;
560
    bool sub(void) const;
561

562
    bool supportsThrottleModeCenterZero(void) const;
563
    bool supportsNegativeThrust(void) const;
564
    bool supportsRadio(void) const;
565
    bool supportsJSButton(void) const;
566
    bool supportsMotorInterference(void) const;
567

Don Gagne's avatar
Don Gagne committed
568 569
    void setGuidedMode(bool guidedMode);

Don Gagne's avatar
Don Gagne committed
570 571 572
    QString prearmError(void) const { return _prearmError; }
    void setPrearmError(const QString& prearmError);

573
    QmlObjectListModel* trajectoryPoints(void) { return &_mapTrajectoryList; }
574
    QmlObjectListModel* cameraTriggerPoints(void) { return &_cameraTriggerPoints; }
575
    QmlObjectListModel* adsbVehicles(void) { return &_adsbVehicles; }
dogmaphobic's avatar
dogmaphobic committed
576 577 578

    int  flowImageIndex() { return _flowImageIndex; }

579 580 581 582
    //-- Mavlink Logging
    void startMavlinkLog();
    void stopMavlinkLog();

583 584 585
    /// 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
586 587
    ///     @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
588

589 590 591 592 593 594
    typedef enum {
        MessageNone,
        MessageNormal,
        MessageWarning,
        MessageError
    } MessageType_t;
dogmaphobic's avatar
dogmaphobic committed
595

596 597 598 599 600 601 602 603 604 605 606 607 608 609 610 611 612 613 614 615 616 617
    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; }
618
    bool            landing                 () const { return _landing; }
619
    bool            guidedMode              () const;
620
    bool            vtolInFwdFlight         () const { return _vtolInFwdFlight; }
621 622 623
    uint8_t         baseMode                () const { return _base_mode; }
    uint32_t        customMode              () const { return _custom_mode; }
    bool            isOfflineEditingVehicle () const { return _offlineEditingVehicle; }
624 625
    QString         brandImageIndoor        () const;
    QString         brandImageOutdoor       () const;
626
    QStringList     unhealthySensors        () const;
627
    QString         missionFlightMode       () const;
628
    QString         pauseFlightMode         () const;
629
    QString         rtlFlightMode           () const;
630
    QString         landFlightMode          () const;
631
    QString         takeControlFlightMode   () const;
DonLakeFlyer's avatar
DonLakeFlyer committed
632 633
    double          defaultCruiseSpeed      () const { return _defaultCruiseSpeed; }
    double          defaultHoverSpeed       () const { return _defaultHoverSpeed; }
634
    QString         firmwareTypeString      () const;
Gus Grubba's avatar
Gus Grubba committed
635 636 637 638 639 640
    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; }
641 642
    int             telemetryLNoise         () { return _telemetryLNoise; }
    int             telemetryRNoise         () { return _telemetryRNoise; }
643
    bool            autoDisarm              ();
644
    bool            highLatencyLink         () const { return _highLatencyLink; }
645 646 647
    /// Get the maximum MAVLink protocol version supported
    /// @return the maximum version
    unsigned        maxProtoVersion         () const { return _maxProtoVersion; }
648

Don Gagne's avatar
Don Gagne committed
649 650 651 652 653 654 655 656
    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; }
657
    Fact* flightDistance    (void) { return &_flightDistanceFact; }
658
    Fact* distanceToHome    (void) { return &_distanceToHomeFact; }
659
    Fact* hobbs             (void) { return &_hobbsFact; }
Don Gagne's avatar
Don Gagne committed
660

661 662 663 664
    FactGroup* gpsFactGroup         (void) { return &_gpsFactGroup; }
    FactGroup* batteryFactGroup     (void) { return &_batteryFactGroup; }
    FactGroup* windFactGroup        (void) { return &_windFactGroup; }
    FactGroup* vibrationFactGroup   (void) { return &_vibrationFactGroup; }
665
    FactGroup* temperatureFactGroup (void) { return &_temperatureFactGroup; }
dheideman's avatar
dheideman committed
666
    FactGroup* clockFactGroup       (void) { return &_clockFactGroup; }
Don Gagne's avatar
Don Gagne committed
667

668
    void setConnectionLostEnabled(bool connectionLostEnabled);
669

670 671
    ParameterManager* parameterManager(void) { return _parameterManager; }
    ParameterManager* parameterManager(void) const { return _parameterManager; }
dogmaphobic's avatar
dogmaphobic committed
672

Don Gagne's avatar
Don Gagne committed
673 674
    static const int cMaxRcChannels = 18;

Don Gagne's avatar
Don Gagne committed
675
    bool containsLink(LinkInterface* link) { return _links.contains(link); }
676 677 678 679 680 681

    /// 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
682
    /// Signals: mavCommandResult on success or failure
683
    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
684

685 686 687 688
    /// Same as sendMavCommand but available from Qml.
    Q_INVOKABLE void sendCommand(int component, int command, bool showError, double param1 = 0.0f, double param2 = 0.0f, double param3 = 0.0f, double param4 = 0.0f, double param5 = 0.0f, double param6 = 0.0f, double param7 = 0.0f)
        { sendMavCommand(component, (MAV_CMD)command, showError, param1, param2, param3, param4, param5, param6, param7); }

Don Gagne's avatar
Don Gagne committed
689 690 691
    int firmwareMajorVersion(void) const { return _firmwareMajorVersion; }
    int firmwareMinorVersion(void) const { return _firmwareMinorVersion; }
    int firmwarePatchVersion(void) const { return _firmwarePatchVersion; }
692
    int firmwareVersionType(void) const { return _firmwareVersionType; }
693 694 695
    int firmwareCustomMajorVersion(void) const { return _firmwareCustomMajorVersion; }
    int firmwareCustomMinorVersion(void) const { return _firmwareCustomMinorVersion; }
    int firmwareCustomPatchVersion(void) const { return _firmwareCustomPatchVersion; }
696 697
    QString firmwareVersionTypeString(void) const;
    void setFirmwareVersion(int majorVersion, int minorVersion, int patchVersion, FIRMWARE_VERSION_TYPE versionType = FIRMWARE_VERSION_TYPE_OFFICIAL);
698
    void setFirmwareCustomVersion(int majorVersion, int minorVersion, int patchVersion);
699
    static const int versionNotSetValue = -1;
Don Gagne's avatar
Don Gagne committed
700

701
    QString gitHash(void) const { return _gitHash; }
Gus Grubba's avatar
Gus Grubba committed
702 703
    quint64 vehicleUID(void) const { return _uid; }
    QString vehicleUIDStr();
704

705 706 707
    bool soloFirmware(void) const { return _soloFirmware; }
    void setSoloFirmware(bool soloFirmware);

708 709 710 711
    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
712

Don Gagne's avatar
Don Gagne committed
713 714 715 716 717 718 719 720 721
    /// @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);

722 723 724 725 726 727 728
    /// @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);

729 730 731 732
    QString vehicleImageOpaque  () const;
    QString vehicleImageOutline () const;
    QString vehicleImageCompass () const;

733
    const QVariantList&         toolBarIndicators   ();
Gus Grubba's avatar
Gus Grubba committed
734
    const QVariantList&         staticCameraList    (void) const;
735

736 737
    bool capabilitiesKnown      (void) const { return _vehicleCapabilitiesKnown; }
    uint64_t capabilityBits     (void) const { return _capabilityBits; }    // Change signalled by capabilityBitsChanged
738

739
    QGCCameraManager*           dynamicCameras      () { return _cameras; }
740
    QString                     hobbsMeter          ();
741

742 743 744
    /// @true: When flying a mission the vehicle is always facing towards the next waypoint
    bool vehicleYawsToNextWaypointInMission(void) const;

DonLakeFlyer's avatar
DonLakeFlyer committed
745 746 747 748
    /// 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; }

Don Gagne's avatar
Don Gagne committed
749
    void forceInitialPlanRequestComplete(void);
750

751 752
    void _setFlying(bool flying);
    void _setLanding(bool landing);
753
    void setVtolInFwdFlight(bool vtolInFwdFlight);
DonLakeFlyer's avatar
DonLakeFlyer committed
754
    void _setHomePosition(QGeoCoordinate& homeCoord);
755
    void _setMaxProtoVersion (unsigned version);
DonLakeFlyer's avatar
DonLakeFlyer committed
756

757 758 759
    /// Vehicle is about to be deleted
    void prepareDelete();

760
signals:
Don Gagne's avatar
Don Gagne committed
761
    void allLinksInactive(Vehicle* vehicle);
762
    void coordinateChanged(QGeoCoordinate coordinate);
763
    void joystickModeChanged(int mode);
764 765
    void joystickEnabledChanged(bool enabled);
    void activeChanged(bool active);
Don Gagne's avatar
Don Gagne committed
766
    void mavlinkMessageReceived(const mavlink_message_t& message);
767
    void homePositionChanged(const QGeoCoordinate& homePosition);
Don Gagne's avatar
Don Gagne committed
768 769 770
    void armedChanged(bool armed);
    void flightModeChanged(const QString& flightMode);
    void hilModeChanged(bool hilMode);
771 772
    /** @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);
773 774
    void connectionLostChanged(bool connectionLost);
    void connectionLostEnabledChanged(bool connectionLostEnabled);
Don Gagne's avatar
Don Gagne committed
775
    void autoDisconnectChanged(bool autoDisconnectChanged);
Don Gagne's avatar
Don Gagne committed
776
    void flyingChanged(bool flying);
777
    void landingChanged(bool landing);
Don Gagne's avatar
Don Gagne committed
778
    void guidedModeChanged(bool guidedMode);
779
    void vtolInFwdFlightChanged(bool vtolInFwdFlight);
Don Gagne's avatar
Don Gagne committed
780
    void prearmErrorChanged(const QString& prearmError);
781
    void soloFirmwareChanged(bool soloFirmware);
782
    void unhealthySensorsChanged(void);
DonLakeFlyer's avatar
DonLakeFlyer committed
783 784
    void defaultCruiseSpeedChanged(double cruiseSpeed);
    void defaultHoverSpeedChanged(double hoverSpeed);
785 786
    void firmwareTypeChanged(void);
    void vehicleTypeChanged(void);
787
    void dynamicCamerasChanged();
788
    void hobbsMeterChanged();
789
    void capabilitiesKnownChanged(bool capabilitiesKnown);
Don Gagne's avatar
Don Gagne committed
790
    void initialPlanRequestCompleteChanged(bool initialPlanRequestComplete);
791
    void capabilityBitsChanged(uint64_t capabilityBits);
792
    void toolBarIndicatorsChanged(void);
793
    void highLatencyLinkChanged(bool highLatencyLink);
dogmaphobic's avatar
dogmaphobic committed
794

795 796 797 798
    void messagesReceivedChanged    ();
    void messagesSentChanged        ();
    void messagesLostChanged        ();

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

Gus Grubba's avatar
Gus Grubba committed
802 803 804 805 806 807 808 809 810 811 812 813 814 815 816
    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);
817 818
    void telemetryLNoiseChanged     (int value);
    void telemetryRNoiseChanged     (int value);
819
    void autoDisarmChanged          (void);
dogmaphobic's avatar
dogmaphobic committed
820

821 822
    void firmwareVersionChanged(void);
    void firmwareCustomVersionChanged(void);
823
    void gitHashChanged(QString hash);
Gus Grubba's avatar
Gus Grubba committed
824
    void vehicleUIDChanged();
825

Don Gagne's avatar
Don Gagne committed
826 827 828 829 830 831 832 833
    /// 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);

834 835 836 837 838
    void mavlinkRawImu(mavlink_message_t message);
    void mavlinkScaledImu1(mavlink_message_t message);
    void mavlinkScaledImu2(mavlink_message_t message);
    void mavlinkScaledImu3(mavlink_message_t message);

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

842 843 844 845 846 847
    /// 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
848
    void mavCommandResult(int vehicleId, int component, int command, int result, bool noReponseFromVehicle);
849

850
    // MAVlink Serial Data
851 852
    void mavlinkSerialControl(uint8_t device, uint8_t flags, uint16_t timeout, uint32_t baudrate, QByteArray data);

853 854 855
    // MAVLink protocol version
    void requestProtocolVersion(unsigned version);

856 857
private slots:
    void _mavlinkMessageReceived(LinkInterface* link, mavlink_message_t message);
Don Gagne's avatar
Don Gagne committed
858
    void _linkInactiveOrDeleted(LinkInterface* link);
859
    void _sendMessageOnLink(LinkInterface* link, mavlink_message_t message);
860
    void _sendMessageMultipleNext(void);
861
    void _addNewMapTrajectoryPoint(void);
862
    void _parametersReady(bool parametersReady);
Don Gagne's avatar
Don Gagne committed
863
    void _remoteControlRSSIChanged(uint8_t rssi);
Don Gagne's avatar
Don Gagne committed
864
    void _handleFlightModeChanged(const QString& flightMode);
865
    void _announceArmedChanged(bool armed);
866 867 868 869
    void _offlineFirmwareTypeSettingChanged(QVariant value);
    void _offlineVehicleTypeSettingChanged(QVariant value);
    void _offlineCruiseSpeedSettingChanged(QVariant value);
    void _offlineHoverSpeedSettingChanged(QVariant value);
870
    void _updateHighLatencyLink(void);
871

872
    void _handleTextMessage                 (int newCount);
dogmaphobic's avatar
dogmaphobic committed
873
    void _handletextMessageReceived         (UASMessage* message);
874 875 876 877
    /** @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
878 879
    /** @brief A new camera image has arrived */
    void _imageReady                        (UASInterface* uas);
880
    void _connectionLostTimeout(void);
Don Gagne's avatar
Don Gagne committed
881
    void _prearmErrorTimeout(void);
DonLakeFlyer's avatar
DonLakeFlyer committed
882 883 884
    void _missionLoadComplete(void);
    void _geoFenceLoadComplete(void);
    void _rallyPointLoadComplete(void);
885
    void _sendMavCommandAgain(void);
886 887
    void _clearTrajectoryPoints(void);
    void _clearCameraTriggerPoints(void);
888
    void _updateDistanceToHome(void);
889 890
    void _updateHobbsMeter(void);
    void _vehicleParamLoaded(bool ready);
Jacob Walser's avatar
Jacob Walser committed
891

Gus Grubba's avatar
Gus Grubba committed
892 893
    void _trafficUpdate         (bool alert, QString traffic_id, QString vehicle_id, QGeoCoordinate location, float heading);
    void _adsbTimerTimeout      ();
894

895 896 897
private:
    bool _containsLink(LinkInterface* link);
    void _addLink(LinkInterface* link);
898 899
    void _loadSettings(void);
    void _saveSettings(void);
900
    void _startJoystick(bool start);
Don Gagne's avatar
Don Gagne committed
901 902
    void _handleHomePosition(mavlink_message_t& message);
    void _handleHeartbeat(mavlink_message_t& message);
903
    void _handleRadioStatus(mavlink_message_t& message);
Don Gagne's avatar
Don Gagne committed
904 905
    void _handleRCChannels(mavlink_message_t& message);
    void _handleRCChannelsRaw(mavlink_message_t& message);
Don Gagne's avatar
Don Gagne committed
906 907
    void _handleBatteryStatus(mavlink_message_t& message);
    void _handleSysStatus(mavlink_message_t& message);
908
    void _handleWindCov(mavlink_message_t& message);
909
    void _handleVibration(mavlink_message_t& message);
Don Gagne's avatar
Don Gagne committed
910
    void _handleExtendedSysState(mavlink_message_t& message);
911
    void _handleCommandAck(mavlink_message_t& message);
912
    void _handleCommandLong(mavlink_message_t& message);
Gus Grubba's avatar
Gus Grubba committed
913
    void _handleAutopilotVersion(LinkInterface* link, mavlink_message_t& message);
914
    void _handleProtocolVersion(LinkInterface* link, mavlink_message_t& message);
915
    void _handleHilActuatorControls(mavlink_message_t& message);
916 917 918 919
    void _handleGpsRawInt(mavlink_message_t& message);
    void _handleGlobalPositionInt(mavlink_message_t& message);
    void _handleAltitude(mavlink_message_t& message);
    void _handleVfrHud(mavlink_message_t& message);
920 921 922
    void _handleScaledPressure(mavlink_message_t& message);
    void _handleScaledPressure2(mavlink_message_t& message);
    void _handleScaledPressure3(mavlink_message_t& message);
923
    void _handleHighLatency2(mavlink_message_t& message);
924 925
    // ArduPilot dialect messages
#if !defined(NO_ARDUPILOT_DIALECT)
926
    void _handleCameraFeedback(const mavlink_message_t& message);
927 928
    void _handleWind(mavlink_message_t& message);
#endif
929
    void _handleCameraImageCaptured(const mavlink_message_t& message);
930
    void _handleADSBVehicle(const mavlink_message_t& message);
931
    void _missionManagerError(int errorCode, const QString& errorMsg);
932
    void _geoFenceManagerError(int errorCode, const QString& errorMsg);
933
    void _rallyPointManagerError(int errorCode, const QString& errorMsg);
934 935
    void _mapTrajectoryStart(void);
    void _mapTrajectoryStop(void);
936
    void _connectionActive(void);
937 938
    void _say(const QString& text);
    QString _vehicleIdSpeech(void);
939 940 941
    void _handleMavlinkLoggingData(mavlink_message_t& message);
    void _handleMavlinkLoggingDataAcked(mavlink_message_t& message);
    void _ackMavlinkLogData(uint16_t sequence);
942
    void _sendNextQueuedMavCommand(void);
943
    void _updatePriorityLink(void);
944
    void _commonInit(void);
DonLakeFlyer's avatar
DonLakeFlyer committed
945
    void _startPlanRequest(void);
946
    void _setupAutoDisarmSignalling(void);
DonLakeFlyer's avatar
DonLakeFlyer committed
947
    void _setCapabilities(uint64_t capabilityBits);
Don Gagne's avatar
Don Gagne committed
948

949
    int     _id;                    ///< Mavlink system id
950
    int     _defaultComponentId;
951
    bool    _active;
952
    bool    _offlineEditingVehicle; ///< This Vehicle is a "disconnected" vehicle for ui use while offline editing
dogmaphobic's avatar
dogmaphobic committed
953

954
    MAV_AUTOPILOT       _firmwareType;
955
    MAV_TYPE            _vehicleType;
956
    FirmwarePlugin*     _firmwarePlugin;
957
    QObject*            _firmwarePluginInstanceData;
958
    AutoPilotPlugin*    _autopilotPlugin;
Don Gagne's avatar
Don Gagne committed
959
    MAVLinkProtocol*    _mavlink;
960
    bool                _soloFirmware;
961
    QGCToolbox*         _toolbox;
962
    SettingsManager*    _settingsManager;
dogmaphobic's avatar
dogmaphobic committed
963

Don Gagne's avatar
Don Gagne committed
964
    QList<LinkInterface*> _links;
dogmaphobic's avatar
dogmaphobic committed
965

966
    JoystickMode_t  _joystickMode;
967
    bool            _joystickEnabled;
dogmaphobic's avatar
dogmaphobic committed
968

969
    UAS* _uas;
dogmaphobic's avatar
dogmaphobic committed
970

971
    QGeoCoordinate  _coordinate;
972
    QGeoCoordinate  _homePosition;
dogmaphobic's avatar
dogmaphobic committed
973

974 975 976 977 978 979 980 981 982
    UASInterface*   _mav;
    int             _currentMessageCount;
    int             _messageCount;
    int             _currentErrorCount;
    int             _currentWarningCount;
    int             _currentNormalCount;
    MessageType_t   _currentMessageType;
    QString         _latestError;
    int             _updateCount;
dogmaphobic's avatar
dogmaphobic committed
983
    QString         _formatedMessage;
Don Gagne's avatar
Don Gagne committed
984 985
    int             _rcRSSI;
    double          _rcRSSIstore;
Don Gagne's avatar
Don Gagne committed
986
    bool            _autoDisconnect;    ///< true: Automatically disconnect vehicle when last connection goes away or lost heartbeat
Don Gagne's avatar
Don Gagne committed
987
    bool            _flying;
988
    bool            _landing;
989
    bool            _vtolInFwdFlight;
990 991 992 993
    uint32_t        _onboardControlSensorsPresent;
    uint32_t        _onboardControlSensorsEnabled;
    uint32_t        _onboardControlSensorsHealth;
    uint32_t        _onboardControlSensorsUnhealthy;
994 995
    bool            _gpsRawIntMessageAvailable;
    bool            _globalPositionIntMessageAvailable;
DonLakeFlyer's avatar
DonLakeFlyer committed
996 997
    double          _defaultCruiseSpeed;
    double          _defaultHoverSpeed;
Gus Grubba's avatar
Gus Grubba committed
998 999 1000 1001 1002
    int             _telemetryRRSSI;
    int             _telemetryLRSSI;
    uint32_t        _telemetryRXErrors;
    uint32_t        _telemetryFixed;
    uint32_t        _telemetryTXBuffer;
1003 1004
    int             _telemetryLNoise;
    int             _telemetryRNoise;
1005
    unsigned        _maxProtoVersion;
1006
    bool            _vehicleCapabilitiesKnown;
1007
    uint64_t        _capabilityBits;
1008
    bool            _highLatencyLink;
dogmaphobic's avatar
dogmaphobic committed
1009

1010 1011
    QGCCameraManager* _cameras;

1012 1013 1014 1015 1016 1017 1018 1019 1020 1021 1022
    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;
1023
    static const int                _mavCommandAckTimeoutMSecs = 3000;
DonLakeFlyer's avatar
DonLakeFlyer committed
1024
    static const int                _mavCommandAckTimeoutMSecsHighLatency = 120000;
1025

Don Gagne's avatar
Don Gagne committed
1026 1027 1028 1029
    QString             _prearmError;
    QTimer              _prearmErrorTimer;
    static const int    _prearmErrorTimeoutMSecs = 35 * 1000;   ///< Take away prearm error after 35 seconds

1030 1031 1032 1033 1034 1035
    // 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
1036 1037
    bool                _initialPlanRequestComplete;

Don Gagne's avatar
Don Gagne committed
1038
    MissionManager*     _missionManager;
1039
    bool                _missionManagerInitialRequestSent;
1040

1041
    GeoFenceManager*    _geoFenceManager;
1042 1043 1044 1045
    bool                _geoFenceManagerInitialRequestSent;

    RallyPointManager*  _rallyPointManager;
    bool                _rallyPointManagerInitialRequestSent;
1046

1047 1048
    ParameterManager*   _parameterManager;

1049
#if defined(QGC_AIRMAP_ENABLED)
1050
    AirspaceVehicleManager* _airspaceVehicleManager;
1051
#endif
dogmaphobic's avatar
dogmaphobic committed
1052

Don Gagne's avatar
Don Gagne committed
1053 1054 1055
    bool    _armed;         ///< true: vehicle is armed
    uint8_t _base_mode;     ///< base_mode from HEARTBEAT
    uint32_t _custom_mode;  ///< custom_mode from HEARTBEAT
1056 1057 1058 1059 1060 1061

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

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

1065 1066
    static const int _sendMessageMultipleRetries = 5;
    static const int _sendMessageMultipleIntraMessageDelay = 500;
dogmaphobic's avatar
dogmaphobic committed
1067

1068 1069
    QTimer  _sendMultipleTimer;
    int     _nextSendMessageMultipleIndex;
dogmaphobic's avatar
dogmaphobic committed
1070

1071
    QTime               _flightTimer;
1072 1073 1074 1075 1076
    QTimer              _mapTrajectoryTimer;
    QmlObjectListModel  _mapTrajectoryList;
    QGeoCoordinate      _mapTrajectoryLastCoordinate;
    bool                _mapTrajectoryHaveFirstCoordinate;
    static const int    _mapTrajectoryMsecsBetweenPoints = 1000;
1077

1078 1079
    QmlObjectListModel  _cameraTriggerPoints;

1080 1081
    QmlObjectListModel              _adsbVehicles;
    QMap<uint32_t, ADSBVehicle*>    _adsbICAOMap;
1082
    QMap<QString, ADSBVehicle*>     _trafficVehicleMap;
1083
    QTimer                          _adsbTimer;
1084

1085
    // Toolbox references
dogmaphobic's avatar
dogmaphobic committed
1086 1087 1088 1089 1090
    FirmwarePluginManager*      _firmwarePluginManager;
    JoystickManager*            _joystickManager;

    int                         _flowImageIndex;

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

1093 1094 1095 1096 1097 1098 1099
    uint                _messagesReceived;
    uint                _messagesSent;
    uint                _messagesLost;
    uint8_t             _messageSeq;
    uint8_t             _compID;
    bool                _heardFrom;

Don Gagne's avatar
Don Gagne committed
1100 1101 1102
    int _firmwareMajorVersion;
    int _firmwareMinorVersion;
    int _firmwarePatchVersion;
1103 1104 1105
    int _firmwareCustomMajorVersion;
    int _firmwareCustomMinorVersion;
    int _firmwareCustomPatchVersion;
1106
    FIRMWARE_VERSION_TYPE _firmwareVersionType;
Don Gagne's avatar
Don Gagne committed
1107

1108
    QString _gitHash;
Gus Grubba's avatar
Gus Grubba committed
1109
    quint64 _uid;
1110

1111
    int _lastAnnouncedLowBatteryPercent;
1112

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

Don Gagne's avatar
Don Gagne committed
1115 1116 1117 1118 1119 1120 1121 1122 1123 1124
    // FactGroup facts

    Fact _rollFact;
    Fact _pitchFact;
    Fact _headingFact;
    Fact _groundSpeedFact;
    Fact _airSpeedFact;
    Fact _climbRateFact;
    Fact _altitudeRelativeFact;
    Fact _altitudeAMSLFact;
1125
    Fact _flightDistanceFact;
1126
    Fact _flightTimeFact;
1127
    Fact _distanceToHomeFact;
1128
    Fact _hobbsFact;
Don Gagne's avatar
Don Gagne committed
1129

1130 1131 1132 1133
    VehicleGPSFactGroup         _gpsFactGroup;
    VehicleBatteryFactGroup     _batteryFactGroup;
    VehicleWindFactGroup        _windFactGroup;
    VehicleVibrationFactGroup   _vibrationFactGroup;
1134
    VehicleTemperatureFactGroup _temperatureFactGroup;
dheideman's avatar
dheideman committed
1135
    VehicleClockFactGroup       _clockFactGroup;
Don Gagne's avatar
Don Gagne committed
1136 1137 1138 1139 1140 1141 1142 1143 1144

    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;
1145
    static const char* _flightDistanceFactName;
1146
    static const char* _flightTimeFactName;
1147
    static const char* _distanceToHomeFactName;
1148
    static const char* _hobbsFactName;
Don Gagne's avatar
Don Gagne committed
1149

Don Gagne's avatar
Don Gagne committed
1150
    static const char* _gpsFactGroupName;
Don Gagne's avatar
Don Gagne committed
1151
    static const char* _batteryFactGroupName;
Don Gagne's avatar
Don Gagne committed
1152
    static const char* _windFactGroupName;
1153
    static const char* _vibrationFactGroupName;
1154
    static const char* _temperatureFactGroupName;
dheideman's avatar
dheideman committed
1155
    static const char* _clockFactGroupName;
Don Gagne's avatar
Don Gagne committed
1156 1157 1158

    static const int _vehicleUIUpdateRateMSecs = 100;

1159
    // Settings keys
1160 1161
    static const char* _settingsGroup;
    static const char* _joystickModeSettingsKey;
1162
    static const char* _joystickEnabledSettingsKey;
Don Gagne's avatar
Don Gagne committed
1163

1164
};