Vehicle.h 50.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 11 12 13 14 15 16 17

/// @file
///     @author Don Gagne <don@thegagnes.com>

#ifndef Vehicle_H
#define Vehicle_H

#include <QObject>
18
#include <QGeoCoordinate>
19
#include <QElapsedTimer>
20

Don Gagne's avatar
Don Gagne committed
21
#include "FactGroup.h"
22 23
#include "LinkInterface.h"
#include "QGCMAVLink.h"
24
#include "QmlObjectListModel.h"
Don Gagne's avatar
Don Gagne committed
25
#include "MAVLinkProtocol.h"
dogmaphobic's avatar
dogmaphobic committed
26
#include "UASMessageHandler.h"
27
#include "SettingsFact.h"
28

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

Q_DECLARE_LOGGING_CATEGORY(VehicleLog)

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

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

public:
    VehicleVibrationFactGroup(QObject* parent = NULL);

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

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

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

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

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

public:
    VehicleWindFactGroup(QObject* parent = NULL);

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

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

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

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

Don Gagne's avatar
Don Gagne committed
108 109 110 111 112 113 114 115 116 117 118 119 120
class VehicleGPSFactGroup : public FactGroup
{
    Q_OBJECT

public:
    VehicleGPSFactGroup(QObject* parent = NULL);

    Q_PROPERTY(Fact* hdop               READ hdop               CONSTANT)
    Q_PROPERTY(Fact* vdop               READ vdop               CONSTANT)
    Q_PROPERTY(Fact* courseOverGround   READ courseOverGround   CONSTANT)
    Q_PROPERTY(Fact* count              READ count              CONSTANT)
    Q_PROPERTY(Fact* lock               READ lock               CONSTANT)

121 122 123 124 125
    Fact* hdop              (void) { return &_hdopFact; }
    Fact* vdop              (void) { return &_vdopFact; }
    Fact* courseOverGround  (void) { return &_courseOverGroundFact; }
    Fact* count             (void) { return &_countFact; }
    Fact* lock              (void) { return &_lockFact; }
Don Gagne's avatar
Don Gagne committed
126

Don Gagne's avatar
Don Gagne committed
127 128 129 130 131 132
    static const char* _hdopFactName;
    static const char* _vdopFactName;
    static const char* _courseOverGroundFactName;
    static const char* _countFactName;
    static const char* _lockFactName;

Don Gagne's avatar
Don Gagne committed
133 134 135 136 137 138
private:
    Fact        _hdopFact;
    Fact        _vdopFact;
    Fact        _courseOverGroundFact;
    Fact        _countFact;
    Fact        _lockFact;
Don Gagne's avatar
Don Gagne committed
139
};
Don Gagne's avatar
Don Gagne committed
140

Don Gagne's avatar
Don Gagne committed
141 142 143 144 145 146 147 148 149 150 151 152
class VehicleBatteryFactGroup : public FactGroup
{
    Q_OBJECT

public:
    VehicleBatteryFactGroup(QObject* parent = NULL);

    Q_PROPERTY(Fact* voltage            READ voltage            CONSTANT)
    Q_PROPERTY(Fact* percentRemaining   READ percentRemaining   CONSTANT)
    Q_PROPERTY(Fact* mahConsumed        READ mahConsumed        CONSTANT)
    Q_PROPERTY(Fact* current            READ current            CONSTANT)
    Q_PROPERTY(Fact* temperature        READ temperature        CONSTANT)
153 154 155 156 157 158 159 160
    Q_PROPERTY(Fact* cellCount          READ cellCount          CONSTANT)

    Fact* voltage                   (void) { return &_voltageFact; }
    Fact* percentRemaining          (void) { return &_percentRemainingFact; }
    Fact* mahConsumed               (void) { return &_mahConsumedFact; }
    Fact* current                   (void) { return &_currentFact; }
    Fact* temperature               (void) { return &_temperatureFact; }
    Fact* cellCount                 (void) { return &_cellCountFact; }
Don Gagne's avatar
Don Gagne committed
161 162 163 164 165 166 167 168 169


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

170 171
    static const char* _settingsGroup;

Don Gagne's avatar
Don Gagne committed
172 173 174 175 176 177 178 179
    static const double _voltageUnavailable;
    static const int    _percentRemainingUnavailable;
    static const int    _mahConsumedUnavailable;
    static const int    _currentUnavailable;
    static const double _temperatureUnavailable;
    static const int    _cellCountUnavailable;

private:
180 181 182 183 184 185
    Fact            _voltageFact;
    Fact            _percentRemainingFact;
    Fact            _mahConsumedFact;
    Fact            _currentFact;
    Fact            _temperatureFact;
    Fact            _cellCountFact;
Don Gagne's avatar
Don Gagne committed
186 187
};

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

public:
    VehicleTemperatureFactGroup(QObject* parent = NULL);

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

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

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

    static const char* _settingsGroup;

    static const double _temperatureUnavailable;

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

Don Gagne's avatar
Don Gagne committed
217
class Vehicle : public FactGroup
218 219
{
    Q_OBJECT
dogmaphobic's avatar
dogmaphobic committed
220

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

230 231 232 233 234
    // The following is used to create a disconnected Vehicle for use while offline editing.
    Vehicle(MAV_AUTOPILOT           firmwareType,
            MAV_TYPE                vehicleType,
            FirmwarePluginManager*  firmwarePluginManager,
            QObject*                parent = NULL);
235

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

238 239 240 241 242
    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)
243
    Q_PROPERTY(bool                 autoDisarm              READ autoDisarm                                             NOTIFY autoDisarmChanged)
244 245 246 247 248
    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)
249
    Q_PROPERTY(QmlObjectListModel*  cameraTriggerPoints     READ cameraTriggerPoints                                    CONSTANT)
250 251 252 253 254 255 256 257 258 259 260 261 262 263 264 265 266
    Q_PROPERTY(float                latitude                READ latitude                                               NOTIFY coordinateChanged)
    Q_PROPERTY(float                longitude               READ longitude                                              NOTIFY coordinateChanged)
    Q_PROPERTY(bool                 messageTypeNone         READ messageTypeNone                                        NOTIFY messageTypeChanged)
    Q_PROPERTY(bool                 messageTypeNormal       READ messageTypeNormal                                      NOTIFY messageTypeChanged)
    Q_PROPERTY(bool                 messageTypeWarning      READ messageTypeWarning                                     NOTIFY messageTypeChanged)
    Q_PROPERTY(bool                 messageTypeError        READ messageTypeError                                       NOTIFY messageTypeChanged)
    Q_PROPERTY(int                  newMessageCount         READ newMessageCount                                        NOTIFY newMessageCountChanged)
    Q_PROPERTY(int                  messageCount            READ messageCount                                           NOTIFY messageCountChanged)
    Q_PROPERTY(QString              formatedMessages        READ formatedMessages                                       NOTIFY formatedMessagesChanged)
    Q_PROPERTY(QString              formatedMessage         READ formatedMessage                                        NOTIFY formatedMessageChanged)
    Q_PROPERTY(QString              latestError             READ latestError                                            NOTIFY latestErrorChanged)
    Q_PROPERTY(int                  joystickMode            READ joystickMode           WRITE setJoystickMode           NOTIFY joystickModeChanged)
    Q_PROPERTY(QStringList          joystickModes           READ joystickModes                                          CONSTANT)
    Q_PROPERTY(bool                 joystickEnabled         READ joystickEnabled        WRITE setJoystickEnabled        NOTIFY joystickEnabledChanged)
    Q_PROPERTY(bool                 active                  READ active                 WRITE setActive                 NOTIFY activeChanged)
    Q_PROPERTY(int                  flowImageIndex          READ flowImageIndex                                         NOTIFY flowImageIndexChanged)
    Q_PROPERTY(int                  rcRSSI                  READ rcRSSI                                                 NOTIFY rcRSSIChanged)
267 268
    Q_PROPERTY(bool                 px4Firmware             READ px4Firmware                                            NOTIFY firmwareTypeChanged)
    Q_PROPERTY(bool                 apmFirmware             READ apmFirmware                                            NOTIFY firmwareTypeChanged)
269 270 271 272 273 274 275
    Q_PROPERTY(bool                 soloFirmware            READ soloFirmware           WRITE setSoloFirmware           NOTIFY soloFirmwareChanged)
    Q_PROPERTY(bool                 genericFirmware         READ genericFirmware                                        CONSTANT)
    Q_PROPERTY(bool                 connectionLost          READ connectionLost                                         NOTIFY connectionLostChanged)
    Q_PROPERTY(bool                 connectionLostEnabled   READ connectionLostEnabled  WRITE setConnectionLostEnabled  NOTIFY connectionLostEnabledChanged)
    Q_PROPERTY(uint                 messagesReceived        READ messagesReceived                                       NOTIFY messagesReceivedChanged)
    Q_PROPERTY(uint                 messagesSent            READ messagesSent                                           NOTIFY messagesSentChanged)
    Q_PROPERTY(uint                 messagesLost            READ messagesLost                                           NOTIFY messagesLostChanged)
276 277 278 279 280
    Q_PROPERTY(bool                 fixedWing               READ fixedWing                                              NOTIFY vehicleTypeChanged)
    Q_PROPERTY(bool                 multiRotor              READ multiRotor                                             NOTIFY vehicleTypeChanged)
    Q_PROPERTY(bool                 vtol                    READ vtol                                                   NOTIFY vehicleTypeChanged)
    Q_PROPERTY(bool                 rover                   READ rover                                                  NOTIFY vehicleTypeChanged)
    Q_PROPERTY(bool                 sub                     READ sub                                                    NOTIFY vehicleTypeChanged)
281
    Q_PROPERTY(bool                 supportsManualControl   READ supportsManualControl                                  CONSTANT)
282
    Q_PROPERTY(bool        supportsThrottleModeCenterZero   READ supportsThrottleModeCenterZero                         CONSTANT)
283
    Q_PROPERTY(bool                 supportsJSButton        READ supportsJSButton                                       CONSTANT)
284
    Q_PROPERTY(bool                 supportsRadio           READ supportsRadio                                          CONSTANT)
285 286
    Q_PROPERTY(bool               supportsCalibratePressure READ supportsCalibratePressure                              CONSTANT)
    Q_PROPERTY(bool               supportsMotorInterference READ supportsMotorInterference                              CONSTANT)
287 288
    Q_PROPERTY(bool                 autoDisconnect          MEMBER _autoDisconnect                                      NOTIFY autoDisconnectChanged)
    Q_PROPERTY(QString              prearmError             READ prearmError            WRITE setPrearmError            NOTIFY prearmErrorChanged)
Don Gagne's avatar
Don Gagne committed
289 290 291
    Q_PROPERTY(int                  motorCount              READ motorCount                                             CONSTANT)
    Q_PROPERTY(bool                 coaxialMotors           READ coaxialMotors                                          CONSTANT)
    Q_PROPERTY(bool                 xConfigMotors           READ xConfigMotors                                          CONSTANT)
292
    Q_PROPERTY(bool                 isOfflineEditingVehicle READ isOfflineEditingVehicle                                CONSTANT)
293 294
    Q_PROPERTY(QString              brandImageIndoor        READ brandImageIndoor                                       NOTIFY firmwareTypeChanged)
    Q_PROPERTY(QString              brandImageOutdoor       READ brandImageOutdoor                                      NOTIFY firmwareTypeChanged)
295
    Q_PROPERTY(QStringList          unhealthySensors        READ unhealthySensors                                       NOTIFY unhealthySensorsChanged)
296
    Q_PROPERTY(QString              missionFlightMode       READ missionFlightMode                                      CONSTANT)
297
    Q_PROPERTY(QString              pauseFlightMode         READ pauseFlightMode                                        CONSTANT)
298
    Q_PROPERTY(QString              rtlFlightMode           READ rtlFlightMode                                          CONSTANT)
299
    Q_PROPERTY(QString              landFlightMode          READ landFlightMode                                         CONSTANT)
300
    Q_PROPERTY(QString              takeControlFlightMode   READ takeControlFlightMode                                  CONSTANT)
301 302
    Q_PROPERTY(QString              firmwareTypeString      READ firmwareTypeString                                     NOTIFY firmwareTypeChanged)
    Q_PROPERTY(QString              vehicleTypeString       READ vehicleTypeString                                      NOTIFY vehicleTypeChanged)
303 304 305
    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
306 307 308 309 310 311 312
    Q_PROPERTY(int                  telemetryRRSSI          READ telemetryRRSSI                                         NOTIFY telemetryRRSSIChanged)
    Q_PROPERTY(int                  telemetryLRSSI          READ telemetryLRSSI                                         NOTIFY telemetryLRSSIChanged)
    Q_PROPERTY(unsigned int         telemetryRXErrors       READ telemetryRXErrors                                      NOTIFY telemetryRXErrorsChanged)
    Q_PROPERTY(unsigned int         telemetryFixed          READ telemetryFixed                                         NOTIFY telemetryFixedChanged)
    Q_PROPERTY(unsigned int         telemetryTXBuffer       READ telemetryTXBuffer                                      NOTIFY telemetryTXBufferChanged)
    Q_PROPERTY(unsigned int         telemetryLNoise         READ telemetryLNoise                                        NOTIFY telemetryLNoiseChanged)
    Q_PROPERTY(unsigned int         telemetryRNoise         READ telemetryRNoise                                        NOTIFY telemetryRNoiseChanged)
313
    Q_PROPERTY(QVariantList         toolBarIndicators       READ toolBarIndicators                                      CONSTANT)
314
    Q_PROPERTY(QVariantList         cameraList              READ cameraList                                             CONSTANT)
315

Don Gagne's avatar
Don Gagne committed
316 317 318 319 320 321 322 323 324 325 326 327
    /// true: Vehicle is flying, false: Vehicle is on ground
    Q_PROPERTY(bool flying      READ flying     WRITE setFlying     NOTIFY flyingChanged)

    /// true: Vehicle is in Guided mode and can respond to guided commands, false: vehicle cannot respond to direct control commands
    Q_PROPERTY(bool guidedMode  READ guidedMode WRITE setGuidedMode NOTIFY guidedModeChanged)

    /// true: Guided mode commands are supported by this vehicle
    Q_PROPERTY(bool guidedModeSupported READ guidedModeSupported CONSTANT)

    /// true: pauseVehicle command is supported
    Q_PROPERTY(bool pauseVehicleSupported READ pauseVehicleSupported CONSTANT)

328 329 330
    /// true: Orbit mode is supported by this vehicle
    Q_PROPERTY(bool orbitModeSupported READ orbitModeSupported CONSTANT)

331 332
    Q_PROPERTY(ParameterManager* parameterManager READ parameterManager CONSTANT)

Don Gagne's avatar
Don Gagne committed
333 334 335 336 337 338 339 340 341 342
    // 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)
343
    Q_PROPERTY(Fact* flightDistance     READ flightDistance     CONSTANT)
Don Gagne's avatar
Don Gagne committed
344

345 346 347 348 349
    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
350

351 352 353 354 355
    Q_PROPERTY(int firmwareMajorVersion READ firmwareMajorVersion NOTIFY firmwareMajorVersionChanged)
    Q_PROPERTY(int firmwareMinorVersion READ firmwareMinorVersion NOTIFY firmwareMinorVersionChanged)
    Q_PROPERTY(int firmwarePatchVersion READ firmwarePatchVersion NOTIFY firmwarePatchVersionChanged)
    Q_PROPERTY(int firmwareVersionType READ firmwareVersionType NOTIFY firmwareVersionTypeChanged)
    Q_PROPERTY(QString firmwareVersionTypeString READ firmwareVersionTypeString NOTIFY firmwareVersionTypeChanged)
356
    Q_PROPERTY(QString gitHash READ gitHash NOTIFY gitHashChanged)
357

358 359
    /// Resets link status counters
    Q_INVOKABLE void resetCounters  ();
360 361 362 363 364 365 366 367

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

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

Don Gagne's avatar
Don Gagne committed
372
    Q_INVOKABLE void virtualTabletJoystickValue(double roll, double pitch, double yaw, double thrust);
Don Gagne's avatar
Don Gagne committed
373
    Q_INVOKABLE void disconnectInactiveVehicle(void);
Don Gagne's avatar
Don Gagne committed
374

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

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

387 388 389
    /// 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
390

391 392 393 394 395 396 397
    /// 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
398 399 400 401 402 403 404
    /// 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);

405
    /// Command vehicle to abort landing
406
    Q_INVOKABLE void abortLanding(double climbOutAltitude);
407

408 409
    Q_INVOKABLE void startMission(void);

410 411 412
    /// Alter the current mission item on the vehicle
    Q_INVOKABLE void setCurrentMissionSequence(int seq);

413 414 415
    /// Reboot vehicle
    Q_INVOKABLE void rebootVehicle();

dogmaphobic's avatar
dogmaphobic committed
416 417 418
    /// Clear Messages
    Q_INVOKABLE void clearMessages();

Don Gagne's avatar
Don Gagne committed
419 420
    Q_INVOKABLE void triggerCamera(void);

Don Gagne's avatar
Don Gagne committed
421 422
#if 0
    // Temporarily removed, waiting for new command implementation
Don Gagne's avatar
Don Gagne committed
423 424 425 426 427
    /// 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
428
#endif
Don Gagne's avatar
Don Gagne committed
429

Don Gagne's avatar
Don Gagne committed
430 431
    bool guidedModeSupported(void) const;
    bool pauseVehicleSupported(void) const;
432
    bool orbitModeSupported(void) const;
Don Gagne's avatar
Don Gagne committed
433

434
    // Property accessors
Don Gagne's avatar
Don Gagne committed
435

436
    QGeoCoordinate coordinate(void) { return _coordinate; }
dogmaphobic's avatar
dogmaphobic committed
437

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

447 448
    int joystickMode(void);
    void setJoystickMode(int mode);
dogmaphobic's avatar
dogmaphobic committed
449

450 451
    /// List of joystick mode names
    QStringList joystickModes(void);
dogmaphobic's avatar
dogmaphobic committed
452

453 454
    bool joystickEnabled(void);
    void setJoystickEnabled(bool enabled);
dogmaphobic's avatar
dogmaphobic committed
455

456 457 458
    // Is vehicle active with respect to current active vehicle in QGC
    bool active(void);
    void setActive(bool active);
dogmaphobic's avatar
dogmaphobic committed
459

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

466 467 468
    /// Returns the highest quality link available to the Vehicle. If you need to hold a refernce to this link use
    /// LinkManager::sharedLinkInterfaceForGet to get QSharedPointer for link.
    LinkInterface* priorityLink(void) { return _priorityLink.data(); }
469 470 471 472 473

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

474 475 476
    /// 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
477

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

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

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

487
    int manualControlReservedButtonCount(void);
dogmaphobic's avatar
dogmaphobic committed
488

489 490 491
    MissionManager*     missionManager(void)    { return _missionManager; }
    GeoFenceManager*    geoFenceManager(void)   { return _geoFenceManager; }
    RallyPointManager*  rallyPointManager(void) { return _rallyPointManager; }
dogmaphobic's avatar
dogmaphobic committed
492

493
    QGeoCoordinate homePosition(void);
dogmaphobic's avatar
dogmaphobic committed
494

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

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

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

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

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

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

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

525
    QmlObjectListModel* trajectoryPoints(void) { return &_mapTrajectoryList; }
526
    QmlObjectListModel* cameraTriggerPoints(void) { return &_cameraTriggerPoints; }
dogmaphobic's avatar
dogmaphobic committed
527 528 529

    int  flowImageIndex() { return _flowImageIndex; }

530 531 532 533
    //-- Mavlink Logging
    void startMavlinkLog();
    void stopMavlinkLog();

534 535 536
    /// 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
537 538
    ///     @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
539

540 541 542 543 544 545
    typedef enum {
        MessageNone,
        MessageNormal,
        MessageWarning,
        MessageError
    } MessageType_t;
dogmaphobic's avatar
dogmaphobic committed
546

547 548 549 550 551 552 553 554 555 556 557 558 559 560 561 562 563 564 565 566 567 568 569 570 571 572
    bool            messageTypeNone         () { return _currentMessageType == MessageNone; }
    bool            messageTypeNormal       () { return _currentMessageType == MessageNormal; }
    bool            messageTypeWarning      () { return _currentMessageType == MessageWarning; }
    bool            messageTypeError        () { return _currentMessageType == MessageError; }
    int             newMessageCount         () { return _currentMessageCount; }
    int             messageCount            () { return _messageCount; }
    QString         formatedMessages        ();
    QString         formatedMessage         () { return _formatedMessage; }
    QString         latestError             () { return _latestError; }
    float           latitude                () { return _coordinate.latitude(); }
    float           longitude               () { return _coordinate.longitude(); }
    bool            mavPresent              () { return _mav != NULL; }
    int             rcRSSI                  () { return _rcRSSI; }
    bool            px4Firmware             () const { return _firmwareType == MAV_AUTOPILOT_PX4; }
    bool            apmFirmware             () const { return _firmwareType == MAV_AUTOPILOT_ARDUPILOTMEGA; }
    bool            genericFirmware         () const { return !px4Firmware() && !apmFirmware(); }
    bool            connectionLost          () const { return _connectionLost; }
    bool            connectionLostEnabled   () const { return _connectionLostEnabled; }
    uint            messagesReceived        () { return _messagesReceived; }
    uint            messagesSent            () { return _messagesSent; }
    uint            messagesLost            () { return _messagesLost; }
    bool            flying                  () const { return _flying; }
    bool            guidedMode              () const;
    uint8_t         baseMode                () const { return _base_mode; }
    uint32_t        customMode              () const { return _custom_mode; }
    bool            isOfflineEditingVehicle () const { return _offlineEditingVehicle; }
573 574
    QString         brandImageIndoor        () const;
    QString         brandImageOutdoor       () const;
575
    QStringList     unhealthySensors        () const;
576
    QString         missionFlightMode       () const;
577
    QString         pauseFlightMode         () const;
578
    QString         rtlFlightMode           () const;
579
    QString         landFlightMode          () const;
580
    QString         takeControlFlightMode   () const;
DonLakeFlyer's avatar
DonLakeFlyer committed
581 582
    double          defaultCruiseSpeed      () const { return _defaultCruiseSpeed; }
    double          defaultHoverSpeed       () const { return _defaultHoverSpeed; }
583
    QString         firmwareTypeString      () const;
Gus Grubba's avatar
Gus Grubba committed
584 585 586 587 588 589 590 591
    QString         vehicleTypeString       () const;
    int             telemetryRRSSI          () { return _telemetryRRSSI; }
    int             telemetryLRSSI          () { return _telemetryLRSSI; }
    unsigned int    telemetryRXErrors       () { return _telemetryRXErrors; }
    unsigned int    telemetryFixed          () { return _telemetryFixed; }
    unsigned int    telemetryTXBuffer       () { return _telemetryTXBuffer; }
    unsigned int    telemetryLNoise         () { return _telemetryLNoise; }
    unsigned int    telemetryRNoise         () { return _telemetryRNoise; }
592
    bool            autoDisarm              ();
593

Don Gagne's avatar
Don Gagne committed
594 595 596 597 598 599 600 601
    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; }
602
    Fact* flightDistance    (void) { return &_flightDistanceFact; }
Don Gagne's avatar
Don Gagne committed
603

604 605 606 607
    FactGroup* gpsFactGroup         (void) { return &_gpsFactGroup; }
    FactGroup* batteryFactGroup     (void) { return &_batteryFactGroup; }
    FactGroup* windFactGroup        (void) { return &_windFactGroup; }
    FactGroup* vibrationFactGroup   (void) { return &_vibrationFactGroup; }
608
    FactGroup* temperatureFactGroup (void) { return &_temperatureFactGroup; }
Don Gagne's avatar
Don Gagne committed
609

610
    void setConnectionLostEnabled(bool connectionLostEnabled);
611

612 613
    ParameterManager* parameterManager(void) { return _parameterManager; }
    ParameterManager* parameterManager(void) const { return _parameterManager; }
dogmaphobic's avatar
dogmaphobic committed
614

Don Gagne's avatar
Don Gagne committed
615 616
    static const int cMaxRcChannels = 18;

Don Gagne's avatar
Don Gagne committed
617
    bool containsLink(LinkInterface* link) { return _links.contains(link); }
618 619 620 621 622 623

    /// 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
624
    /// Signals: mavCommandResult on success or failure
625
    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
626

Don Gagne's avatar
Don Gagne committed
627 628 629
    int firmwareMajorVersion(void) const { return _firmwareMajorVersion; }
    int firmwareMinorVersion(void) const { return _firmwareMinorVersion; }
    int firmwarePatchVersion(void) const { return _firmwarePatchVersion; }
630 631 632
    int firmwareVersionType(void) const { return _firmwareVersionType; }
    QString firmwareVersionTypeString(void) const;
    void setFirmwareVersion(int majorVersion, int minorVersion, int patchVersion, FIRMWARE_VERSION_TYPE versionType = FIRMWARE_VERSION_TYPE_OFFICIAL);
633
    static const int versionNotSetValue = -1;
Don Gagne's avatar
Don Gagne committed
634

635 636
    QString gitHash(void) const { return _gitHash; }

637 638 639
    bool soloFirmware(void) const { return _soloFirmware; }
    void setSoloFirmware(bool soloFirmware);

640 641 642 643
    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
644

Don Gagne's avatar
Don Gagne committed
645 646 647 648 649 650 651 652 653
    /// @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);

654 655 656 657 658 659 660
    /// @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);

661 662 663 664
    QString vehicleImageOpaque  () const;
    QString vehicleImageOutline () const;
    QString vehicleImageCompass () const;

665 666
    const QVariantList& toolBarIndicators   ();
    const QVariantList& cameraList          (void) const;
667

668
    bool supportsMissionItemInt(void) const { return _supportsMissionItemInt; }
669

670 671 672
    /// @true: When flying a mission the vehicle is always facing towards the next waypoint
    bool vehicleYawsToNextWaypointInMission(void) const;

DonLakeFlyer's avatar
DonLakeFlyer committed
673 674 675 676
    /// 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; }

DonLakeFlyer's avatar
DonLakeFlyer committed
677 678
    void _setHomePosition(QGeoCoordinate& homeCoord);

679
signals:
Don Gagne's avatar
Don Gagne committed
680
    void allLinksInactive(Vehicle* vehicle);
681
    void coordinateChanged(QGeoCoordinate coordinate);
682
    void joystickModeChanged(int mode);
683 684
    void joystickEnabledChanged(bool enabled);
    void activeChanged(bool active);
Don Gagne's avatar
Don Gagne committed
685
    void mavlinkMessageReceived(const mavlink_message_t& message);
686
    void homePositionChanged(const QGeoCoordinate& homePosition);
Don Gagne's avatar
Don Gagne committed
687 688 689
    void armedChanged(bool armed);
    void flightModeChanged(const QString& flightMode);
    void hilModeChanged(bool hilMode);
690 691
    /** @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);
692 693
    void connectionLostChanged(bool connectionLost);
    void connectionLostEnabledChanged(bool connectionLostEnabled);
Don Gagne's avatar
Don Gagne committed
694
    void autoDisconnectChanged(bool autoDisconnectChanged);
Don Gagne's avatar
Don Gagne committed
695 696
    void flyingChanged(bool flying);
    void guidedModeChanged(bool guidedMode);
Don Gagne's avatar
Don Gagne committed
697
    void prearmErrorChanged(const QString& prearmError);
698
    void soloFirmwareChanged(bool soloFirmware);
699
    void unhealthySensorsChanged(void);
DonLakeFlyer's avatar
DonLakeFlyer committed
700 701
    void defaultCruiseSpeedChanged(double cruiseSpeed);
    void defaultHoverSpeedChanged(double hoverSpeed);
702 703
    void firmwareTypeChanged(void);
    void vehicleTypeChanged(void);
dogmaphobic's avatar
dogmaphobic committed
704

705 706 707 708
    void messagesReceivedChanged    ();
    void messagesSentChanged        ();
    void messagesLostChanged        ();

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

Gus Grubba's avatar
Gus Grubba committed
712 713 714 715 716 717 718 719 720 721 722 723 724 725 726 727 728
    void messageTypeChanged         ();
    void newMessageCountChanged     ();
    void messageCountChanged        ();
    void formatedMessagesChanged    ();
    void formatedMessageChanged     ();
    void latestErrorChanged         ();
    void longitudeChanged           ();
    void currentConfigChanged       ();
    void flowImageIndexChanged      ();
    void rcRSSIChanged              (int rcRSSI);
    void telemetryRRSSIChanged      (int value);
    void telemetryLRSSIChanged      (int value);
    void telemetryRXErrorsChanged   (unsigned int value);
    void telemetryFixedChanged      (unsigned int value);
    void telemetryTXBufferChanged   (unsigned int value);
    void telemetryLNoiseChanged     (unsigned int value);
    void telemetryRNoiseChanged     (unsigned int value);
729
    void autoDisarmChanged          (void);
dogmaphobic's avatar
dogmaphobic committed
730

731 732 733 734 735
    void firmwareMajorVersionChanged(int major);
    void firmwareMinorVersionChanged(int minor);
    void firmwarePatchVersionChanged(int patch);
    void firmwareVersionTypeChanged(int type);

736 737
    void gitHashChanged(QString hash);

Don Gagne's avatar
Don Gagne committed
738 739 740 741 742 743 744 745
    /// 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);

746 747 748 749 750
    void mavlinkRawImu(mavlink_message_t message);
    void mavlinkScaledImu1(mavlink_message_t message);
    void mavlinkScaledImu2(mavlink_message_t message);
    void mavlinkScaledImu3(mavlink_message_t message);

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

754 755 756 757 758 759
    /// 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
760
    void mavCommandResult(int vehicleId, int component, int command, int result, bool noReponseFromVehicle);
761

762 763 764
    // Mavlink Serial Data
    void mavlinkSerialControl(uint8_t device, uint8_t flags, uint16_t timeout, uint32_t baudrate, QByteArray data);

765 766
private slots:
    void _mavlinkMessageReceived(LinkInterface* link, mavlink_message_t message);
Gus Grubba's avatar
Gus Grubba committed
767
    void _telemetryChanged(LinkInterface* link, unsigned rxerrors, unsigned fixed, int rssi, int remrssi, unsigned txbuf, unsigned noise, unsigned remnoise);
Don Gagne's avatar
Don Gagne committed
768
    void _linkInactiveOrDeleted(LinkInterface* link);
769
    void _sendMessageOnLink(LinkInterface* link, mavlink_message_t message);
770
    void _sendMessageMultipleNext(void);
771
    void _addNewMapTrajectoryPoint(void);
772
    void _parametersReady(bool parametersReady);
Don Gagne's avatar
Don Gagne committed
773
    void _remoteControlRSSIChanged(uint8_t rssi);
Don Gagne's avatar
Don Gagne committed
774
    void _handleFlightModeChanged(const QString& flightMode);
775
    void _announceArmedChanged(bool armed);
776 777 778 779
    void _offlineFirmwareTypeSettingChanged(QVariant value);
    void _offlineVehicleTypeSettingChanged(QVariant value);
    void _offlineCruiseSpeedSettingChanged(QVariant value);
    void _offlineHoverSpeedSettingChanged(QVariant value);
780

781
    void _handleTextMessage                 (int newCount);
dogmaphobic's avatar
dogmaphobic committed
782
    void _handletextMessageReceived         (UASMessage* message);
783 784 785 786
    /** @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
787 788
    /** @brief A new camera image has arrived */
    void _imageReady                        (UASInterface* uas);
789
    void _connectionLostTimeout(void);
Don Gagne's avatar
Don Gagne committed
790
    void _prearmErrorTimeout(void);
DonLakeFlyer's avatar
DonLakeFlyer committed
791 792 793
    void _missionLoadComplete(void);
    void _geoFenceLoadComplete(void);
    void _rallyPointLoadComplete(void);
794
    void _sendMavCommandAgain(void);
Jacob Walser's avatar
Jacob Walser committed
795
    void _activeJoystickChanged(void);
796 797
    void _clearTrajectoryPoints(void);
    void _clearCameraTriggerPoints(void);
Jacob Walser's avatar
Jacob Walser committed
798

799 800 801
private:
    bool _containsLink(LinkInterface* link);
    void _addLink(LinkInterface* link);
802 803
    void _loadSettings(void);
    void _saveSettings(void);
804
    void _startJoystick(bool start);
Don Gagne's avatar
Don Gagne committed
805 806
    void _handleHomePosition(mavlink_message_t& message);
    void _handleHeartbeat(mavlink_message_t& message);
Don Gagne's avatar
Don Gagne committed
807 808
    void _handleRCChannels(mavlink_message_t& message);
    void _handleRCChannelsRaw(mavlink_message_t& message);
Don Gagne's avatar
Don Gagne committed
809 810
    void _handleBatteryStatus(mavlink_message_t& message);
    void _handleSysStatus(mavlink_message_t& message);
811
    void _handleWindCov(mavlink_message_t& message);
Don Gagne's avatar
Don Gagne committed
812
    void _handleWind(mavlink_message_t& message);
813
    void _handleVibration(mavlink_message_t& message);
Don Gagne's avatar
Don Gagne committed
814
    void _handleExtendedSysState(mavlink_message_t& message);
815
    void _handleCommandAck(mavlink_message_t& message);
Gus Grubba's avatar
Gus Grubba committed
816
    void _handleAutopilotVersion(LinkInterface* link, mavlink_message_t& message);
817
    void _handleHilActuatorControls(mavlink_message_t& message);
818 819 820 821
    void _handleGpsRawInt(mavlink_message_t& message);
    void _handleGlobalPositionInt(mavlink_message_t& message);
    void _handleAltitude(mavlink_message_t& message);
    void _handleVfrHud(mavlink_message_t& message);
822 823 824
    void _handleScaledPressure(mavlink_message_t& message);
    void _handleScaledPressure2(mavlink_message_t& message);
    void _handleScaledPressure3(mavlink_message_t& message);
825 826
    void _handleCameraFeedback(const mavlink_message_t& message);
    void _handleCameraImageCaptured(const mavlink_message_t& message);
827
    void _missionManagerError(int errorCode, const QString& errorMsg);
828
    void _geoFenceManagerError(int errorCode, const QString& errorMsg);
829
    void _rallyPointManagerError(int errorCode, const QString& errorMsg);
830 831
    void _mapTrajectoryStart(void);
    void _mapTrajectoryStop(void);
832
    void _connectionActive(void);
833 834
    void _say(const QString& text);
    QString _vehicleIdSpeech(void);
835 836 837
    void _handleMavlinkLoggingData(mavlink_message_t& message);
    void _handleMavlinkLoggingDataAcked(mavlink_message_t& message);
    void _ackMavlinkLogData(uint16_t sequence);
838
    void _sendNextQueuedMavCommand(void);
839
    void _updatePriorityLink(void);
840
    void _commonInit(void);
DonLakeFlyer's avatar
DonLakeFlyer committed
841
    void _startPlanRequest(void);
842
    void _setupAutoDisarmSignalling(void);
DonLakeFlyer's avatar
DonLakeFlyer committed
843
    void _setCapabilities(uint64_t capabilityBits);
Don Gagne's avatar
Don Gagne committed
844

845
    int     _id;                    ///< Mavlink system id
846
    int     _defaultComponentId;
847
    bool    _active;
848
    bool    _offlineEditingVehicle; ///< This Vehicle is a "disconnected" vehicle for ui use while offline editing
dogmaphobic's avatar
dogmaphobic committed
849

850
    MAV_AUTOPILOT       _firmwareType;
851
    MAV_TYPE            _vehicleType;
852
    FirmwarePlugin*     _firmwarePlugin;
853
    QObject*            _firmwarePluginInstanceData;
854
    AutoPilotPlugin*    _autopilotPlugin;
Don Gagne's avatar
Don Gagne committed
855
    MAVLinkProtocol*    _mavlink;
856
    bool                _soloFirmware;
857
    SettingsManager*    _settingsManager;
dogmaphobic's avatar
dogmaphobic committed
858

Don Gagne's avatar
Don Gagne committed
859
    QList<LinkInterface*> _links;
dogmaphobic's avatar
dogmaphobic committed
860

861
    JoystickMode_t  _joystickMode;
862
    bool            _joystickEnabled;
dogmaphobic's avatar
dogmaphobic committed
863

864
    UAS* _uas;
dogmaphobic's avatar
dogmaphobic committed
865

866
    QGeoCoordinate  _coordinate;
867
    QGeoCoordinate  _homePosition;
dogmaphobic's avatar
dogmaphobic committed
868

869 870 871 872 873 874 875 876 877
    UASInterface*   _mav;
    int             _currentMessageCount;
    int             _messageCount;
    int             _currentErrorCount;
    int             _currentWarningCount;
    int             _currentNormalCount;
    MessageType_t   _currentMessageType;
    QString         _latestError;
    int             _updateCount;
dogmaphobic's avatar
dogmaphobic committed
878
    QString         _formatedMessage;
Don Gagne's avatar
Don Gagne committed
879 880
    int             _rcRSSI;
    double          _rcRSSIstore;
Don Gagne's avatar
Don Gagne committed
881
    bool            _autoDisconnect;    ///< true: Automatically disconnect vehicle when last connection goes away or lost heartbeat
Don Gagne's avatar
Don Gagne committed
882
    bool            _flying;
883 884 885 886
    uint32_t        _onboardControlSensorsPresent;
    uint32_t        _onboardControlSensorsEnabled;
    uint32_t        _onboardControlSensorsHealth;
    uint32_t        _onboardControlSensorsUnhealthy;
887 888
    bool            _gpsRawIntMessageAvailable;
    bool            _globalPositionIntMessageAvailable;
DonLakeFlyer's avatar
DonLakeFlyer committed
889 890
    double          _defaultCruiseSpeed;
    double          _defaultHoverSpeed;
Gus Grubba's avatar
Gus Grubba committed
891 892 893 894 895 896 897
    int             _telemetryRRSSI;
    int             _telemetryLRSSI;
    uint32_t        _telemetryRXErrors;
    uint32_t        _telemetryFixed;
    uint32_t        _telemetryTXBuffer;
    uint32_t        _telemetryLNoise;
    uint32_t        _telemetryRNoise;
898 899
    bool            _vehicleCapabilitiesKnown;
    bool            _supportsMissionItemInt;
dogmaphobic's avatar
dogmaphobic committed
900

901 902 903 904 905 906 907 908 909 910 911
    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;
912
    static const int                _mavCommandAckTimeoutMSecs = 3000;
913

Don Gagne's avatar
Don Gagne committed
914 915 916 917
    QString             _prearmError;
    QTimer              _prearmErrorTimer;
    static const int    _prearmErrorTimeoutMSecs = 35 * 1000;   ///< Take away prearm error after 35 seconds

918 919 920 921 922 923
    // 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
924 925
    bool                _initialPlanRequestComplete;

Don Gagne's avatar
Don Gagne committed
926
    MissionManager*     _missionManager;
927
    bool                _missionManagerInitialRequestSent;
928

929
    GeoFenceManager*    _geoFenceManager;
930 931 932 933
    bool                _geoFenceManagerInitialRequestSent;

    RallyPointManager*  _rallyPointManager;
    bool                _rallyPointManagerInitialRequestSent;
934

935
    ParameterManager*    _parameterManager;
dogmaphobic's avatar
dogmaphobic committed
936

Don Gagne's avatar
Don Gagne committed
937 938 939
    bool    _armed;         ///< true: vehicle is armed
    uint8_t _base_mode;     ///< base_mode from HEARTBEAT
    uint32_t _custom_mode;  ///< custom_mode from HEARTBEAT
940 941 942 943 944 945

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

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

949 950
    static const int _sendMessageMultipleRetries = 5;
    static const int _sendMessageMultipleIntraMessageDelay = 500;
dogmaphobic's avatar
dogmaphobic committed
951

952 953
    QTimer  _sendMultipleTimer;
    int     _nextSendMessageMultipleIndex;
dogmaphobic's avatar
dogmaphobic committed
954

955 956 957 958 959
    QTimer              _mapTrajectoryTimer;
    QmlObjectListModel  _mapTrajectoryList;
    QGeoCoordinate      _mapTrajectoryLastCoordinate;
    bool                _mapTrajectoryHaveFirstCoordinate;
    static const int    _mapTrajectoryMsecsBetweenPoints = 1000;
960

961 962
    QmlObjectListModel  _cameraTriggerPoints;

963
    // Toolbox references
dogmaphobic's avatar
dogmaphobic committed
964 965 966 967 968
    FirmwarePluginManager*      _firmwarePluginManager;
    JoystickManager*            _joystickManager;

    int                         _flowImageIndex;

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

971 972 973 974 975 976 977
    uint                _messagesReceived;
    uint                _messagesSent;
    uint                _messagesLost;
    uint8_t             _messageSeq;
    uint8_t             _compID;
    bool                _heardFrom;

Don Gagne's avatar
Don Gagne committed
978 979 980
    int _firmwareMajorVersion;
    int _firmwareMinorVersion;
    int _firmwarePatchVersion;
981
    FIRMWARE_VERSION_TYPE _firmwareVersionType;
Don Gagne's avatar
Don Gagne committed
982

983 984
    QString _gitHash;

985
    int _lastAnnouncedLowBatteryPercent;
986

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

Don Gagne's avatar
Don Gagne committed
989 990 991 992 993 994 995 996 997 998
    // FactGroup facts

    Fact _rollFact;
    Fact _pitchFact;
    Fact _headingFact;
    Fact _groundSpeedFact;
    Fact _airSpeedFact;
    Fact _climbRateFact;
    Fact _altitudeRelativeFact;
    Fact _altitudeAMSLFact;
999
    Fact _flightDistanceFact;
Don Gagne's avatar
Don Gagne committed
1000

1001 1002 1003 1004
    VehicleGPSFactGroup         _gpsFactGroup;
    VehicleBatteryFactGroup     _batteryFactGroup;
    VehicleWindFactGroup        _windFactGroup;
    VehicleVibrationFactGroup   _vibrationFactGroup;
1005
    VehicleTemperatureFactGroup _temperatureFactGroup;
Don Gagne's avatar
Don Gagne committed
1006 1007 1008 1009 1010 1011 1012 1013 1014

    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;
1015
    static const char* _flightDistanceFactName;
Don Gagne's avatar
Don Gagne committed
1016

Don Gagne's avatar
Don Gagne committed
1017
    static const char* _gpsFactGroupName;
Don Gagne's avatar
Don Gagne committed
1018
    static const char* _batteryFactGroupName;
Don Gagne's avatar
Don Gagne committed
1019
    static const char* _windFactGroupName;
1020
    static const char* _vibrationFactGroupName;
1021
    static const char* _temperatureFactGroupName;
Don Gagne's avatar
Don Gagne committed
1022 1023 1024

    static const int _vehicleUIUpdateRateMSecs = 100;

1025
    // Settings keys
1026 1027
    static const char* _settingsGroup;
    static const char* _joystickModeSettingsKey;
1028
    static const char* _joystickEnabledSettingsKey;
Don Gagne's avatar
Don Gagne committed
1029

1030 1031
};
#endif