Vehicle.h 55.3 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
class AirMapController;
39 40 41

Q_DECLARE_LOGGING_CATEGORY(VehicleLog)

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

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

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

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

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

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

public:
    VehicleGPSFactGroup(QObject* parent = NULL);

113 114
    Q_PROPERTY(Fact* lat                READ lat                CONSTANT)
    Q_PROPERTY(Fact* lon                READ lon                CONSTANT)
Don Gagne's avatar
Don Gagne committed
115 116 117 118 119 120
    Q_PROPERTY(Fact* hdop               READ hdop               CONSTANT)
    Q_PROPERTY(Fact* vdop               READ vdop               CONSTANT)
    Q_PROPERTY(Fact* courseOverGround   READ courseOverGround   CONSTANT)
    Q_PROPERTY(Fact* count              READ count              CONSTANT)
    Q_PROPERTY(Fact* lock               READ lock               CONSTANT)

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

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

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

    Fact* voltage                   (void) { return &_voltageFact; }
    Fact* percentRemaining          (void) { return &_percentRemainingFact; }
    Fact* mahConsumed               (void) { return &_mahConsumedFact; }
    Fact* current                   (void) { return &_currentFact; }
    Fact* temperature               (void) { return &_temperatureFact; }
    Fact* cellCount                 (void) { return &_cellCountFact; }
Don Gagne's avatar
Don Gagne committed
167 168 169 170 171 172 173 174 175


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

176 177
    static const char* _settingsGroup;

Don Gagne's avatar
Don Gagne committed
178 179 180 181 182 183 184 185
    static const double _voltageUnavailable;
    static const int    _percentRemainingUnavailable;
    static const int    _mahConsumedUnavailable;
    static const int    _currentUnavailable;
    static const double _temperatureUnavailable;
    static const int    _cellCountUnavailable;

private:
186 187 188 189 190 191
    Fact            _voltageFact;
    Fact            _percentRemainingFact;
    Fact            _mahConsumedFact;
    Fact            _currentFact;
    Fact            _temperatureFact;
    Fact            _cellCountFact;
Don Gagne's avatar
Don Gagne committed
192 193
};

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

public:
    VehicleTemperatureFactGroup(QObject* parent = NULL);

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

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

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

    static const char* _settingsGroup;

    static const double _temperatureUnavailable;

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

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

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

236 237 238 239 240
    // 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);
241

242
    ~Vehicle();
dogmaphobic's avatar
dogmaphobic committed
243

244 245 246 247 248
    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)
249
    Q_PROPERTY(bool                 autoDisarm              READ autoDisarm                                             NOTIFY autoDisarmChanged)
250 251 252 253 254
    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)
255
    Q_PROPERTY(QmlObjectListModel*  cameraTriggerPoints     READ cameraTriggerPoints                                    CONSTANT)
256 257 258 259 260 261 262 263 264 265 266 267 268 269 270 271 272
    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)
273 274
    Q_PROPERTY(bool                 px4Firmware             READ px4Firmware                                            NOTIFY firmwareTypeChanged)
    Q_PROPERTY(bool                 apmFirmware             READ apmFirmware                                            NOTIFY firmwareTypeChanged)
275 276 277 278 279 280 281
    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)
282 283 284 285 286
    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)
287
    Q_PROPERTY(bool        supportsThrottleModeCenterZero   READ supportsThrottleModeCenterZero                         CONSTANT)
288
    Q_PROPERTY(bool                supportsNegativeThrust   READ supportsNegativeThrust                                 CONSTANT)
289
    Q_PROPERTY(bool                 supportsJSButton        READ supportsJSButton                                       CONSTANT)
290
    Q_PROPERTY(bool                 supportsRadio           READ supportsRadio                                          CONSTANT)
291
    Q_PROPERTY(bool               supportsMotorInterference READ supportsMotorInterference                              CONSTANT)
292 293
    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
294 295 296
    Q_PROPERTY(int                  motorCount              READ motorCount                                             CONSTANT)
    Q_PROPERTY(bool                 coaxialMotors           READ coaxialMotors                                          CONSTANT)
    Q_PROPERTY(bool                 xConfigMotors           READ xConfigMotors                                          CONSTANT)
297
    Q_PROPERTY(bool                 isOfflineEditingVehicle READ isOfflineEditingVehicle                                CONSTANT)
298 299
    Q_PROPERTY(QString              brandImageIndoor        READ brandImageIndoor                                       NOTIFY firmwareTypeChanged)
    Q_PROPERTY(QString              brandImageOutdoor       READ brandImageOutdoor                                      NOTIFY firmwareTypeChanged)
300
    Q_PROPERTY(QStringList          unhealthySensors        READ unhealthySensors                                       NOTIFY unhealthySensorsChanged)
301
    Q_PROPERTY(QString              missionFlightMode       READ missionFlightMode                                      CONSTANT)
302
    Q_PROPERTY(QString              pauseFlightMode         READ pauseFlightMode                                        CONSTANT)
303
    Q_PROPERTY(QString              rtlFlightMode           READ rtlFlightMode                                          CONSTANT)
304
    Q_PROPERTY(QString              landFlightMode          READ landFlightMode                                         CONSTANT)
305
    Q_PROPERTY(QString              takeControlFlightMode   READ takeControlFlightMode                                  CONSTANT)
306 307
    Q_PROPERTY(QString              firmwareTypeString      READ firmwareTypeString                                     NOTIFY firmwareTypeChanged)
    Q_PROPERTY(QString              vehicleTypeString       READ vehicleTypeString                                      NOTIFY vehicleTypeChanged)
308 309 310
    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
311 312 313 314 315
    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)
316 317
    Q_PROPERTY(int                  telemetryLNoise         READ telemetryLNoise                                        NOTIFY telemetryLNoiseChanged)
    Q_PROPERTY(int                  telemetryRNoise         READ telemetryRNoise                                        NOTIFY telemetryRNoiseChanged)
318
    Q_PROPERTY(QVariantList         toolBarIndicators       READ toolBarIndicators                                      CONSTANT)
319
    Q_PROPERTY(QmlObjectListModel*  adsbVehicles            READ adsbVehicles                                           CONSTANT)
Don Gagne's avatar
Don Gagne committed
320
    Q_PROPERTY(bool              initialPlanRequestComplete READ initialPlanRequestComplete                             NOTIFY initialPlanRequestCompleteChanged)
Gus Grubba's avatar
Gus Grubba committed
321
    Q_PROPERTY(QVariantList         staticCameraList        READ staticCameraList                                       CONSTANT)
322
    Q_PROPERTY(QGCCameraManager*    dynamicCameras          READ dynamicCameras                                         NOTIFY dynamicCamerasChanged)
323
    Q_PROPERTY(QString              hobbsMeter              READ hobbsMeter                                             NOTIFY hobbsMeterChanged)
324
    Q_PROPERTY(AirMapController*    airMapController        READ airMapController                                       CONSTANT)
325

326 327 328 329 330 331 332 333
    // 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
    Q_PROPERTY(bool takeoffVehicleSupported READ takeoffVehicleSupported CONSTANT)                          ///< Guided takeoff supported
334

335 336
    Q_PROPERTY(ParameterManager* parameterManager READ parameterManager CONSTANT)

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

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

357 358 359 360 361 362 363 364 365
    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
366 367
    Q_PROPERTY(quint64  vehicleUID                  READ vehicleUID                 NOTIFY vehicleUIDChanged)
    Q_PROPERTY(QString  vehicleUIDStr               READ vehicleUIDStr              NOTIFY vehicleUIDChanged)
368

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

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

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

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

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

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

398 399 400
    /// 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
401

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

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

419 420
    Q_INVOKABLE void startMission(void);

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

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

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

Don Gagne's avatar
Don Gagne committed
430
    Q_INVOKABLE void triggerCamera(void);
Don Gagne's avatar
Don Gagne committed
431
    Q_INVOKABLE void sendPlan(QString planFile);
Don Gagne's avatar
Don Gagne committed
432

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

442 443 444 445
    bool guidedModeSupported    (void) const;
    bool pauseVehicleSupported  (void) const;
    bool orbitModeSupported     (void) const;
    bool takeoffVehicleSupported(void) const;
Don Gagne's avatar
Don Gagne committed
446

447
    // Property accessors
Don Gagne's avatar
Don Gagne committed
448

449
    QGeoCoordinate coordinate(void) { return _coordinate; }
dogmaphobic's avatar
dogmaphobic committed
450

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

460 461
    int joystickMode(void);
    void setJoystickMode(int mode);
dogmaphobic's avatar
dogmaphobic committed
462

463 464
    /// List of joystick mode names
    QStringList joystickModes(void);
dogmaphobic's avatar
dogmaphobic committed
465

466 467
    bool joystickEnabled(void);
    void setJoystickEnabled(bool enabled);
dogmaphobic's avatar
dogmaphobic committed
468

469 470 471
    // Is vehicle active with respect to current active vehicle in QGC
    bool active(void);
    void setActive(bool active);
dogmaphobic's avatar
dogmaphobic committed
472

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

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

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

487 488 489
    /// 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
490

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

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

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

500
    int manualControlReservedButtonCount(void);
dogmaphobic's avatar
dogmaphobic committed
501

502 503 504
    MissionManager*     missionManager(void)    { return _missionManager; }
    GeoFenceManager*    geoFenceManager(void)   { return _geoFenceManager; }
    RallyPointManager*  rallyPointManager(void) { return _rallyPointManager; }
dogmaphobic's avatar
dogmaphobic committed
505

506
    QGeoCoordinate homePosition(void);
dogmaphobic's avatar
dogmaphobic committed
507

Don Gagne's avatar
Don Gagne committed
508 509 510 511 512
    bool armed(void) { return _armed; }
    void setArmed(bool armed);

    bool flightModeSetAvailable(void);
    QStringList flightModes(void);
Don Gagne's avatar
Don Gagne committed
513
    QString flightMode(void) const;
Don Gagne's avatar
Don Gagne committed
514 515 516 517
    void setFlightMode(const QString& flightMode);

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

519 520
    bool fixedWing(void) const;
    bool multiRotor(void) const;
Don Gagne's avatar
Don Gagne committed
521
    bool vtol(void) const;
Don Gagne's avatar
Don Gagne committed
522
    bool rover(void) const;
523
    bool sub(void) const;
524

525
    bool supportsThrottleModeCenterZero(void) const;
526
    bool supportsNegativeThrust(void) const;
527
    bool supportsRadio(void) const;
528
    bool supportsJSButton(void) const;
529
    bool supportsMotorInterference(void) const;
530

Don Gagne's avatar
Don Gagne committed
531 532
    void setGuidedMode(bool guidedMode);

Don Gagne's avatar
Don Gagne committed
533 534 535
    QString prearmError(void) const { return _prearmError; }
    void setPrearmError(const QString& prearmError);

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

540 541
    AirMapController* airMapController() { return _airMapController; }

dogmaphobic's avatar
dogmaphobic committed
542 543
    int  flowImageIndex() { return _flowImageIndex; }

544 545 546 547
    //-- Mavlink Logging
    void startMavlinkLog();
    void stopMavlinkLog();

548 549 550
    /// 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
551 552
    ///     @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
553

554 555 556 557 558 559
    typedef enum {
        MessageNone,
        MessageNormal,
        MessageWarning,
        MessageError
    } MessageType_t;
dogmaphobic's avatar
dogmaphobic committed
560

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

Don Gagne's avatar
Don Gagne committed
612 613 614 615 616 617 618 619
    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; }
620
    Fact* flightDistance    (void) { return &_flightDistanceFact; }
621
    Fact* distanceToHome    (void) { return &_distanceToHomeFact; }
622
    Fact* hobbs             (void) { return &_hobbsFact; }
Don Gagne's avatar
Don Gagne committed
623

624 625 626 627
    FactGroup* gpsFactGroup         (void) { return &_gpsFactGroup; }
    FactGroup* batteryFactGroup     (void) { return &_batteryFactGroup; }
    FactGroup* windFactGroup        (void) { return &_windFactGroup; }
    FactGroup* vibrationFactGroup   (void) { return &_vibrationFactGroup; }
628
    FactGroup* temperatureFactGroup (void) { return &_temperatureFactGroup; }
Don Gagne's avatar
Don Gagne committed
629

630
    void setConnectionLostEnabled(bool connectionLostEnabled);
631

632 633
    ParameterManager* parameterManager(void) { return _parameterManager; }
    ParameterManager* parameterManager(void) const { return _parameterManager; }
dogmaphobic's avatar
dogmaphobic committed
634

Don Gagne's avatar
Don Gagne committed
635 636
    static const int cMaxRcChannels = 18;

Don Gagne's avatar
Don Gagne committed
637
    bool containsLink(LinkInterface* link) { return _links.contains(link); }
638 639 640 641 642 643

    /// 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
644
    /// Signals: mavCommandResult on success or failure
645
    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
646

647 648 649 650
    /// 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
651 652 653
    int firmwareMajorVersion(void) const { return _firmwareMajorVersion; }
    int firmwareMinorVersion(void) const { return _firmwareMinorVersion; }
    int firmwarePatchVersion(void) const { return _firmwarePatchVersion; }
654
    int firmwareVersionType(void) const { return _firmwareVersionType; }
655 656 657
    int firmwareCustomMajorVersion(void) const { return _firmwareCustomMajorVersion; }
    int firmwareCustomMinorVersion(void) const { return _firmwareCustomMinorVersion; }
    int firmwareCustomPatchVersion(void) const { return _firmwareCustomPatchVersion; }
658 659
    QString firmwareVersionTypeString(void) const;
    void setFirmwareVersion(int majorVersion, int minorVersion, int patchVersion, FIRMWARE_VERSION_TYPE versionType = FIRMWARE_VERSION_TYPE_OFFICIAL);
660
    void setFirmwareCustomVersion(int majorVersion, int minorVersion, int patchVersion);
661
    static const int versionNotSetValue = -1;
Don Gagne's avatar
Don Gagne committed
662

663
    QString gitHash(void) const { return _gitHash; }
Gus Grubba's avatar
Gus Grubba committed
664 665
    quint64 vehicleUID(void) const { return _uid; }
    QString vehicleUIDStr();
666

667 668 669
    bool soloFirmware(void) const { return _soloFirmware; }
    void setSoloFirmware(bool soloFirmware);

670 671 672 673
    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
674

Don Gagne's avatar
Don Gagne committed
675 676 677 678 679 680 681 682 683
    /// @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);

684 685 686 687 688 689 690
    /// @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);

691 692 693 694
    QString vehicleImageOpaque  () const;
    QString vehicleImageOutline () const;
    QString vehicleImageCompass () const;

695
    const QVariantList&         toolBarIndicators   ();
Gus Grubba's avatar
Gus Grubba committed
696
    const QVariantList&         staticCameraList    (void) const;
697

698 699
    bool capabilitiesKnown      (void) const { return _vehicleCapabilitiesKnown; }
    uint64_t capabilityBits     (void) const { return _capabilityBits; }    // Change signalled by capabilityBitsChanged
700

701
    QGCCameraManager*           dynamicCameras      () { return _cameras; }
702
    QString                     hobbsMeter          ();
703

704 705 706
    /// @true: When flying a mission the vehicle is always facing towards the next waypoint
    bool vehicleYawsToNextWaypointInMission(void) const;

DonLakeFlyer's avatar
DonLakeFlyer committed
707 708 709 710
    /// 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
711
    void forceInitialPlanRequestComplete(void);
712

713 714
    void _setFlying(bool flying);
    void _setLanding(bool landing);
DonLakeFlyer's avatar
DonLakeFlyer committed
715
    void _setHomePosition(QGeoCoordinate& homeCoord);
716
    void _setMaxProtoVersion (unsigned version);
DonLakeFlyer's avatar
DonLakeFlyer committed
717

718 719 720
    /// Vehicle is about to be deleted
    void prepareDelete();

721
signals:
Don Gagne's avatar
Don Gagne committed
722
    void allLinksInactive(Vehicle* vehicle);
723
    void coordinateChanged(QGeoCoordinate coordinate);
724
    void joystickModeChanged(int mode);
725 726
    void joystickEnabledChanged(bool enabled);
    void activeChanged(bool active);
Don Gagne's avatar
Don Gagne committed
727
    void mavlinkMessageReceived(const mavlink_message_t& message);
728
    void homePositionChanged(const QGeoCoordinate& homePosition);
Don Gagne's avatar
Don Gagne committed
729 730 731
    void armedChanged(bool armed);
    void flightModeChanged(const QString& flightMode);
    void hilModeChanged(bool hilMode);
732 733
    /** @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);
734 735
    void connectionLostChanged(bool connectionLost);
    void connectionLostEnabledChanged(bool connectionLostEnabled);
Don Gagne's avatar
Don Gagne committed
736
    void autoDisconnectChanged(bool autoDisconnectChanged);
Don Gagne's avatar
Don Gagne committed
737
    void flyingChanged(bool flying);
738
    void landingChanged(bool landing);
Don Gagne's avatar
Don Gagne committed
739
    void guidedModeChanged(bool guidedMode);
Don Gagne's avatar
Don Gagne committed
740
    void prearmErrorChanged(const QString& prearmError);
741
    void soloFirmwareChanged(bool soloFirmware);
742
    void unhealthySensorsChanged(void);
DonLakeFlyer's avatar
DonLakeFlyer committed
743 744
    void defaultCruiseSpeedChanged(double cruiseSpeed);
    void defaultHoverSpeedChanged(double hoverSpeed);
745 746
    void firmwareTypeChanged(void);
    void vehicleTypeChanged(void);
747
    void dynamicCamerasChanged();
748
    void hobbsMeterChanged();
749
    void capabilitiesKnownChanged(bool capabilitiesKnown);
Don Gagne's avatar
Don Gagne committed
750
    void initialPlanRequestCompleteChanged(bool initialPlanRequestComplete);
751
    void capabilityBitsChanged(uint64_t capabilityBits);
dogmaphobic's avatar
dogmaphobic committed
752

753 754 755 756
    void messagesReceivedChanged    ();
    void messagesSentChanged        ();
    void messagesLostChanged        ();

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

Gus Grubba's avatar
Gus Grubba committed
760 761 762 763 764 765 766 767 768 769 770 771 772 773 774
    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);
775 776
    void telemetryLNoiseChanged     (int value);
    void telemetryRNoiseChanged     (int value);
777
    void autoDisarmChanged          (void);
dogmaphobic's avatar
dogmaphobic committed
778

779 780
    void firmwareVersionChanged(void);
    void firmwareCustomVersionChanged(void);
781
    void gitHashChanged(QString hash);
Gus Grubba's avatar
Gus Grubba committed
782
    void vehicleUIDChanged();
783

Don Gagne's avatar
Don Gagne committed
784 785 786 787 788 789 790 791
    /// 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);

792 793 794 795 796
    void mavlinkRawImu(mavlink_message_t message);
    void mavlinkScaledImu1(mavlink_message_t message);
    void mavlinkScaledImu2(mavlink_message_t message);
    void mavlinkScaledImu3(mavlink_message_t message);

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

800 801 802 803 804 805
    /// 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
806
    void mavCommandResult(int vehicleId, int component, int command, int result, bool noReponseFromVehicle);
807

808
    // MAVlink Serial Data
809 810
    void mavlinkSerialControl(uint8_t device, uint8_t flags, uint16_t timeout, uint32_t baudrate, QByteArray data);

811 812 813
    // MAVLink protocol version
    void requestProtocolVersion(unsigned version);

814 815
private slots:
    void _mavlinkMessageReceived(LinkInterface* link, mavlink_message_t message);
Don Gagne's avatar
Don Gagne committed
816
    void _linkInactiveOrDeleted(LinkInterface* link);
817
    void _sendMessageOnLink(LinkInterface* link, mavlink_message_t message);
818
    void _sendMessageMultipleNext(void);
819
    void _addNewMapTrajectoryPoint(void);
820
    void _parametersReady(bool parametersReady);
Don Gagne's avatar
Don Gagne committed
821
    void _remoteControlRSSIChanged(uint8_t rssi);
Don Gagne's avatar
Don Gagne committed
822
    void _handleFlightModeChanged(const QString& flightMode);
823
    void _announceArmedChanged(bool armed);
824 825 826 827
    void _offlineFirmwareTypeSettingChanged(QVariant value);
    void _offlineVehicleTypeSettingChanged(QVariant value);
    void _offlineCruiseSpeedSettingChanged(QVariant value);
    void _offlineHoverSpeedSettingChanged(QVariant value);
828

829
    void _handleTextMessage                 (int newCount);
dogmaphobic's avatar
dogmaphobic committed
830
    void _handletextMessageReceived         (UASMessage* message);
831 832 833 834
    /** @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
835 836
    /** @brief A new camera image has arrived */
    void _imageReady                        (UASInterface* uas);
837
    void _connectionLostTimeout(void);
Don Gagne's avatar
Don Gagne committed
838
    void _prearmErrorTimeout(void);
DonLakeFlyer's avatar
DonLakeFlyer committed
839 840 841
    void _missionLoadComplete(void);
    void _geoFenceLoadComplete(void);
    void _rallyPointLoadComplete(void);
842
    void _sendMavCommandAgain(void);
Jacob Walser's avatar
Jacob Walser committed
843
    void _activeJoystickChanged(void);
844 845
    void _clearTrajectoryPoints(void);
    void _clearCameraTriggerPoints(void);
846
    void _updateDistanceToHome(void);
847 848
    void _updateHobbsMeter(void);
    void _vehicleParamLoaded(bool ready);
Jacob Walser's avatar
Jacob Walser committed
849

850 851
    void _trafficUpdate(QString traffic_id, QString vehicle_id, QGeoCoordinate location, float heading);

852 853 854
private:
    bool _containsLink(LinkInterface* link);
    void _addLink(LinkInterface* link);
855 856
    void _loadSettings(void);
    void _saveSettings(void);
857
    void _startJoystick(bool start);
Don Gagne's avatar
Don Gagne committed
858 859
    void _handleHomePosition(mavlink_message_t& message);
    void _handleHeartbeat(mavlink_message_t& message);
860
    void _handleRadioStatus(mavlink_message_t& message);
Don Gagne's avatar
Don Gagne committed
861 862
    void _handleRCChannels(mavlink_message_t& message);
    void _handleRCChannelsRaw(mavlink_message_t& message);
Don Gagne's avatar
Don Gagne committed
863 864
    void _handleBatteryStatus(mavlink_message_t& message);
    void _handleSysStatus(mavlink_message_t& message);
865
    void _handleWindCov(mavlink_message_t& message);
Don Gagne's avatar
Don Gagne committed
866
    void _handleWind(mavlink_message_t& message);
867
    void _handleVibration(mavlink_message_t& message);
Don Gagne's avatar
Don Gagne committed
868
    void _handleExtendedSysState(mavlink_message_t& message);
869
    void _handleCommandAck(mavlink_message_t& message);
870
    void _handleCommandLong(mavlink_message_t& message);
Gus Grubba's avatar
Gus Grubba committed
871
    void _handleAutopilotVersion(LinkInterface* link, mavlink_message_t& message);
872
    void _handleProtocolVersion(LinkInterface* link, mavlink_message_t& message);
873
    void _handleHilActuatorControls(mavlink_message_t& message);
874 875 876 877
    void _handleGpsRawInt(mavlink_message_t& message);
    void _handleGlobalPositionInt(mavlink_message_t& message);
    void _handleAltitude(mavlink_message_t& message);
    void _handleVfrHud(mavlink_message_t& message);
878 879 880
    void _handleScaledPressure(mavlink_message_t& message);
    void _handleScaledPressure2(mavlink_message_t& message);
    void _handleScaledPressure3(mavlink_message_t& message);
881 882
    void _handleCameraFeedback(const mavlink_message_t& message);
    void _handleCameraImageCaptured(const mavlink_message_t& message);
883
    void _handleADSBVehicle(const mavlink_message_t& message);
884
    void _missionManagerError(int errorCode, const QString& errorMsg);
885
    void _geoFenceManagerError(int errorCode, const QString& errorMsg);
886
    void _rallyPointManagerError(int errorCode, const QString& errorMsg);
887 888
    void _mapTrajectoryStart(void);
    void _mapTrajectoryStop(void);
889
    void _connectionActive(void);
890 891
    void _say(const QString& text);
    QString _vehicleIdSpeech(void);
892 893 894
    void _handleMavlinkLoggingData(mavlink_message_t& message);
    void _handleMavlinkLoggingDataAcked(mavlink_message_t& message);
    void _ackMavlinkLogData(uint16_t sequence);
895
    void _sendNextQueuedMavCommand(void);
896
    void _updatePriorityLink(void);
897
    void _commonInit(void);
DonLakeFlyer's avatar
DonLakeFlyer committed
898
    void _startPlanRequest(void);
899
    void _setupAutoDisarmSignalling(void);
DonLakeFlyer's avatar
DonLakeFlyer committed
900
    void _setCapabilities(uint64_t capabilityBits);
Don Gagne's avatar
Don Gagne committed
901

902
    int     _id;                    ///< Mavlink system id
903
    int     _defaultComponentId;
904
    bool    _active;
905
    bool    _offlineEditingVehicle; ///< This Vehicle is a "disconnected" vehicle for ui use while offline editing
dogmaphobic's avatar
dogmaphobic committed
906

907
    MAV_AUTOPILOT       _firmwareType;
908
    MAV_TYPE            _vehicleType;
909
    FirmwarePlugin*     _firmwarePlugin;
910
    QObject*            _firmwarePluginInstanceData;
911
    AutoPilotPlugin*    _autopilotPlugin;
Don Gagne's avatar
Don Gagne committed
912
    MAVLinkProtocol*    _mavlink;
913
    bool                _soloFirmware;
914
    QGCToolbox*         _toolbox;
915
    SettingsManager*    _settingsManager;
dogmaphobic's avatar
dogmaphobic committed
916

Don Gagne's avatar
Don Gagne committed
917
    QList<LinkInterface*> _links;
dogmaphobic's avatar
dogmaphobic committed
918

919
    JoystickMode_t  _joystickMode;
920
    bool            _joystickEnabled;
dogmaphobic's avatar
dogmaphobic committed
921

922
    UAS* _uas;
dogmaphobic's avatar
dogmaphobic committed
923

924
    QGeoCoordinate  _coordinate;
925
    QGeoCoordinate  _homePosition;
dogmaphobic's avatar
dogmaphobic committed
926

927 928 929 930 931 932 933 934 935
    UASInterface*   _mav;
    int             _currentMessageCount;
    int             _messageCount;
    int             _currentErrorCount;
    int             _currentWarningCount;
    int             _currentNormalCount;
    MessageType_t   _currentMessageType;
    QString         _latestError;
    int             _updateCount;
dogmaphobic's avatar
dogmaphobic committed
936
    QString         _formatedMessage;
Don Gagne's avatar
Don Gagne committed
937 938
    int             _rcRSSI;
    double          _rcRSSIstore;
Don Gagne's avatar
Don Gagne committed
939
    bool            _autoDisconnect;    ///< true: Automatically disconnect vehicle when last connection goes away or lost heartbeat
Don Gagne's avatar
Don Gagne committed
940
    bool            _flying;
941
    bool            _landing;
942 943 944 945
    uint32_t        _onboardControlSensorsPresent;
    uint32_t        _onboardControlSensorsEnabled;
    uint32_t        _onboardControlSensorsHealth;
    uint32_t        _onboardControlSensorsUnhealthy;
946 947
    bool            _gpsRawIntMessageAvailable;
    bool            _globalPositionIntMessageAvailable;
DonLakeFlyer's avatar
DonLakeFlyer committed
948 949
    double          _defaultCruiseSpeed;
    double          _defaultHoverSpeed;
Gus Grubba's avatar
Gus Grubba committed
950 951 952 953 954
    int             _telemetryRRSSI;
    int             _telemetryLRSSI;
    uint32_t        _telemetryRXErrors;
    uint32_t        _telemetryFixed;
    uint32_t        _telemetryTXBuffer;
955 956
    int             _telemetryLNoise;
    int             _telemetryRNoise;
957
    unsigned        _maxProtoVersion;
958
    bool            _vehicleCapabilitiesKnown;
959
    uint64_t        _capabilityBits;
dogmaphobic's avatar
dogmaphobic committed
960

961 962
    QGCCameraManager* _cameras;

963 964 965 966 967 968 969 970 971 972 973
    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;
974
    static const int                _mavCommandAckTimeoutMSecs = 3000;
975

Don Gagne's avatar
Don Gagne committed
976 977 978 979
    QString             _prearmError;
    QTimer              _prearmErrorTimer;
    static const int    _prearmErrorTimeoutMSecs = 35 * 1000;   ///< Take away prearm error after 35 seconds

980 981 982 983 984 985
    // 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
986 987
    bool                _initialPlanRequestComplete;

Don Gagne's avatar
Don Gagne committed
988
    MissionManager*     _missionManager;
989
    bool                _missionManagerInitialRequestSent;
990

991
    GeoFenceManager*    _geoFenceManager;
992 993 994 995
    bool                _geoFenceManagerInitialRequestSent;

    RallyPointManager*  _rallyPointManager;
    bool                _rallyPointManagerInitialRequestSent;
996

997 998 999
    ParameterManager*   _parameterManager;

    AirMapController*   _airMapController;
dogmaphobic's avatar
dogmaphobic committed
1000

Don Gagne's avatar
Don Gagne committed
1001 1002 1003
    bool    _armed;         ///< true: vehicle is armed
    uint8_t _base_mode;     ///< base_mode from HEARTBEAT
    uint32_t _custom_mode;  ///< custom_mode from HEARTBEAT
1004 1005 1006 1007 1008 1009

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

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

1013 1014
    static const int _sendMessageMultipleRetries = 5;
    static const int _sendMessageMultipleIntraMessageDelay = 500;
dogmaphobic's avatar
dogmaphobic committed
1015

1016 1017
    QTimer  _sendMultipleTimer;
    int     _nextSendMessageMultipleIndex;
dogmaphobic's avatar
dogmaphobic committed
1018

1019
    QTime               _flightTimer;
1020 1021 1022 1023 1024
    QTimer              _mapTrajectoryTimer;
    QmlObjectListModel  _mapTrajectoryList;
    QGeoCoordinate      _mapTrajectoryLastCoordinate;
    bool                _mapTrajectoryHaveFirstCoordinate;
    static const int    _mapTrajectoryMsecsBetweenPoints = 1000;
1025

1026 1027
    QmlObjectListModel  _cameraTriggerPoints;

1028 1029
    QmlObjectListModel              _adsbVehicles;
    QMap<uint32_t, ADSBVehicle*>    _adsbICAOMap;
1030
    QMap<QString, ADSBVehicle*>     _trafficVehicleMap;
1031

1032
    // Toolbox references
dogmaphobic's avatar
dogmaphobic committed
1033 1034 1035 1036 1037
    FirmwarePluginManager*      _firmwarePluginManager;
    JoystickManager*            _joystickManager;

    int                         _flowImageIndex;

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

1040 1041 1042 1043 1044 1045 1046
    uint                _messagesReceived;
    uint                _messagesSent;
    uint                _messagesLost;
    uint8_t             _messageSeq;
    uint8_t             _compID;
    bool                _heardFrom;

Don Gagne's avatar
Don Gagne committed
1047 1048 1049
    int _firmwareMajorVersion;
    int _firmwareMinorVersion;
    int _firmwarePatchVersion;
1050 1051 1052
    int _firmwareCustomMajorVersion;
    int _firmwareCustomMinorVersion;
    int _firmwareCustomPatchVersion;
1053
    FIRMWARE_VERSION_TYPE _firmwareVersionType;
Don Gagne's avatar
Don Gagne committed
1054

1055
    QString _gitHash;
Gus Grubba's avatar
Gus Grubba committed
1056
    quint64 _uid;
1057

1058
    int _lastAnnouncedLowBatteryPercent;
1059

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

Don Gagne's avatar
Don Gagne committed
1062 1063 1064 1065 1066 1067 1068 1069 1070 1071
    // FactGroup facts

    Fact _rollFact;
    Fact _pitchFact;
    Fact _headingFact;
    Fact _groundSpeedFact;
    Fact _airSpeedFact;
    Fact _climbRateFact;
    Fact _altitudeRelativeFact;
    Fact _altitudeAMSLFact;
1072
    Fact _flightDistanceFact;
1073
    Fact _flightTimeFact;
1074
    Fact _distanceToHomeFact;
1075
    Fact _hobbsFact;
Don Gagne's avatar
Don Gagne committed
1076

1077 1078 1079 1080
    VehicleGPSFactGroup         _gpsFactGroup;
    VehicleBatteryFactGroup     _batteryFactGroup;
    VehicleWindFactGroup        _windFactGroup;
    VehicleVibrationFactGroup   _vibrationFactGroup;
1081
    VehicleTemperatureFactGroup _temperatureFactGroup;
Don Gagne's avatar
Don Gagne committed
1082 1083 1084 1085 1086 1087 1088 1089 1090

    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;
1091
    static const char* _flightDistanceFactName;
1092
    static const char* _flightTimeFactName;
1093
    static const char* _distanceToHomeFactName;
1094
    static const char* _hobbsFactName;
Don Gagne's avatar
Don Gagne committed
1095

Don Gagne's avatar
Don Gagne committed
1096
    static const char* _gpsFactGroupName;
Don Gagne's avatar
Don Gagne committed
1097
    static const char* _batteryFactGroupName;
Don Gagne's avatar
Don Gagne committed
1098
    static const char* _windFactGroupName;
1099
    static const char* _vibrationFactGroupName;
1100
    static const char* _temperatureFactGroupName;
Don Gagne's avatar
Don Gagne committed
1101 1102 1103

    static const int _vehicleUIUpdateRateMSecs = 100;

1104
    // Settings keys
1105 1106
    static const char* _settingsGroup;
    static const char* _joystickModeSettingsKey;
1107
    static const char* _joystickEnabledSettingsKey;
Don Gagne's avatar
Don Gagne committed
1108

1109
};