Vehicle.h 58.1 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
#include <AirspaceManagement.h>
24

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

Q_DECLARE_LOGGING_CATEGORY(VehicleLog)

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

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

public:
    VehicleVibrationFactGroup(QObject* parent = NULL);

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

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

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

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

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

public:
    VehicleWindFactGroup(QObject* parent = NULL);

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

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

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

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

Don Gagne's avatar
Don Gagne committed
107 108 109 110 111 112 113
class VehicleGPSFactGroup : public FactGroup
{
    Q_OBJECT

public:
    VehicleGPSFactGroup(QObject* parent = NULL);

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

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

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

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

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


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

180 181
    static const char* _settingsGroup;

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

private:
191 192 193 194 195 196
    Fact            _voltageFact;
    Fact            _percentRemainingFact;
    Fact            _mahConsumedFact;
    Fact            _currentFact;
    Fact            _temperatureFact;
    Fact            _cellCountFact;
197
    Fact            _instantPowerFact;
Don Gagne's avatar
Don Gagne committed
198 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
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
229 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
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
255
class Vehicle : public FactGroup
256 257
{
    Q_OBJECT
dogmaphobic's avatar
dogmaphobic committed
258

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

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

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

276 277 278 279 280
    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)
281
    Q_PROPERTY(bool                 autoDisarm              READ autoDisarm                                             NOTIFY autoDisarmChanged)
282 283 284 285 286
    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)
287
    Q_PROPERTY(QmlObjectListModel*  cameraTriggerPoints     READ cameraTriggerPoints                                    CONSTANT)
288 289 290 291 292 293 294 295 296 297 298 299 300 301 302 303 304
    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)
305 306
    Q_PROPERTY(bool                 px4Firmware             READ px4Firmware                                            NOTIFY firmwareTypeChanged)
    Q_PROPERTY(bool                 apmFirmware             READ apmFirmware                                            NOTIFY firmwareTypeChanged)
307 308 309 310 311 312 313
    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)
314 315 316 317 318
    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)
319
    Q_PROPERTY(bool        supportsThrottleModeCenterZero   READ supportsThrottleModeCenterZero                         CONSTANT)
320
    Q_PROPERTY(bool                supportsNegativeThrust   READ supportsNegativeThrust                                 CONSTANT)
321
    Q_PROPERTY(bool                 supportsJSButton        READ supportsJSButton                                       CONSTANT)
322
    Q_PROPERTY(bool                 supportsRadio           READ supportsRadio                                          CONSTANT)
323
    Q_PROPERTY(bool               supportsMotorInterference READ supportsMotorInterference                              CONSTANT)
324 325
    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
326 327 328
    Q_PROPERTY(int                  motorCount              READ motorCount                                             CONSTANT)
    Q_PROPERTY(bool                 coaxialMotors           READ coaxialMotors                                          CONSTANT)
    Q_PROPERTY(bool                 xConfigMotors           READ xConfigMotors                                          CONSTANT)
329
    Q_PROPERTY(bool                 isOfflineEditingVehicle READ isOfflineEditingVehicle                                CONSTANT)
330 331
    Q_PROPERTY(QString              brandImageIndoor        READ brandImageIndoor                                       NOTIFY firmwareTypeChanged)
    Q_PROPERTY(QString              brandImageOutdoor       READ brandImageOutdoor                                      NOTIFY firmwareTypeChanged)
332
    Q_PROPERTY(QStringList          unhealthySensors        READ unhealthySensors                                       NOTIFY unhealthySensorsChanged)
333
    Q_PROPERTY(QString              missionFlightMode       READ missionFlightMode                                      CONSTANT)
334
    Q_PROPERTY(QString              pauseFlightMode         READ pauseFlightMode                                        CONSTANT)
335
    Q_PROPERTY(QString              rtlFlightMode           READ rtlFlightMode                                          CONSTANT)
336
    Q_PROPERTY(QString              landFlightMode          READ landFlightMode                                         CONSTANT)
337
    Q_PROPERTY(QString              takeControlFlightMode   READ takeControlFlightMode                                  CONSTANT)
338 339
    Q_PROPERTY(QString              firmwareTypeString      READ firmwareTypeString                                     NOTIFY firmwareTypeChanged)
    Q_PROPERTY(QString              vehicleTypeString       READ vehicleTypeString                                      NOTIFY vehicleTypeChanged)
340 341 342
    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
343 344 345 346 347
    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)
348 349
    Q_PROPERTY(int                  telemetryLNoise         READ telemetryLNoise                                        NOTIFY telemetryLNoiseChanged)
    Q_PROPERTY(int                  telemetryRNoise         READ telemetryRNoise                                        NOTIFY telemetryRNoiseChanged)
350
    Q_PROPERTY(QVariantList         toolBarIndicators       READ toolBarIndicators                                      NOTIFY toolBarIndicatorsChanged)
351
    Q_PROPERTY(QmlObjectListModel*  adsbVehicles            READ adsbVehicles                                           CONSTANT)
Don Gagne's avatar
Don Gagne committed
352
    Q_PROPERTY(bool              initialPlanRequestComplete READ initialPlanRequestComplete                             NOTIFY initialPlanRequestCompleteChanged)
Gus Grubba's avatar
Gus Grubba committed
353
    Q_PROPERTY(QVariantList         staticCameraList        READ staticCameraList                                       CONSTANT)
354
    Q_PROPERTY(QGCCameraManager*    dynamicCameras          READ dynamicCameras                                         NOTIFY dynamicCamerasChanged)
355
    Q_PROPERTY(QString              hobbsMeter              READ hobbsMeter                                             NOTIFY hobbsMeterChanged)
356
    Q_PROPERTY(bool                 vtolInFwdFlight         READ vtolInFwdFlight        WRITE setVtolInFwdFlight        NOTIFY vtolInFwdFlightChanged)
357
    Q_PROPERTY(bool                 highLatencyLink         READ highLatencyLink                                        NOTIFY highLatencyLinkChanged)
358 359
    Q_PROPERTY(AirspaceAuthorization::PermitStatus  flightPermitStatus    READ flightPermitStatus                       NOTIFY flightPermitStatusChanged)   ///< state of flight permission
    Q_PROPERTY(AirspaceController*   airspaceController     READ airspaceController                                     CONSTANT)
360

361 362 363 364 365 366 367
    // 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
368
    Q_PROPERTY(bool takeoffVehicleSupported READ takeoffVehicleSupported CONSTANT)                          ///< Guided takeoff supported    
369

370 371
    Q_PROPERTY(ParameterManager* parameterManager READ parameterManager CONSTANT)

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

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

393 394 395 396 397 398 399 400 401
    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
402 403
    Q_PROPERTY(quint64  vehicleUID                  READ vehicleUID                 NOTIFY vehicleUIDChanged)
    Q_PROPERTY(QString  vehicleUIDStr               READ vehicleUIDStr              NOTIFY vehicleUIDChanged)
404

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

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

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

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

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

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

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

437 438 439
    /// 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
440

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

455
    /// Command vehicle to abort landing
456
    Q_INVOKABLE void abortLanding(double climbOutAltitude);
457

458 459
    Q_INVOKABLE void startMission(void);

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

463 464 465
    /// Reboot vehicle
    Q_INVOKABLE void rebootVehicle();

dogmaphobic's avatar
dogmaphobic committed
466 467 468
    /// Clear Messages
    Q_INVOKABLE void clearMessages();

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

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

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

486
    // Property accessors
Don Gagne's avatar
Don Gagne committed
487

488
    QGeoCoordinate coordinate(void) { return _coordinate; }
dogmaphobic's avatar
dogmaphobic committed
489

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

499 500
    int joystickMode(void);
    void setJoystickMode(int mode);
dogmaphobic's avatar
dogmaphobic committed
501

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

505 506
    bool joystickEnabled(void);
    void setJoystickEnabled(bool enabled);
dogmaphobic's avatar
dogmaphobic committed
507

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

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

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

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

526 527 528
    /// 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
529

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

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

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

539
    int manualControlReservedButtonCount(void);
dogmaphobic's avatar
dogmaphobic committed
540

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

545
    QGeoCoordinate homePosition(void);
dogmaphobic's avatar
dogmaphobic committed
546

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

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

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

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

564
    bool supportsThrottleModeCenterZero(void) const;
565
    bool supportsNegativeThrust(void) const;
566
    bool supportsRadio(void) const;
567
    bool supportsJSButton(void) const;
568
    bool supportsMotorInterference(void) const;
569

Don Gagne's avatar
Don Gagne committed
570 571
    void setGuidedMode(bool guidedMode);

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

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

579
    AirspaceController* airspaceController() { return _airspaceController; }
580

dogmaphobic's avatar
dogmaphobic committed
581 582
    int  flowImageIndex() { return _flowImageIndex; }

583 584 585 586
    //-- Mavlink Logging
    void startMavlinkLog();
    void stopMavlinkLog();

587 588 589
    /// 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
590 591
    ///     @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
592

593 594 595 596 597 598
    typedef enum {
        MessageNone,
        MessageNormal,
        MessageWarning,
        MessageError
    } MessageType_t;
dogmaphobic's avatar
dogmaphobic committed
599

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

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

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

672
    void setConnectionLostEnabled(bool connectionLostEnabled);
673

674 675
    ParameterManager* parameterManager(void) { return _parameterManager; }
    ParameterManager* parameterManager(void) const { return _parameterManager; }
dogmaphobic's avatar
dogmaphobic committed
676

Don Gagne's avatar
Don Gagne committed
677 678
    static const int cMaxRcChannels = 18;

Don Gagne's avatar
Don Gagne committed
679
    bool containsLink(LinkInterface* link) { return _links.contains(link); }
680 681 682 683 684 685

    /// 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
686
    /// Signals: mavCommandResult on success or failure
687
    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
688

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

705
    QString gitHash(void) const { return _gitHash; }
Gus Grubba's avatar
Gus Grubba committed
706 707
    quint64 vehicleUID(void) const { return _uid; }
    QString vehicleUIDStr();
708

709 710 711
    bool soloFirmware(void) const { return _soloFirmware; }
    void setSoloFirmware(bool soloFirmware);

712 713 714 715
    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
716

Don Gagne's avatar
Don Gagne committed
717 718 719 720 721 722 723 724 725
    /// @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);

726 727 728 729 730 731 732
    /// @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);

733 734 735 736
    QString vehicleImageOpaque  () const;
    QString vehicleImageOutline () const;
    QString vehicleImageCompass () const;

737
    const QVariantList&         toolBarIndicators   ();
Gus Grubba's avatar
Gus Grubba committed
738
    const QVariantList&         staticCameraList    (void) const;
739

740 741
    bool capabilitiesKnown      (void) const { return _vehicleCapabilitiesKnown; }
    uint64_t capabilityBits     (void) const { return _capabilityBits; }    // Change signalled by capabilityBitsChanged
742

743
    QGCCameraManager*           dynamicCameras      () { return _cameras; }
744
    QString                     hobbsMeter          ();
745

746 747 748
    /// @true: When flying a mission the vehicle is always facing towards the next waypoint
    bool vehicleYawsToNextWaypointInMission(void) const;

DonLakeFlyer's avatar
DonLakeFlyer committed
749 750 751 752
    /// 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
753
    void forceInitialPlanRequestComplete(void);
754

755 756
    void _setFlying(bool flying);
    void _setLanding(bool landing);
757
    void setVtolInFwdFlight(bool vtolInFwdFlight);
DonLakeFlyer's avatar
DonLakeFlyer committed
758
    void _setHomePosition(QGeoCoordinate& homeCoord);
759
    void _setMaxProtoVersion (unsigned version);
DonLakeFlyer's avatar
DonLakeFlyer committed
760

761 762 763
    /// Vehicle is about to be deleted
    void prepareDelete();

764 765 766 767 768
    AirspaceAuthorization::PermitStatus flightPermitStatus() const
        { return _airspaceManagerPerVehicle ? _airspaceManagerPerVehicle->flightPermitStatus() : AirspaceAuthorization::PermitUnknown; }

    AirspaceManagerPerVehicle* airspaceManager() const { return _airspaceManagerPerVehicle; }

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

dogmaphobic's avatar
dogmaphobic committed
805

806 807 808 809
    void messagesReceivedChanged    ();
    void messagesSentChanged        ();
    void messagesLostChanged        ();

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

Gus Grubba's avatar
Gus Grubba committed
813 814 815 816 817 818 819 820 821 822 823 824 825 826 827
    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);
828 829
    void telemetryLNoiseChanged     (int value);
    void telemetryRNoiseChanged     (int value);
830
    void autoDisarmChanged          (void);
dogmaphobic's avatar
dogmaphobic committed
831

832 833
    void firmwareVersionChanged(void);
    void firmwareCustomVersionChanged(void);
834
    void gitHashChanged(QString hash);
Gus Grubba's avatar
Gus Grubba committed
835
    void vehicleUIDChanged();
836

Don Gagne's avatar
Don Gagne committed
837 838 839 840 841 842 843 844
    /// 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);

845 846 847 848 849
    void mavlinkRawImu(mavlink_message_t message);
    void mavlinkScaledImu1(mavlink_message_t message);
    void mavlinkScaledImu2(mavlink_message_t message);
    void mavlinkScaledImu3(mavlink_message_t message);

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

853 854 855 856 857 858
    /// 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
859
    void mavCommandResult(int vehicleId, int component, int command, int result, bool noReponseFromVehicle);
860

861
    // MAVlink Serial Data
862 863
    void mavlinkSerialControl(uint8_t device, uint8_t flags, uint16_t timeout, uint32_t baudrate, QByteArray data);

864 865 866
    // MAVLink protocol version
    void requestProtocolVersion(unsigned version);

867 868
private slots:
    void _mavlinkMessageReceived(LinkInterface* link, mavlink_message_t message);
Don Gagne's avatar
Don Gagne committed
869
    void _linkInactiveOrDeleted(LinkInterface* link);
870
    void _sendMessageOnLink(LinkInterface* link, mavlink_message_t message);
871
    void _sendMessageMultipleNext(void);
872
    void _addNewMapTrajectoryPoint(void);
873
    void _parametersReady(bool parametersReady);
Don Gagne's avatar
Don Gagne committed
874
    void _remoteControlRSSIChanged(uint8_t rssi);
Don Gagne's avatar
Don Gagne committed
875
    void _handleFlightModeChanged(const QString& flightMode);
876
    void _announceArmedChanged(bool armed);
877 878 879 880
    void _offlineFirmwareTypeSettingChanged(QVariant value);
    void _offlineVehicleTypeSettingChanged(QVariant value);
    void _offlineCruiseSpeedSettingChanged(QVariant value);
    void _offlineHoverSpeedSettingChanged(QVariant value);
881
    void _updateHighLatencyLink(void);
882

883
    void _handleTextMessage                 (int newCount);
dogmaphobic's avatar
dogmaphobic committed
884
    void _handletextMessageReceived         (UASMessage* message);
885 886 887 888
    /** @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
889 890
    /** @brief A new camera image has arrived */
    void _imageReady                        (UASInterface* uas);
891
    void _connectionLostTimeout(void);
Don Gagne's avatar
Don Gagne committed
892
    void _prearmErrorTimeout(void);
DonLakeFlyer's avatar
DonLakeFlyer committed
893 894 895
    void _missionLoadComplete(void);
    void _geoFenceLoadComplete(void);
    void _rallyPointLoadComplete(void);
896
    void _sendMavCommandAgain(void);
897 898
    void _clearTrajectoryPoints(void);
    void _clearCameraTriggerPoints(void);
899
    void _updateDistanceToHome(void);
900 901
    void _updateHobbsMeter(void);
    void _vehicleParamLoaded(bool ready);
Jacob Walser's avatar
Jacob Walser committed
902

903
    void _trafficUpdate(QString traffic_id, QString vehicle_id, QGeoCoordinate location, float heading);
904
    void _adsbTimerTimeout();
905

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

959
    int     _id;                    ///< Mavlink system id
960
    int     _defaultComponentId;
961
    bool    _active;
962
    bool    _offlineEditingVehicle; ///< This Vehicle is a "disconnected" vehicle for ui use while offline editing
dogmaphobic's avatar
dogmaphobic committed
963

964
    MAV_AUTOPILOT       _firmwareType;
965
    MAV_TYPE            _vehicleType;
966
    FirmwarePlugin*     _firmwarePlugin;
967
    QObject*            _firmwarePluginInstanceData;
968
    AutoPilotPlugin*    _autopilotPlugin;
Don Gagne's avatar
Don Gagne committed
969
    MAVLinkProtocol*    _mavlink;
970
    bool                _soloFirmware;
971
    QGCToolbox*         _toolbox;
972
    SettingsManager*    _settingsManager;
dogmaphobic's avatar
dogmaphobic committed
973

Don Gagne's avatar
Don Gagne committed
974
    QList<LinkInterface*> _links;
dogmaphobic's avatar
dogmaphobic committed
975

976
    JoystickMode_t  _joystickMode;
977
    bool            _joystickEnabled;
dogmaphobic's avatar
dogmaphobic committed
978

979
    UAS* _uas;
dogmaphobic's avatar
dogmaphobic committed
980

981
    QGeoCoordinate  _coordinate;
982
    QGeoCoordinate  _homePosition;
dogmaphobic's avatar
dogmaphobic committed
983

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

1020 1021
    QGCCameraManager* _cameras;

1022 1023 1024 1025 1026 1027 1028 1029 1030 1031 1032
    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;
1033
    static const int                _mavCommandAckTimeoutMSecs = 3000;
1034

Don Gagne's avatar
Don Gagne committed
1035 1036 1037 1038
    QString             _prearmError;
    QTimer              _prearmErrorTimer;
    static const int    _prearmErrorTimeoutMSecs = 35 * 1000;   ///< Take away prearm error after 35 seconds

1039 1040 1041 1042 1043 1044
    // 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
1045 1046
    bool                _initialPlanRequestComplete;

Don Gagne's avatar
Don Gagne committed
1047
    MissionManager*     _missionManager;
1048
    bool                _missionManagerInitialRequestSent;
1049

1050
    GeoFenceManager*    _geoFenceManager;
1051 1052 1053 1054
    bool                _geoFenceManagerInitialRequestSent;

    RallyPointManager*  _rallyPointManager;
    bool                _rallyPointManagerInitialRequestSent;
1055

1056 1057
    ParameterManager*   _parameterManager;

1058 1059
    AirspaceController*   _airspaceController;
    AirspaceManagerPerVehicle* _airspaceManagerPerVehicle;
dogmaphobic's avatar
dogmaphobic committed
1060

Don Gagne's avatar
Don Gagne committed
1061 1062 1063
    bool    _armed;         ///< true: vehicle is armed
    uint8_t _base_mode;     ///< base_mode from HEARTBEAT
    uint32_t _custom_mode;  ///< custom_mode from HEARTBEAT
1064 1065 1066 1067 1068 1069

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

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

1073 1074
    static const int _sendMessageMultipleRetries = 5;
    static const int _sendMessageMultipleIntraMessageDelay = 500;
dogmaphobic's avatar
dogmaphobic committed
1075

1076 1077
    QTimer  _sendMultipleTimer;
    int     _nextSendMessageMultipleIndex;
dogmaphobic's avatar
dogmaphobic committed
1078

1079
    QTime               _flightTimer;
1080 1081 1082 1083 1084
    QTimer              _mapTrajectoryTimer;
    QmlObjectListModel  _mapTrajectoryList;
    QGeoCoordinate      _mapTrajectoryLastCoordinate;
    bool                _mapTrajectoryHaveFirstCoordinate;
    static const int    _mapTrajectoryMsecsBetweenPoints = 1000;
1085

1086 1087
    QmlObjectListModel  _cameraTriggerPoints;

1088 1089
    QmlObjectListModel              _adsbVehicles;
    QMap<uint32_t, ADSBVehicle*>    _adsbICAOMap;
1090
    QMap<QString, ADSBVehicle*>     _trafficVehicleMap;
1091
    QTimer                          _adsbTimer;
1092

1093
    // Toolbox references
dogmaphobic's avatar
dogmaphobic committed
1094 1095 1096 1097 1098
    FirmwarePluginManager*      _firmwarePluginManager;
    JoystickManager*            _joystickManager;

    int                         _flowImageIndex;

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

1101 1102 1103 1104 1105 1106 1107
    uint                _messagesReceived;
    uint                _messagesSent;
    uint                _messagesLost;
    uint8_t             _messageSeq;
    uint8_t             _compID;
    bool                _heardFrom;

Don Gagne's avatar
Don Gagne committed
1108 1109 1110
    int _firmwareMajorVersion;
    int _firmwareMinorVersion;
    int _firmwarePatchVersion;
1111 1112 1113
    int _firmwareCustomMajorVersion;
    int _firmwareCustomMinorVersion;
    int _firmwareCustomPatchVersion;
1114
    FIRMWARE_VERSION_TYPE _firmwareVersionType;
Don Gagne's avatar
Don Gagne committed
1115

1116
    QString _gitHash;
Gus Grubba's avatar
Gus Grubba committed
1117
    quint64 _uid;
1118

1119
    int _lastAnnouncedLowBatteryPercent;
1120

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

Don Gagne's avatar
Don Gagne committed
1123 1124 1125 1126 1127 1128 1129 1130 1131 1132
    // FactGroup facts

    Fact _rollFact;
    Fact _pitchFact;
    Fact _headingFact;
    Fact _groundSpeedFact;
    Fact _airSpeedFact;
    Fact _climbRateFact;
    Fact _altitudeRelativeFact;
    Fact _altitudeAMSLFact;
1133
    Fact _flightDistanceFact;
1134
    Fact _flightTimeFact;
1135
    Fact _distanceToHomeFact;
1136
    Fact _hobbsFact;
Don Gagne's avatar
Don Gagne committed
1137

1138 1139 1140 1141
    VehicleGPSFactGroup         _gpsFactGroup;
    VehicleBatteryFactGroup     _batteryFactGroup;
    VehicleWindFactGroup        _windFactGroup;
    VehicleVibrationFactGroup   _vibrationFactGroup;
1142
    VehicleTemperatureFactGroup _temperatureFactGroup;
dheideman's avatar
dheideman committed
1143
    VehicleClockFactGroup       _clockFactGroup;
Don Gagne's avatar
Don Gagne committed
1144 1145 1146 1147 1148 1149 1150 1151 1152

    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;
1153
    static const char* _flightDistanceFactName;
1154
    static const char* _flightTimeFactName;
1155
    static const char* _distanceToHomeFactName;
1156
    static const char* _hobbsFactName;
Don Gagne's avatar
Don Gagne committed
1157

Don Gagne's avatar
Don Gagne committed
1158
    static const char* _gpsFactGroupName;
Don Gagne's avatar
Don Gagne committed
1159
    static const char* _batteryFactGroupName;
Don Gagne's avatar
Don Gagne committed
1160
    static const char* _windFactGroupName;
1161
    static const char* _vibrationFactGroupName;
1162
    static const char* _temperatureFactGroupName;
dheideman's avatar
dheideman committed
1163
    static const char* _clockFactGroupName;
Don Gagne's avatar
Don Gagne committed
1164 1165 1166

    static const int _vehicleUIUpdateRateMSecs = 100;

1167
    // Settings keys
1168 1169
    static const char* _settingsGroup;
    static const char* _joystickModeSettingsKey;
1170
    static const char* _joystickEnabledSettingsKey;
Don Gagne's avatar
Don Gagne committed
1171

1172
};