Vehicle.h 82.4 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 <QVariantList>
14
#include <QGeoCoordinate>
15

Don Gagne's avatar
Don Gagne committed
16
#include "FactGroup.h"
17 18
#include "LinkInterface.h"
#include "QGCMAVLink.h"
19
#include "QmlObjectListModel.h"
Don Gagne's avatar
Don Gagne committed
20
#include "MAVLinkProtocol.h"
dogmaphobic's avatar
dogmaphobic committed
21
#include "UASMessageHandler.h"
22
#include "SettingsFact.h"
23
#include "QGCMapCircle.h"
24

25 26
class UAS;
class UASInterface;
27
class FirmwarePlugin;
28
class FirmwarePluginManager;
29
class AutoPilotPlugin;
Don Gagne's avatar
Don Gagne committed
30
class MissionManager;
31
class GeoFenceManager;
32
class RallyPointManager;
33
class ParameterManager;
34
class JoystickManager;
dogmaphobic's avatar
dogmaphobic committed
35
class UASMessage;
36
class SettingsManager;
37
class ADSBVehicle;
38
class QGCCameraManager;
Gus Grubba's avatar
Gus Grubba committed
39
class Joystick;
40 41 42
#if defined(QGC_AIRMAP_ENABLED)
class AirspaceVehicleManager;
#endif
43 44 45

Q_DECLARE_LOGGING_CATEGORY(VehicleLog)

Don Gagne's avatar
Don Gagne committed
46 47
class Vehicle;

48 49 50 51 52
class VehicleDistanceSensorFactGroup : public FactGroup
{
    Q_OBJECT

public:
53
    VehicleDistanceSensorFactGroup(QObject* parent = nullptr);
54

55 56 57 58 59 60 61 62 63 64
    Q_PROPERTY(Fact* rotationNone       READ rotationNone       CONSTANT)
    Q_PROPERTY(Fact* rotationYaw45      READ rotationYaw45      CONSTANT)
    Q_PROPERTY(Fact* rotationYaw90      READ rotationYaw90      CONSTANT)
    Q_PROPERTY(Fact* rotationYaw135     READ rotationYaw135     CONSTANT)
    Q_PROPERTY(Fact* rotationYaw180     READ rotationYaw180     CONSTANT)
    Q_PROPERTY(Fact* rotationYaw225     READ rotationYaw225     CONSTANT)
    Q_PROPERTY(Fact* rotationYaw270     READ rotationYaw270     CONSTANT)
    Q_PROPERTY(Fact* rotationYaw315     READ rotationYaw315     CONSTANT)
    Q_PROPERTY(Fact* rotationPitch90    READ rotationPitch90    CONSTANT)
    Q_PROPERTY(Fact* rotationPitch270   READ rotationPitch270   CONSTANT)
65 66

    Fact* rotationNone      (void) { return &_rotationNoneFact; }
67
    Fact* rotationYaw45     (void) { return &_rotationYaw45Fact; }
68
    Fact* rotationYaw90     (void) { return &_rotationYaw90Fact; }
69
    Fact* rotationYaw135    (void) { return &_rotationYaw90Fact; }
70
    Fact* rotationYaw180    (void) { return &_rotationYaw180Fact; }
71
    Fact* rotationYaw225    (void) { return &_rotationYaw180Fact; }
72
    Fact* rotationYaw270    (void) { return &_rotationYaw270Fact; }
73 74 75 76 77 78
    Fact* rotationYaw315    (void) { return &_rotationYaw315Fact; }
    Fact* rotationPitch90   (void) { return &_rotationPitch90Fact; }
    Fact* rotationPitch270  (void) { return &_rotationPitch270Fact; }

    bool idSet(void) { return _idSet; }
    void setIdSet(bool idSet) { _idSet = idSet; }
79 80
    uint8_t id(void) { return _id; }
    void setId(uint8_t id) { _id = id; }
81 82

    static const char* _rotationNoneFactName;
83
    static const char* _rotationYaw45FactName;
84
    static const char* _rotationYaw90FactName;
85
    static const char* _rotationYaw135FactName;
86
    static const char* _rotationYaw180FactName;
87
    static const char* _rotationYaw225FactName;
88
    static const char* _rotationYaw270FactName;
89 90 91
    static const char* _rotationYaw315FactName;
    static const char* _rotationPitch90FactName;
    static const char* _rotationPitch270FactName;
92 93 94

private:
    Fact _rotationNoneFact;
95
    Fact _rotationYaw45Fact;
96
    Fact _rotationYaw90Fact;
97
    Fact _rotationYaw135Fact;
98
    Fact _rotationYaw180Fact;
99
    Fact _rotationYaw225Fact;
100
    Fact _rotationYaw270Fact;
101 102 103 104 105 106
    Fact _rotationYaw315Fact;
    Fact _rotationPitch90Fact;
    Fact _rotationPitch270Fact;

    bool    _idSet; // true: _id is set to seen sensor id
    uint8_t _id;    // The id for the sensor being tracked. Current support for only a single sensor.
107 108
};

DonLakeFlyer's avatar
DonLakeFlyer committed
109 110 111 112 113
class VehicleSetpointFactGroup : public FactGroup
{
    Q_OBJECT

public:
114
    VehicleSetpointFactGroup(QObject* parent = nullptr);
DonLakeFlyer's avatar
DonLakeFlyer committed
115 116 117 118 119 120 121 122 123 124 125 126 127 128 129 130 131 132 133 134 135 136 137 138 139 140 141 142 143 144 145

    Q_PROPERTY(Fact* roll       READ roll       CONSTANT)
    Q_PROPERTY(Fact* pitch      READ pitch      CONSTANT)
    Q_PROPERTY(Fact* yaw        READ yaw        CONSTANT)
    Q_PROPERTY(Fact* rollRate   READ rollRate   CONSTANT)
    Q_PROPERTY(Fact* pitchRate  READ pitchRate  CONSTANT)
    Q_PROPERTY(Fact* yawRate    READ yawRate    CONSTANT)

    Fact* roll      (void) { return &_rollFact; }
    Fact* pitch     (void) { return &_pitchFact; }
    Fact* yaw       (void) { return &_yawFact; }
    Fact* rollRate  (void) { return &_rollRateFact; }
    Fact* pitchRate (void) { return &_pitchRateFact; }
    Fact* yawRate   (void) { return &_yawRateFact; }

    static const char* _rollFactName;
    static const char* _pitchFactName;
    static const char* _yawFactName;
    static const char* _rollRateFactName;
    static const char* _pitchRateFactName;
    static const char* _yawRateFactName;

private:
    Fact _rollFact;
    Fact _pitchFact;
    Fact _yawFact;
    Fact _rollRateFact;
    Fact _pitchRateFact;
    Fact _yawRateFact;
};

146 147 148 149 150
class VehicleVibrationFactGroup : public FactGroup
{
    Q_OBJECT

public:
151
    VehicleVibrationFactGroup(QObject* parent = nullptr);
152 153 154 155 156 157 158 159

    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)

160 161 162 163 164 165
    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; }
166 167 168 169 170 171 172 173 174 175 176 177 178 179 180 181 182

    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
183 184 185 186 187
class VehicleWindFactGroup : public FactGroup
{
    Q_OBJECT

public:
188
    VehicleWindFactGroup(QObject* parent = nullptr);
Don Gagne's avatar
Don Gagne committed
189 190 191 192 193

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

194 195 196
    Fact* direction     (void) { return &_directionFact; }
    Fact* speed         (void) { return &_speedFact; }
    Fact* verticalSpeed (void) { return &_verticalSpeedFact; }
Don Gagne's avatar
Don Gagne committed
197 198 199 200 201 202 203 204 205 206 207

    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
208 209 210 211 212
class VehicleGPSFactGroup : public FactGroup
{
    Q_OBJECT

public:
213
    VehicleGPSFactGroup(QObject* parent = nullptr);
Don Gagne's avatar
Don Gagne committed
214

215 216
    Q_PROPERTY(Fact* lat                READ lat                CONSTANT)
    Q_PROPERTY(Fact* lon                READ lon                CONSTANT)
Don Gagne's avatar
Don Gagne committed
217 218 219 220 221 222
    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)

223 224
    Fact* lat               (void) { return &_latFact; }
    Fact* lon               (void) { return &_lonFact; }
225 226 227 228 229
    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
230

231 232
    static const char* _latFactName;
    static const char* _lonFactName;
Don Gagne's avatar
Don Gagne committed
233 234 235 236 237 238
    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
239
private:
240 241
    Fact        _latFact;
    Fact        _lonFact;
Don Gagne's avatar
Don Gagne committed
242 243 244 245 246
    Fact        _hdopFact;
    Fact        _vdopFact;
    Fact        _courseOverGroundFact;
    Fact        _countFact;
    Fact        _lockFact;
Don Gagne's avatar
Don Gagne committed
247
};
Don Gagne's avatar
Don Gagne committed
248

Don Gagne's avatar
Don Gagne committed
249 250 251 252 253
class VehicleBatteryFactGroup : public FactGroup
{
    Q_OBJECT

public:
254
    VehicleBatteryFactGroup(QObject* parent = nullptr);
Don Gagne's avatar
Don Gagne committed
255 256 257 258 259 260

    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)
261
    Q_PROPERTY(Fact* cellCount          READ cellCount          CONSTANT)
262
    Q_PROPERTY(Fact* instantPower       READ instantPower       CONSTANT)
263 264
    Q_PROPERTY(Fact* timeRemaining      READ timeRemaining      CONSTANT)
    Q_PROPERTY(Fact* chargeState        READ chargeState        CONSTANT)
265 266 267 268 269 270 271

    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; }
272
    Fact* instantPower              (void) { return &_instantPowerFact; }
273 274
    Fact* timeRemaining             (void) { return &_timeRemainingFact; }
    Fact* chargeState               (void) { return &_chargeStateFact; }
Don Gagne's avatar
Don Gagne committed
275 276 277 278 279 280 281

    static const char* _voltageFactName;
    static const char* _percentRemainingFactName;
    static const char* _mahConsumedFactName;
    static const char* _currentFactName;
    static const char* _temperatureFactName;
    static const char* _cellCountFactName;
282
    static const char* _instantPowerFactName;
283 284
    static const char* _timeRemainingFactName;
    static const char* _chargeStateFactName;
Don Gagne's avatar
Don Gagne committed
285

286 287
    static const char* _settingsGroup;

Don Gagne's avatar
Don Gagne committed
288 289 290 291 292 293
    static const double _voltageUnavailable;
    static const int    _percentRemainingUnavailable;
    static const int    _mahConsumedUnavailable;
    static const int    _currentUnavailable;
    static const double _temperatureUnavailable;
    static const int    _cellCountUnavailable;
294
    static const double _instantPowerUnavailable;
Don Gagne's avatar
Don Gagne committed
295 296

private:
297 298 299 300 301 302
    Fact            _voltageFact;
    Fact            _percentRemainingFact;
    Fact            _mahConsumedFact;
    Fact            _currentFact;
    Fact            _temperatureFact;
    Fact            _cellCountFact;
303
    Fact            _instantPowerFact;
304 305
    Fact            _timeRemainingFact;
    Fact            _chargeStateFact;
Don Gagne's avatar
Don Gagne committed
306 307
};

308 309 310 311 312
class VehicleTemperatureFactGroup : public FactGroup
{
    Q_OBJECT

public:
313
    VehicleTemperatureFactGroup(QObject* parent = nullptr);
314 315 316 317 318 319 320 321 322 323 324 325 326 327 328 329 330 331 332 333 334 335 336

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

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

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

    static const char* _settingsGroup;

    static const double _temperatureUnavailable;

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

dheideman's avatar
dheideman committed
337 338 339 340 341
class VehicleClockFactGroup : public FactGroup
{
    Q_OBJECT

public:
342
    VehicleClockFactGroup(QObject* parent = nullptr);
dheideman's avatar
dheideman committed
343 344 345 346 347 348 349 350 351 352 353 354 355 356 357 358 359 360 361 362

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

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

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

    static const char* _settingsGroup;

private slots:
    void _updateAllValues(void) override;

private:
    Fact            _currentTimeFact;
    Fact            _currentDateFact;
};

363 364 365 366 367 368 369 370 371 372 373 374 375 376 377 378 379 380 381 382 383 384 385 386 387 388 389 390 391 392 393 394 395 396 397 398 399 400 401 402 403 404 405 406 407 408 409 410 411 412 413 414 415 416 417 418 419 420 421 422 423 424 425 426 427 428 429 430 431 432 433 434 435 436 437 438 439 440 441 442 443 444 445 446 447 448 449 450 451 452 453 454 455 456 457 458 459 460 461 462 463 464 465 466 467 468 469 470 471 472 473 474 475 476 477 478 479 480 481
class VehicleEstimatorStatusFactGroup : public FactGroup
{
    Q_OBJECT

public:
    VehicleEstimatorStatusFactGroup(QObject* parent = nullptr);

    Q_PROPERTY(Fact* goodAttitudeEstimate           READ goodAttitudeEstimate           CONSTANT)
    Q_PROPERTY(Fact* goodHorizVelEstimate           READ goodHorizVelEstimate           CONSTANT)
    Q_PROPERTY(Fact* goodVertVelEstimate            READ goodVertVelEstimate            CONSTANT)
    Q_PROPERTY(Fact* goodHorizPosRelEstimate        READ goodHorizPosRelEstimate        CONSTANT)
    Q_PROPERTY(Fact* goodHorizPosAbsEstimate        READ goodHorizPosAbsEstimate        CONSTANT)
    Q_PROPERTY(Fact* goodVertPosAbsEstimate         READ goodVertPosAbsEstimate         CONSTANT)
    Q_PROPERTY(Fact* goodVertPosAGLEstimate         READ goodVertPosAGLEstimate         CONSTANT)
    Q_PROPERTY(Fact* goodConstPosModeEstimate       READ goodConstPosModeEstimate       CONSTANT)
    Q_PROPERTY(Fact* goodPredHorizPosRelEstimate    READ goodPredHorizPosRelEstimate    CONSTANT)
    Q_PROPERTY(Fact* goodPredHorizPosAbsEstimate    READ goodPredHorizPosAbsEstimate    CONSTANT)
    Q_PROPERTY(Fact* gpsGlitch                      READ gpsGlitch                      CONSTANT)
    Q_PROPERTY(Fact* accelError                     READ accelError                     CONSTANT)
    Q_PROPERTY(Fact* velRatio                       READ velRatio                       CONSTANT)
    Q_PROPERTY(Fact* horizPosRatio                  READ horizPosRatio                  CONSTANT)
    Q_PROPERTY(Fact* vertPosRatio                   READ vertPosRatio                   CONSTANT)
    Q_PROPERTY(Fact* magRatio                       READ magRatio                       CONSTANT)
    Q_PROPERTY(Fact* haglRatio                      READ haglRatio                      CONSTANT)
    Q_PROPERTY(Fact* tasRatio                       READ tasRatio                       CONSTANT)
    Q_PROPERTY(Fact* horizPosAccuracy               READ horizPosAccuracy               CONSTANT)
    Q_PROPERTY(Fact* vertPosAccuracy                READ vertPosAccuracy                CONSTANT)

    Fact* goodAttitudeEstimate          (void) { return &_goodAttitudeEstimateFact; }
    Fact* goodHorizVelEstimate          (void) { return &_goodHorizVelEstimateFact; }
    Fact* goodVertVelEstimate           (void) { return &_goodVertVelEstimateFact; }
    Fact* goodHorizPosRelEstimate       (void) { return &_goodHorizPosRelEstimateFact; }
    Fact* goodHorizPosAbsEstimate       (void) { return &_goodHorizPosAbsEstimateFact; }
    Fact* goodVertPosAbsEstimate        (void) { return &_goodVertPosAbsEstimateFact; }
    Fact* goodVertPosAGLEstimate        (void) { return &_goodVertPosAGLEstimateFact; }
    Fact* goodConstPosModeEstimate      (void) { return &_goodConstPosModeEstimateFact; }
    Fact* goodPredHorizPosRelEstimate   (void) { return &_goodPredHorizPosRelEstimateFact; }
    Fact* goodPredHorizPosAbsEstimate   (void) { return &_goodPredHorizPosAbsEstimateFact; }
    Fact* gpsGlitch                     (void) { return &_gpsGlitchFact; }
    Fact* accelError                    (void) { return &_accelErrorFact; }
    Fact* velRatio                      (void) { return &_velRatioFact; }
    Fact* horizPosRatio                 (void) { return &_horizPosRatioFact; }
    Fact* vertPosRatio                  (void) { return &_vertPosRatioFact; }
    Fact* magRatio                      (void) { return &_magRatioFact; }
    Fact* haglRatio                     (void) { return &_haglRatioFact; }
    Fact* tasRatio                      (void) { return &_tasRatioFact; }
    Fact* horizPosAccuracy              (void) { return &_horizPosAccuracyFact; }
    Fact* vertPosAccuracy               (void) { return &_vertPosAccuracyFact; }

    static const char* _goodAttitudeEstimateFactName;
    static const char* _goodHorizVelEstimateFactName;
    static const char* _goodVertVelEstimateFactName;
    static const char* _goodHorizPosRelEstimateFactName;
    static const char* _goodHorizPosAbsEstimateFactName;
    static const char* _goodVertPosAbsEstimateFactName;
    static const char* _goodVertPosAGLEstimateFactName;
    static const char* _goodConstPosModeEstimateFactName;
    static const char* _goodPredHorizPosRelEstimateFactName;
    static const char* _goodPredHorizPosAbsEstimateFactName;
    static const char* _gpsGlitchFactName;
    static const char* _accelErrorFactName;
    static const char* _velRatioFactName;
    static const char* _horizPosRatioFactName;
    static const char* _vertPosRatioFactName;
    static const char* _magRatioFactName;
    static const char* _haglRatioFactName;
    static const char* _tasRatioFactName;
    static const char* _horizPosAccuracyFactName;
    static const char* _vertPosAccuracyFactName;

private:
    Fact _goodAttitudeEstimateFact;
    Fact _goodHorizVelEstimateFact;
    Fact _goodVertVelEstimateFact;
    Fact _goodHorizPosRelEstimateFact;
    Fact _goodHorizPosAbsEstimateFact;
    Fact _goodVertPosAbsEstimateFact;
    Fact _goodVertPosAGLEstimateFact;
    Fact _goodConstPosModeEstimateFact;
    Fact _goodPredHorizPosRelEstimateFact;
    Fact _goodPredHorizPosAbsEstimateFact;
    Fact _gpsGlitchFact;
    Fact _accelErrorFact;
    Fact _velRatioFact;
    Fact _horizPosRatioFact;
    Fact _vertPosRatioFact;
    Fact _magRatioFact;
    Fact _haglRatioFact;
    Fact _tasRatioFact;
    Fact _horizPosAccuracyFact;
    Fact _vertPosAccuracyFact;

#if 0
    typedef enum ESTIMATOR_STATUS_FLAGS
    {
       ESTIMATOR_ATTITUDE=1, /* True if the attitude estimate is good | */
       ESTIMATOR_VELOCITY_HORIZ=2, /* True if the horizontal velocity estimate is good | */
       ESTIMATOR_VELOCITY_VERT=4, /* True if the  vertical velocity estimate is good | */
       ESTIMATOR_POS_HORIZ_REL=8, /* True if the horizontal position (relative) estimate is good | */
       ESTIMATOR_POS_HORIZ_ABS=16, /* True if the horizontal position (absolute) estimate is good | */
       ESTIMATOR_POS_VERT_ABS=32, /* True if the vertical position (absolute) estimate is good | */
       ESTIMATOR_POS_VERT_AGL=64, /* True if the vertical position (above ground) estimate is good | */
       ESTIMATOR_CONST_POS_MODE=128, /* True if the EKF is in a constant position mode and is not using external measurements (eg GPS or optical flow) | */
       ESTIMATOR_PRED_POS_HORIZ_REL=256, /* True if the EKF has sufficient data to enter a mode that will provide a (relative) position estimate | */
       ESTIMATOR_PRED_POS_HORIZ_ABS=512, /* True if the EKF has sufficient data to enter a mode that will provide a (absolute) position estimate | */
       ESTIMATOR_GPS_GLITCH=1024, /* True if the EKF has detected a GPS glitch | */
       ESTIMATOR_ACCEL_ERROR=2048, /* True if the EKF has detected bad accelerometer data | */

        typedef struct __mavlink_estimator_status_t {
         uint64_t time_usec; /*< Timestamp (micros since boot or Unix epoch)*/
         float vel_ratio; /*< Velocity innovation test ratio*/
         float pos_horiz_ratio; /*< Horizontal position innovation test ratio*/
         float pos_vert_ratio; /*< Vertical position innovation test ratio*/
         float mag_ratio; /*< Magnetometer innovation test ratio*/
         float hagl_ratio; /*< Height above terrain innovation test ratio*/
         float tas_ratio; /*< True airspeed innovation test ratio*/
         float pos_horiz_accuracy; /*< Horizontal position 1-STD accuracy relative to the EKF local origin (m)*/
         float pos_vert_accuracy; /*< Vertical position 1-STD accuracy relative to the EKF local origin (m)*/
         uint16_t flags; /*< Integer bitmask indicating which EKF outputs are valid. See definition for ESTIMATOR_STATUS_FLAGS.*/
482 483
        } mavlink_estimator_status_t;
    };
484 485 486 487
#endif
};


Don Gagne's avatar
Don Gagne committed
488
class Vehicle : public FactGroup
489 490
{
    Q_OBJECT
dogmaphobic's avatar
dogmaphobic committed
491

492
public:
493 494
    Vehicle(LinkInterface*          link,
            int                     vehicleId,
495
            int                     defaultComponentId,
496 497 498 499
            MAV_AUTOPILOT           firmwareType,
            MAV_TYPE                vehicleType,
            FirmwarePluginManager*  firmwarePluginManager,
            JoystickManager*        joystickManager);
500

501 502 503 504
    // The following is used to create a disconnected Vehicle for use while offline editing.
    Vehicle(MAV_AUTOPILOT           firmwareType,
            MAV_TYPE                vehicleType,
            FirmwarePluginManager*  firmwarePluginManager,
505
            QObject*                parent = nullptr);
506

507
    ~Vehicle();
dogmaphobic's avatar
dogmaphobic committed
508

509 510 511 512 513
    /// Sensor bits from sensors*Bits properties
    enum MavlinkSysStatus {
        SysStatusSensor3dGyro =                 MAV_SYS_STATUS_SENSOR_3D_GYRO,
        SysStatusSensor3dAccel =                MAV_SYS_STATUS_SENSOR_3D_ACCEL,
        SysStatusSensor3dMag =                  MAV_SYS_STATUS_SENSOR_3D_MAG,
514
        SysStatusSensorAbsolutePressure =       MAV_SYS_STATUS_SENSOR_ABSOLUTE_PRESSURE,
515 516 517 518 519 520 521 522 523 524 525 526 527 528 529 530 531 532 533 534 535 536 537 538 539
        SysStatusSensorDifferentialPressure =   MAV_SYS_STATUS_SENSOR_DIFFERENTIAL_PRESSURE,
        SysStatusSensorGPS =                    MAV_SYS_STATUS_SENSOR_GPS,
        SysStatusSensorOpticalFlow =            MAV_SYS_STATUS_SENSOR_OPTICAL_FLOW,
        SysStatusSensorVisionPosition =         MAV_SYS_STATUS_SENSOR_VISION_POSITION,
        SysStatusSensorLaserPosition =          MAV_SYS_STATUS_SENSOR_LASER_POSITION,
        SysStatusSensorExternalGroundTruth =    MAV_SYS_STATUS_SENSOR_EXTERNAL_GROUND_TRUTH,
        SysStatusSensorAngularRateControl =     MAV_SYS_STATUS_SENSOR_ANGULAR_RATE_CONTROL,
        SysStatusSensorAttitudeStabilization =  MAV_SYS_STATUS_SENSOR_ATTITUDE_STABILIZATION,
        SysStatusSensorYawPosition =            MAV_SYS_STATUS_SENSOR_YAW_POSITION,
        SysStatusSensorZAltitudeControl =       MAV_SYS_STATUS_SENSOR_Z_ALTITUDE_CONTROL,
        SysStatusSensorXYPositionControl =      MAV_SYS_STATUS_SENSOR_XY_POSITION_CONTROL,
        SysStatusSensorMotorOutputs =           MAV_SYS_STATUS_SENSOR_MOTOR_OUTPUTS,
        SysStatusSensorRCReceiver =             MAV_SYS_STATUS_SENSOR_RC_RECEIVER,
        SysStatusSensor3dGyro2 =                MAV_SYS_STATUS_SENSOR_3D_GYRO2,
        SysStatusSensor3dAccel2 =               MAV_SYS_STATUS_SENSOR_3D_ACCEL2,
        SysStatusSensor3dMag2 =                 MAV_SYS_STATUS_SENSOR_3D_MAG2,
        SysStatusSensorGeoFence =               MAV_SYS_STATUS_GEOFENCE,
        SysStatusSensorAHRS =                   MAV_SYS_STATUS_AHRS,
        SysStatusSensorTerrain =                MAV_SYS_STATUS_TERRAIN,
        SysStatusSensorReverseMotor =           MAV_SYS_STATUS_REVERSE_MOTOR,
        SysStatusSensorLogging =                MAV_SYS_STATUS_LOGGING,
        SysStatusSensorBattery =                MAV_SYS_STATUS_SENSOR_BATTERY,
    };
    Q_ENUM(MavlinkSysStatus)

540 541 542 543 544
    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)
545
    Q_PROPERTY(bool                 autoDisarm              READ autoDisarm                                             NOTIFY autoDisarmChanged)
546
    Q_PROPERTY(bool                 flightModeSetAvailable  READ flightModeSetAvailable                                 CONSTANT)
547
    Q_PROPERTY(QStringList          flightModes             READ flightModes                                            NOTIFY flightModesChanged)
548 549 550
    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)
551
    Q_PROPERTY(QmlObjectListModel*  cameraTriggerPoints     READ cameraTriggerPoints                                    CONSTANT)
552 553 554 555 556 557 558 559 560 561 562 563 564 565 566 567 568
    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)
569 570
    Q_PROPERTY(bool                 px4Firmware             READ px4Firmware                                            NOTIFY firmwareTypeChanged)
    Q_PROPERTY(bool                 apmFirmware             READ apmFirmware                                            NOTIFY firmwareTypeChanged)
571 572 573 574 575 576 577
    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)
578 579 580 581 582
    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)
583
    Q_PROPERTY(bool        supportsThrottleModeCenterZero   READ supportsThrottleModeCenterZero                         CONSTANT)
584
    Q_PROPERTY(bool                supportsNegativeThrust   READ supportsNegativeThrust                                 CONSTANT)
585
    Q_PROPERTY(bool                 supportsJSButton        READ supportsJSButton                                       CONSTANT)
586
    Q_PROPERTY(bool                 supportsRadio           READ supportsRadio                                          CONSTANT)
587
    Q_PROPERTY(bool               supportsMotorInterference READ supportsMotorInterference                              CONSTANT)
588 589
    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
590 591 592
    Q_PROPERTY(int                  motorCount              READ motorCount                                             CONSTANT)
    Q_PROPERTY(bool                 coaxialMotors           READ coaxialMotors                                          CONSTANT)
    Q_PROPERTY(bool                 xConfigMotors           READ xConfigMotors                                          CONSTANT)
593
    Q_PROPERTY(bool                 isOfflineEditingVehicle READ isOfflineEditingVehicle                                CONSTANT)
594 595
    Q_PROPERTY(QString              brandImageIndoor        READ brandImageIndoor                                       NOTIFY firmwareTypeChanged)
    Q_PROPERTY(QString              brandImageOutdoor       READ brandImageOutdoor                                      NOTIFY firmwareTypeChanged)
596
    Q_PROPERTY(QStringList          unhealthySensors        READ unhealthySensors                                       NOTIFY unhealthySensorsChanged)
597 598 599
    Q_PROPERTY(int                  sensorsPresentBits      READ sensorsPresentBits                                     NOTIFY sensorsPresentBitsChanged)
    Q_PROPERTY(int                  sensorsEnabledBits      READ sensorsEnabledBits                                     NOTIFY sensorsEnabledBitsChanged)
    Q_PROPERTY(int                  sensorsHealthBits       READ sensorsHealthBits                                      NOTIFY sensorsHealthBitsChanged)
600
    Q_PROPERTY(int                  sensorsUnhealthyBits    READ sensorsUnhealthyBits                                   NOTIFY sensorsUnhealthyBitsChanged) ///< Combination of enabled and health
601
    Q_PROPERTY(QString              missionFlightMode       READ missionFlightMode                                      CONSTANT)
602
    Q_PROPERTY(QString              pauseFlightMode         READ pauseFlightMode                                        CONSTANT)
603
    Q_PROPERTY(QString              rtlFlightMode           READ rtlFlightMode                                          CONSTANT)
DonLakeFlyer's avatar
DonLakeFlyer committed
604 605
    Q_PROPERTY(QString              smartRTLFlightMode      READ smartRTLFlightMode                                     CONSTANT)
    Q_PROPERTY(bool                 supportsSmartRTL        READ supportsSmartRTL                                       CONSTANT)
606
    Q_PROPERTY(QString              landFlightMode          READ landFlightMode                                         CONSTANT)
607
    Q_PROPERTY(QString              takeControlFlightMode   READ takeControlFlightMode                                  CONSTANT)
608 609
    Q_PROPERTY(QString              firmwareTypeString      READ firmwareTypeString                                     NOTIFY firmwareTypeChanged)
    Q_PROPERTY(QString              vehicleTypeString       READ vehicleTypeString                                      NOTIFY vehicleTypeChanged)
610 611 612
    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
613 614 615 616 617
    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)
618 619
    Q_PROPERTY(int                  telemetryLNoise         READ telemetryLNoise                                        NOTIFY telemetryLNoiseChanged)
    Q_PROPERTY(int                  telemetryRNoise         READ telemetryRNoise                                        NOTIFY telemetryRNoiseChanged)
620
    Q_PROPERTY(QVariantList         toolBarIndicators       READ toolBarIndicators                                      NOTIFY toolBarIndicatorsChanged)
621
    Q_PROPERTY(QmlObjectListModel*  adsbVehicles            READ adsbVehicles                                           CONSTANT)
Don Gagne's avatar
Don Gagne committed
622
    Q_PROPERTY(bool              initialPlanRequestComplete READ initialPlanRequestComplete                             NOTIFY initialPlanRequestCompleteChanged)
Gus Grubba's avatar
Gus Grubba committed
623
    Q_PROPERTY(QVariantList         staticCameraList        READ staticCameraList                                       CONSTANT)
624
    Q_PROPERTY(QGCCameraManager*    dynamicCameras          READ dynamicCameras                                         NOTIFY dynamicCamerasChanged)
625
    Q_PROPERTY(QString              hobbsMeter              READ hobbsMeter                                             NOTIFY hobbsMeterChanged)
626
    Q_PROPERTY(bool                 vtolInFwdFlight         READ vtolInFwdFlight        WRITE setVtolInFwdFlight        NOTIFY vtolInFwdFlightChanged)
627
    Q_PROPERTY(bool                 highLatencyLink         READ highLatencyLink                                        NOTIFY highLatencyLinkChanged)
628
    Q_PROPERTY(bool                 supportsTerrainFrame    READ supportsTerrainFrame                                   NOTIFY firmwareTypeChanged)
629
    Q_PROPERTY(QString              priorityLinkName        READ priorityLinkName       WRITE setPriorityLinkByName     NOTIFY priorityLinkNameChanged)
630
    Q_PROPERTY(QVariantList         links                   READ links                                                  NOTIFY linksChanged)
631
    Q_PROPERTY(LinkInterface*       priorityLink            READ priorityLink                                           NOTIFY priorityLinkNameChanged)
632 633 634 635
    Q_PROPERTY(quint64              mavlinkSentCount        READ mavlinkSentCount                                       NOTIFY mavlinkStatusChanged)
    Q_PROPERTY(quint64              mavlinkReceivedCount    READ mavlinkReceivedCount                                   NOTIFY mavlinkStatusChanged)
    Q_PROPERTY(quint64              mavlinkLossCount        READ mavlinkLossCount                                       NOTIFY mavlinkStatusChanged)
    Q_PROPERTY(float                mavlinkLossPercent      READ mavlinkLossPercent                                     NOTIFY mavlinkStatusChanged)
Gus Grubba's avatar
Gus Grubba committed
636 637 638 639
    Q_PROPERTY(qreal                gimbalRoll              READ gimbalRoll                                             NOTIFY gimbalRollChanged)
    Q_PROPERTY(qreal                gimbalPitch             READ gimbalPitch                                            NOTIFY gimbalPitchChanged)
    Q_PROPERTY(qreal                gimbalYaw               READ gimbalYaw                                              NOTIFY gimbalYawChanged)
    Q_PROPERTY(bool                 gimbalData              READ gimbalData                                             NOTIFY gimbalDataChanged)
640

641 642 643 644
    // The following properties relate to Orbit status
    Q_PROPERTY(bool             orbitActive     READ orbitActive        NOTIFY orbitActiveChanged)
    Q_PROPERTY(QGCMapCircle*    orbitMapCircle  READ orbitMapCircle     CONSTANT)

645
    // Vehicle state used for guided control
Don Gagne's avatar
Don Gagne committed
646 647 648 649 650 651 652 653
    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
    Q_PROPERTY(QString  gotoFlightMode          READ gotoFlightMode                                 CONSTANT)                   ///< Flight mode vehicle is in while performing goto
654

655 656
    Q_PROPERTY(ParameterManager* parameterManager READ parameterManager CONSTANT)

Don Gagne's avatar
Don Gagne committed
657 658 659 660 661
    // 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)
DonLakeFlyer's avatar
DonLakeFlyer committed
662 663 664
    Q_PROPERTY(Fact* rollRate           READ rollRate           CONSTANT)
    Q_PROPERTY(Fact* pitchRate          READ pitchRate          CONSTANT)
    Q_PROPERTY(Fact* yawRate            READ yawRate            CONSTANT)
Don Gagne's avatar
Don Gagne committed
665 666 667 668 669
    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)
670
    Q_PROPERTY(Fact* flightDistance     READ flightDistance     CONSTANT)
671
    Q_PROPERTY(Fact* distanceToHome     READ distanceToHome     CONSTANT)
672
    Q_PROPERTY(Fact* headingToNextWP    READ headingToNextWP    CONSTANT)
673
    Q_PROPERTY(Fact* headingToHome      READ headingToHome      CONSTANT)
674
    Q_PROPERTY(Fact* distanceToGCS      READ distanceToGCS      CONSTANT)
675
    Q_PROPERTY(Fact* hobbs              READ hobbs              CONSTANT)
676
    Q_PROPERTY(Fact* throttlePct        READ throttlePct        CONSTANT)
Don Gagne's avatar
Don Gagne committed
677

678 679 680 681 682 683 684 685 686
    Q_PROPERTY(FactGroup* gps               READ gpsFactGroup               CONSTANT)
    Q_PROPERTY(FactGroup* battery           READ battery1FactGroup          CONSTANT)
    Q_PROPERTY(FactGroup* battery2          READ battery2FactGroup          CONSTANT)
    Q_PROPERTY(FactGroup* wind              READ windFactGroup              CONSTANT)
    Q_PROPERTY(FactGroup* vibration         READ vibrationFactGroup         CONSTANT)
    Q_PROPERTY(FactGroup* temperature       READ temperatureFactGroup       CONSTANT)
    Q_PROPERTY(FactGroup* clock             READ clockFactGroup             CONSTANT)
    Q_PROPERTY(FactGroup* setpoint          READ setpointFactGroup          CONSTANT)
    Q_PROPERTY(FactGroup* estimatorStatus   READ estimatorStatusFactGroup   CONSTANT)
Don Gagne's avatar
Don Gagne committed
687

688 689 690 691 692 693 694 695 696
    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
697 698
    Q_PROPERTY(quint64  vehicleUID                  READ vehicleUID                 NOTIFY vehicleUIDChanged)
    Q_PROPERTY(QString  vehicleUIDStr               READ vehicleUIDStr              NOTIFY vehicleUIDChanged)
699

700 701
    /// Resets link status counters
    Q_INVOKABLE void resetCounters  ();
702

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

Gus Grubba's avatar
Gus Grubba committed
706
    Q_INVOKABLE void virtualTabletJoystickValue(double roll, double pitch, double yaw, double thrust);
Don Gagne's avatar
Don Gagne committed
707
    Q_INVOKABLE void disconnectInactiveVehicle(void);
Don Gagne's avatar
Don Gagne committed
708

Don Gagne's avatar
Don Gagne committed
709
    /// Command vehicle to return to launch
DonLakeFlyer's avatar
DonLakeFlyer committed
710
    Q_INVOKABLE void guidedModeRTL(bool smartRTL);
Don Gagne's avatar
Don Gagne committed
711 712 713 714 715

    /// Command vehicle to land at current location
    Q_INVOKABLE void guidedModeLand(void);

    /// Command vehicle to takeoff from current location
716
    Q_INVOKABLE void guidedModeTakeoff(double altitudeRelative);
Don Gagne's avatar
Don Gagne committed
717

718 719 720
    /// @return The minimum takeoff altitude (relative) for guided takeoff.
    Q_INVOKABLE double minimumTakeoffAltitude(void);

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

724 725 726
    /// 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
727

728
    /// Command vehicle to orbit given center point
DonLakeFlyer's avatar
DonLakeFlyer committed
729
    ///     @param centerCoord Orit around this point
730
    ///     @param radius Distance from vehicle to centerCoord
DonLakeFlyer's avatar
DonLakeFlyer committed
731 732
    ///     @param amslAltitude Desired vehicle altitude
    Q_INVOKABLE void guidedModeOrbit(const QGeoCoordinate& centerCoord, double radius, double amslAltitude);
733

Don Gagne's avatar
Don Gagne committed
734 735 736 737 738 739 740
    /// 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);

741
    /// Command vehicle to abort landing
742
    Q_INVOKABLE void abortLanding(double climbOutAltitude);
743

744 745
    Q_INVOKABLE void startMission(void);

746 747 748
    /// Alter the current mission item on the vehicle
    Q_INVOKABLE void setCurrentMissionSequence(int seq);

749 750 751
    /// Reboot vehicle
    Q_INVOKABLE void rebootVehicle();

dogmaphobic's avatar
dogmaphobic committed
752 753 754
    /// Clear Messages
    Q_INVOKABLE void clearMessages();

Don Gagne's avatar
Don Gagne committed
755
    Q_INVOKABLE void triggerCamera(void);
Don Gagne's avatar
Don Gagne committed
756
    Q_INVOKABLE void sendPlan(QString planFile);
Don Gagne's avatar
Don Gagne committed
757

758 759 760 761 762
    /// Used to check if running current version is equal or higher than the one being compared.
    //  returns 1 if current > compare, 0 if current == compare, -1 if current < compare
    Q_INVOKABLE int versionCompare(QString& compare);
    Q_INVOKABLE int versionCompare(int major, int minor, int patch);

Don Gagne's avatar
Don Gagne committed
763 764 765
    /// Test motor
    ///     @param motor Motor number, 1-based
    ///     @param percent 0-no power, 100-full power
766
    Q_INVOKABLE void motorTest(int motor, int percent);
Don Gagne's avatar
Don Gagne committed
767

Don Gagne's avatar
Don Gagne committed
768 769
    Q_INVOKABLE void setPIDTuningTelemetryMode(bool pidTuning);

Gus Grubba's avatar
Gus Grubba committed
770 771 772 773
    Q_INVOKABLE void gimbalControlValue (double pitch, double yaw);
    Q_INVOKABLE void gimbalPitchStep    (int direction);
    Q_INVOKABLE void gimbalYawStep      (int direction);
    Q_INVOKABLE void centerGimbal       ();
774

775 776 777 778
#if !defined(NO_ARDUPILOT_DIALECT)
    Q_INVOKABLE void flashBootloader(void);
#endif

Don Gagne's avatar
Don Gagne committed
779 780 781 782 783
    bool    guidedModeSupported     (void) const;
    bool    pauseVehicleSupported   (void) const;
    bool    orbitModeSupported      (void) const;
    bool    takeoffVehicleSupported (void) const;
    QString gotoFlightMode          (void) const;
Don Gagne's avatar
Don Gagne committed
784

785
    // Property accessors
Don Gagne's avatar
Don Gagne committed
786

787
    QGeoCoordinate coordinate(void) { return _coordinate; }
dogmaphobic's avatar
dogmaphobic committed
788

789
    typedef enum {
790
        JoystickModeRC,         ///< Joystick emulates an RC Transmitter
791 792 793 794 795 796
        JoystickModeAttitude,
        JoystickModePosition,
        JoystickModeForce,
        JoystickModeVelocity,
        JoystickModeMax
    } JoystickMode_t;
dogmaphobic's avatar
dogmaphobic committed
797

798 799
    int joystickMode(void);
    void setJoystickMode(int mode);
dogmaphobic's avatar
dogmaphobic committed
800

801 802
    /// List of joystick mode names
    QStringList joystickModes(void);
dogmaphobic's avatar
dogmaphobic committed
803

804 805
    bool joystickEnabled(void);
    void setJoystickEnabled(bool enabled);
dogmaphobic's avatar
dogmaphobic committed
806

807 808 809
    // Is vehicle active with respect to current active vehicle in QGC
    bool active(void);
    void setActive(bool active);
dogmaphobic's avatar
dogmaphobic committed
810

811 812
    // Property accesors
    int id(void) { return _id; }
813 814
    MAV_AUTOPILOT firmwareType(void) const { return _firmwareType; }
    MAV_TYPE vehicleType(void) const { return _vehicleType; }
815
    Q_INVOKABLE QString vehicleTypeName(void) const;
dogmaphobic's avatar
dogmaphobic committed
816

Patrick José Pereira's avatar
Patrick José Pereira committed
817
    /// Returns the highest quality link available to the Vehicle. If you need to hold a reference to this link use
818 819
    /// LinkManager::sharedLinkInterfaceForGet to get QSharedPointer for link.
    LinkInterface* priorityLink(void) { return _priorityLink.data(); }
820 821 822 823 824

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

825 826 827
    /// 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
828

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

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

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

838 839 840
    MissionManager*     missionManager(void)    { return _missionManager; }
    GeoFenceManager*    geoFenceManager(void)   { return _geoFenceManager; }
    RallyPointManager*  rallyPointManager(void) { return _rallyPointManager; }
dogmaphobic's avatar
dogmaphobic committed
841

842
    QGeoCoordinate homePosition(void);
dogmaphobic's avatar
dogmaphobic committed
843

Gus Grubba's avatar
Gus Grubba committed
844 845
    bool armed      () { return _armed; }
    void setArmed   (bool armed);
Don Gagne's avatar
Don Gagne committed
846 847 848

    bool flightModeSetAvailable(void);
    QStringList flightModes(void);
Don Gagne's avatar
Don Gagne committed
849
    QString flightMode(void) const;
Don Gagne's avatar
Don Gagne committed
850 851
    void setFlightMode(const QString& flightMode);

852
    QString priorityLinkName(void) const;
853
    QVariantList links(void) const;
854 855
    void setPriorityLinkByName(const QString& priorityLinkName);

Don Gagne's avatar
Don Gagne committed
856 857
    bool hilMode(void);
    void setHilMode(bool hilMode);
dogmaphobic's avatar
dogmaphobic committed
858

859 860
    bool fixedWing(void) const;
    bool multiRotor(void) const;
Don Gagne's avatar
Don Gagne committed
861
    bool vtol(void) const;
Don Gagne's avatar
Don Gagne committed
862
    bool rover(void) const;
863
    bool sub(void) const;
864

865
    bool supportsThrottleModeCenterZero (void) const;
866
    bool supportsNegativeThrust         (void);
867 868 869 870
    bool supportsRadio                  (void) const;
    bool supportsJSButton               (void) const;
    bool supportsMotorInterference      (void) const;
    bool supportsTerrainFrame           (void) const;
871

Don Gagne's avatar
Don Gagne committed
872 873
    void setGuidedMode(bool guidedMode);

Don Gagne's avatar
Don Gagne committed
874 875 876
    QString prearmError(void) const { return _prearmError; }
    void setPrearmError(const QString& prearmError);

877
    QmlObjectListModel* trajectoryPoints(void) { return &_mapTrajectoryList; }
878
    QmlObjectListModel* cameraTriggerPoints(void) { return &_cameraTriggerPoints; }
879
    QmlObjectListModel* adsbVehicles(void) { return &_adsbVehicles; }
dogmaphobic's avatar
dogmaphobic committed
880 881 882

    int  flowImageIndex() { return _flowImageIndex; }

883 884 885 886
    //-- Mavlink Logging
    void startMavlinkLog();
    void stopMavlinkLog();

887 888 889
    /// 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
890 891
    ///     @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
892

893 894 895 896 897 898
    typedef enum {
        MessageNone,
        MessageNormal,
        MessageWarning,
        MessageError
    } MessageType_t;
dogmaphobic's avatar
dogmaphobic committed
899

900 901 902 903 904 905 906 907 908
    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; }
909 910 911
    float           latitude                () { return static_cast<float>(_coordinate.latitude()); }
    float           longitude               () { return static_cast<float>(_coordinate.longitude()); }
    bool            mavPresent              () { return _mav != nullptr; }
912 913 914 915 916 917 918 919 920 921
    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; }
922
    bool            landing                 () const { return _landing; }
923
    bool            guidedMode              () const;
924
    bool            vtolInFwdFlight         () const { return _vtolInFwdFlight; }
925 926 927
    uint8_t         baseMode                () const { return _base_mode; }
    uint32_t        customMode              () const { return _custom_mode; }
    bool            isOfflineEditingVehicle () const { return _offlineEditingVehicle; }
928 929
    QString         brandImageIndoor        () const;
    QString         brandImageOutdoor       () const;
930
    QStringList     unhealthySensors        () const;
931 932 933 934
    int             sensorsPresentBits      () const { return static_cast<int>(_onboardControlSensorsPresent); }
    int             sensorsEnabledBits      () const { return static_cast<int>(_onboardControlSensorsEnabled); }
    int             sensorsHealthBits       () const { return static_cast<int>(_onboardControlSensorsHealth); }
    int             sensorsUnhealthyBits    () const { return static_cast<int>(_onboardControlSensorsUnhealthy); }
935
    QString         missionFlightMode       () const;
936
    QString         pauseFlightMode         () const;
937
    QString         rtlFlightMode           () const;
DonLakeFlyer's avatar
DonLakeFlyer committed
938 939
    QString         smartRTLFlightMode      () const;
    bool            supportsSmartRTL        () const;
940
    QString         landFlightMode          () const;
941
    QString         takeControlFlightMode   () const;
DonLakeFlyer's avatar
DonLakeFlyer committed
942 943
    double          defaultCruiseSpeed      () const { return _defaultCruiseSpeed; }
    double          defaultHoverSpeed       () const { return _defaultHoverSpeed; }
944
    QString         firmwareTypeString      () const;
Gus Grubba's avatar
Gus Grubba committed
945 946 947 948 949 950
    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; }
951 952
    int             telemetryLNoise         () { return _telemetryLNoise; }
    int             telemetryRNoise         () { return _telemetryRNoise; }
953
    bool            autoDisarm              ();
954
    bool            highLatencyLink         () const { return _highLatencyLink; }
955 956 957
    bool            orbitActive             () const { return _orbitActive; }
    QGCMapCircle*   orbitMapCircle          () { return &_orbitMapCircle; }

958 959 960
    /// Get the maximum MAVLink protocol version supported
    /// @return the maximum version
    unsigned        maxProtoVersion         () const { return _maxProtoVersion; }
961

Don Gagne's avatar
Don Gagne committed
962 963
    Fact* roll              (void) { return &_rollFact; }
    Fact* pitch             (void) { return &_pitchFact; }
DonLakeFlyer's avatar
DonLakeFlyer committed
964 965 966 967
    Fact* heading           (void) { return &_headingFact; }
    Fact* rollRate          (void) { return &_rollRateFact; }
    Fact* pitchRate         (void) { return &_pitchRateFact; }
    Fact* yawRate           (void) { return &_yawRateFact; }
Don Gagne's avatar
Don Gagne committed
968 969 970 971 972
    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; }
973
    Fact* flightDistance    (void) { return &_flightDistanceFact; }
974
    Fact* distanceToHome    (void) { return &_distanceToHomeFact; }
975
    Fact* headingToNextWP   (void) { return &_headingToNextWPFact; }
976
    Fact* headingToHome     (void) { return &_headingToHomeFact; }
977
    Fact* distanceToGCS     (void) { return &_distanceToGCSFact; }
978
    Fact* hobbs             (void) { return &_hobbsFact; }
979
    Fact* throttlePct       (void) { return &_throttlePctFact; }
Don Gagne's avatar
Don Gagne committed
980

981
    FactGroup* gpsFactGroup             (void) { return &_gpsFactGroup; }
DonLakeFlyer's avatar
DonLakeFlyer committed
982 983
    FactGroup* battery1FactGroup        (void) { return &_battery1FactGroup; }
    FactGroup* battery2FactGroup        (void) { return &_battery2FactGroup; }
984 985 986 987 988 989
    FactGroup* windFactGroup            (void) { return &_windFactGroup; }
    FactGroup* vibrationFactGroup       (void) { return &_vibrationFactGroup; }
    FactGroup* temperatureFactGroup     (void) { return &_temperatureFactGroup; }
    FactGroup* clockFactGroup           (void) { return &_clockFactGroup; }
    FactGroup* setpointFactGroup        (void) { return &_setpointFactGroup; }
    FactGroup* distanceSensorFactGroup  (void) { return &_distanceSensorFactGroup; }
990
    FactGroup* estimatorStatusFactGroup (void) { return &_estimatorStatusFactGroup; }
Don Gagne's avatar
Don Gagne committed
991

992
    void setConnectionLostEnabled(bool connectionLostEnabled);
993

994 995
    ParameterManager* parameterManager(void) { return _parameterManager; }
    ParameterManager* parameterManager(void) const { return _parameterManager; }
dogmaphobic's avatar
dogmaphobic committed
996

Don Gagne's avatar
Don Gagne committed
997 998
    static const int cMaxRcChannels = 18;

Don Gagne's avatar
Don Gagne committed
999
    bool containsLink(LinkInterface* link) { return _links.contains(link); }
1000 1001 1002 1003 1004 1005

    /// 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
1006
    /// Signals: mavCommandResult on success or failure
1007
    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);
1008
    void sendMavCommandInt(int component, MAV_CMD command, MAV_FRAME frame, bool showError, float param1, float param2, float param3, float param4, double param5, double param6, float param7);
Don Gagne's avatar
Don Gagne committed
1009

1010
    /// Same as sendMavCommand but available from Qml.
1011 1012 1013 1014 1015 1016 1017 1018 1019 1020 1021 1022 1023
    Q_INVOKABLE void sendCommand(int component, int command, bool showError, double param1 = 0.0, double param2 = 0.0, double param3 = 0.0, double param4 = 0.0, double param5 = 0.0, double param6 = 0.0, double param7 = 0.0)
    {
        sendMavCommand(
            component, static_cast<MAV_CMD>(command),
            showError,
            static_cast<float>(param1),
            static_cast<float>(param2),
            static_cast<float>(param3),
            static_cast<float>(param4),
            static_cast<float>(param5),
            static_cast<float>(param6),
            static_cast<float>(param7));
    }
1024

Don Gagne's avatar
Don Gagne committed
1025 1026 1027
    int firmwareMajorVersion(void) const { return _firmwareMajorVersion; }
    int firmwareMinorVersion(void) const { return _firmwareMinorVersion; }
    int firmwarePatchVersion(void) const { return _firmwarePatchVersion; }
1028
    int firmwareVersionType(void) const { return _firmwareVersionType; }
1029 1030 1031
    int firmwareCustomMajorVersion(void) const { return _firmwareCustomMajorVersion; }
    int firmwareCustomMinorVersion(void) const { return _firmwareCustomMinorVersion; }
    int firmwareCustomPatchVersion(void) const { return _firmwareCustomPatchVersion; }
1032 1033
    QString firmwareVersionTypeString(void) const;
    void setFirmwareVersion(int majorVersion, int minorVersion, int patchVersion, FIRMWARE_VERSION_TYPE versionType = FIRMWARE_VERSION_TYPE_OFFICIAL);
1034
    void setFirmwareCustomVersion(int majorVersion, int minorVersion, int patchVersion);
1035
    static const int versionNotSetValue = -1;
Don Gagne's avatar
Don Gagne committed
1036

1037
    QString gitHash(void) const { return _gitHash; }
Gus Grubba's avatar
Gus Grubba committed
1038 1039
    quint64 vehicleUID(void) const { return _uid; }
    QString vehicleUIDStr();
1040

1041 1042 1043
    bool soloFirmware(void) const { return _soloFirmware; }
    void setSoloFirmware(bool soloFirmware);

1044 1045 1046 1047
    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
1048

Don Gagne's avatar
Don Gagne committed
1049 1050 1051 1052 1053 1054 1055 1056 1057
    /// @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);

1058 1059 1060 1061 1062 1063 1064
    /// @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);

1065 1066 1067 1068
    QString vehicleImageOpaque  () const;
    QString vehicleImageOutline () const;
    QString vehicleImageCompass () const;

1069
    const QVariantList&         toolBarIndicators   ();
Gus Grubba's avatar
Gus Grubba committed
1070
    const QVariantList&         staticCameraList    (void) const;
1071

1072 1073
    bool capabilitiesKnown      (void) const { return _vehicleCapabilitiesKnown; }
    uint64_t capabilityBits     (void) const { return _capabilityBits; }    // Change signalled by capabilityBitsChanged
1074

1075
    QGCCameraManager*           dynamicCameras      () { return _cameras; }
1076
    QString                     hobbsMeter          ();
1077

1078 1079 1080
    /// @true: When flying a mission the vehicle is always facing towards the next waypoint
    bool vehicleYawsToNextWaypointInMission(void) const;

DonLakeFlyer's avatar
DonLakeFlyer committed
1081 1082 1083 1084
    /// 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
1085
    void forceInitialPlanRequestComplete(void);
1086

1087 1088
    void _setFlying(bool flying);
    void _setLanding(bool landing);
DonLakeFlyer's avatar
DonLakeFlyer committed
1089
    void _setHomePosition(QGeoCoordinate& homeCoord);
1090
    void _setMaxProtoVersion (unsigned version);
DonLakeFlyer's avatar
DonLakeFlyer committed
1091

1092 1093 1094
    /// Vehicle is about to be deleted
    void prepareDelete();

1095 1096 1097 1098 1099
    quint64     mavlinkSentCount        () { return _mavlinkSentCount; }        /// Calculated total number of messages sent to us
    quint64     mavlinkReceivedCount    () { return _mavlinkReceivedCount; }    /// Total number of sucessful messages received
    quint64     mavlinkLossCount        () { return _mavlinkLossCount; }        /// Total number of lost messages
    float       mavlinkLossPercent      () { return _mavlinkLossPercent; }      /// Running loss rate

Gus Grubba's avatar
Gus Grubba committed
1100 1101 1102 1103 1104
    qreal       gimbalRoll              () { return static_cast<qreal>(_curGimbalRoll);}
    qreal       gimbalPitch             () { return static_cast<qreal>(_curGimbalPitch); }
    qreal       gimbalYaw               () { return static_cast<qreal>(_curGinmbalYaw); }
    bool        gimbalData              () { return _haveGimbalData; }

Gus Grubba's avatar
Gus Grubba committed
1105 1106 1107
public slots:
    void setVtolInFwdFlight             (bool vtolInFwdFlight);

1108
signals:
Don Gagne's avatar
Don Gagne committed
1109
    void allLinksInactive(Vehicle* vehicle);
1110
    void coordinateChanged(QGeoCoordinate coordinate);
1111
    void joystickModeChanged(int mode);
1112 1113
    void joystickEnabledChanged(bool enabled);
    void activeChanged(bool active);
Don Gagne's avatar
Don Gagne committed
1114
    void mavlinkMessageReceived(const mavlink_message_t& message);
1115
    void homePositionChanged(const QGeoCoordinate& homePosition);
Don Gagne's avatar
Don Gagne committed
1116 1117 1118
    void armedChanged(bool armed);
    void flightModeChanged(const QString& flightMode);
    void hilModeChanged(bool hilMode);
1119 1120
    /** @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);
1121 1122
    void connectionLostChanged(bool connectionLost);
    void connectionLostEnabledChanged(bool connectionLostEnabled);
Don Gagne's avatar
Don Gagne committed
1123
    void autoDisconnectChanged(bool autoDisconnectChanged);
Don Gagne's avatar
Don Gagne committed
1124
    void flyingChanged(bool flying);
1125
    void landingChanged(bool landing);
Don Gagne's avatar
Don Gagne committed
1126
    void guidedModeChanged(bool guidedMode);
1127
    void vtolInFwdFlightChanged(bool vtolInFwdFlight);
Don Gagne's avatar
Don Gagne committed
1128
    void prearmErrorChanged(const QString& prearmError);
1129
    void soloFirmwareChanged(bool soloFirmware);
1130
    void unhealthySensorsChanged(void);
DonLakeFlyer's avatar
DonLakeFlyer committed
1131 1132
    void defaultCruiseSpeedChanged(double cruiseSpeed);
    void defaultHoverSpeedChanged(double hoverSpeed);
1133 1134
    void firmwareTypeChanged(void);
    void vehicleTypeChanged(void);
1135
    void dynamicCamerasChanged();
1136
    void hobbsMeterChanged();
1137
    void capabilitiesKnownChanged(bool capabilitiesKnown);
Don Gagne's avatar
Don Gagne committed
1138
    void initialPlanRequestCompleteChanged(bool initialPlanRequestComplete);
1139
    void capabilityBitsChanged(uint64_t capabilityBits);
1140
    void toolBarIndicatorsChanged(void);
1141
    void highLatencyLinkChanged(bool highLatencyLink);
1142
    void priorityLinkNameChanged(const QString& priorityLinkName);
1143 1144
    void linksChanged(void);
    void linksPropertiesChanged(void);
1145
    void textMessageReceived(int uasid, int componentid, int severity, QString text);
dogmaphobic's avatar
dogmaphobic committed
1146

1147 1148 1149 1150
    void messagesReceivedChanged    ();
    void messagesSentChanged        ();
    void messagesLostChanged        ();

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

Gus Grubba's avatar
Gus Grubba committed
1154 1155 1156 1157 1158 1159 1160 1161 1162 1163 1164 1165 1166 1167 1168
    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);
1169 1170
    void telemetryLNoiseChanged     (int value);
    void telemetryRNoiseChanged     (int value);
1171
    void autoDisarmChanged          (void);
1172
    void flightModesChanged         (void);
1173 1174 1175
    void sensorsPresentBitsChanged  (int sensorsPresentBits);
    void sensorsEnabledBitsChanged  (int sensorsEnabledBits);
    void sensorsHealthBitsChanged   (int sensorsHealthBits);
1176
    void sensorsUnhealthyBitsChanged(int sensorsUnhealthyBits);
1177
    void orbitActiveChanged         (bool orbitActive);
dogmaphobic's avatar
dogmaphobic committed
1178

1179 1180
    void firmwareVersionChanged(void);
    void firmwareCustomVersionChanged(void);
1181
    void gitHashChanged(QString hash);
Gus Grubba's avatar
Gus Grubba committed
1182
    void vehicleUIDChanged();
1183

Don Gagne's avatar
Don Gagne committed
1184 1185 1186 1187 1188 1189 1190 1191
    /// 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);

1192 1193 1194 1195 1196
    void mavlinkRawImu(mavlink_message_t message);
    void mavlinkScaledImu1(mavlink_message_t message);
    void mavlinkScaledImu2(mavlink_message_t message);
    void mavlinkScaledImu3(mavlink_message_t message);

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

1200 1201 1202 1203 1204 1205
    /// 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
1206
    void mavCommandResult(int vehicleId, int component, int command, int result, bool noReponseFromVehicle);
1207

1208
    // MAVlink Serial Data
1209 1210
    void mavlinkSerialControl(uint8_t device, uint8_t flags, uint16_t timeout, uint32_t baudrate, QByteArray data);

1211
    // MAVLink protocol version
Gus Grubba's avatar
Gus Grubba committed
1212 1213 1214 1215 1216 1217 1218
    void requestProtocolVersion     (unsigned version);
    void mavlinkStatusChanged       ();

    void gimbalRollChanged          ();
    void gimbalPitchChanged         ();
    void gimbalYawChanged           ();
    void gimbalDataChanged          ();
1219

1220 1221
private slots:
    void _mavlinkMessageReceived(LinkInterface* link, mavlink_message_t message);
Don Gagne's avatar
Don Gagne committed
1222
    void _linkInactiveOrDeleted(LinkInterface* link);
1223
    void _sendMessageOnLink(LinkInterface* link, mavlink_message_t message);
1224
    void _sendMessageMultipleNext(void);
1225
    void _addNewMapTrajectoryPoint(void);
1226
    void _parametersReady(bool parametersReady);
Don Gagne's avatar
Don Gagne committed
1227
    void _remoteControlRSSIChanged(uint8_t rssi);
Don Gagne's avatar
Don Gagne committed
1228
    void _handleFlightModeChanged(const QString& flightMode);
1229
    void _announceArmedChanged(bool armed);
1230 1231 1232 1233
    void _offlineFirmwareTypeSettingChanged(QVariant value);
    void _offlineVehicleTypeSettingChanged(QVariant value);
    void _offlineCruiseSpeedSettingChanged(QVariant value);
    void _offlineHoverSpeedSettingChanged(QVariant value);
1234
    void _updateHighLatencyLink(bool sendCommand = true);
1235

1236
    void _handleTextMessage                 (int newCount);
dogmaphobic's avatar
dogmaphobic committed
1237
    void _handletextMessageReceived         (UASMessage* message);
dogmaphobic's avatar
dogmaphobic committed
1238 1239
    /** @brief A new camera image has arrived */
    void _imageReady                        (UASInterface* uas);
Don Gagne's avatar
Don Gagne committed
1240
    void _prearmErrorTimeout(void);
DonLakeFlyer's avatar
DonLakeFlyer committed
1241 1242 1243
    void _missionLoadComplete(void);
    void _geoFenceLoadComplete(void);
    void _rallyPointLoadComplete(void);
1244
    void _sendMavCommandAgain(void);
1245 1246
    void _clearTrajectoryPoints(void);
    void _clearCameraTriggerPoints(void);
1247
    void _updateDistanceHeadingToHome(void);
1248
    void _updateHeadingToNextWP(void);
1249
    void _updateDistanceToGCS(void);
1250 1251
    void _updateHobbsMeter(void);
    void _vehicleParamLoaded(bool ready);
1252
    void _sendQGCTimeToVehicle(void);
1253
    void _mavlinkMessageStatus(int uasId, uint64_t totalSent, uint64_t totalReceived, uint64_t totalLoss, float lossPercent);
Jacob Walser's avatar
Jacob Walser committed
1254

Gus Grubba's avatar
Gus Grubba committed
1255 1256
    void _trafficUpdate         (bool alert, QString traffic_id, QString vehicle_id, QGeoCoordinate location, float heading);
    void _adsbTimerTimeout      ();
1257
    void _orbitTelemetryTimeout (void);
1258
    void _protocolVersionTimeOut(void);
1259

1260
private:
Gus Grubba's avatar
Gus Grubba committed
1261 1262 1263
    bool _containsLink          (LinkInterface* link);
    void _addLink               (LinkInterface* link);
    void _joystickChanged       (Joystick* joystick);
1264 1265
    void _loadSettings(void);
    void _saveSettings(void);
1266
    void _startJoystick(bool start);
DonLakeFlyer's avatar
DonLakeFlyer committed
1267
    void _handlePing(LinkInterface* link, mavlink_message_t& message);
Don Gagne's avatar
Don Gagne committed
1268 1269
    void _handleHomePosition(mavlink_message_t& message);
    void _handleHeartbeat(mavlink_message_t& message);
1270
    void _handleRadioStatus(mavlink_message_t& message);
Don Gagne's avatar
Don Gagne committed
1271 1272
    void _handleRCChannels(mavlink_message_t& message);
    void _handleRCChannelsRaw(mavlink_message_t& message);
Don Gagne's avatar
Don Gagne committed
1273 1274
    void _handleBatteryStatus(mavlink_message_t& message);
    void _handleSysStatus(mavlink_message_t& message);
1275
    void _handleWindCov(mavlink_message_t& message);
1276
    void _handleVibration(mavlink_message_t& message);
Don Gagne's avatar
Don Gagne committed
1277
    void _handleExtendedSysState(mavlink_message_t& message);
1278
    void _handleCommandAck(mavlink_message_t& message);
1279
    void _handleCommandLong(mavlink_message_t& message);
Gus Grubba's avatar
Gus Grubba committed
1280
    void _handleAutopilotVersion(LinkInterface* link, mavlink_message_t& message);
1281
    void _handleProtocolVersion(LinkInterface* link, mavlink_message_t& message);
1282
    void _handleHilActuatorControls(mavlink_message_t& message);
1283 1284 1285 1286
    void _handleGpsRawInt(mavlink_message_t& message);
    void _handleGlobalPositionInt(mavlink_message_t& message);
    void _handleAltitude(mavlink_message_t& message);
    void _handleVfrHud(mavlink_message_t& message);
1287 1288 1289
    void _handleScaledPressure(mavlink_message_t& message);
    void _handleScaledPressure2(mavlink_message_t& message);
    void _handleScaledPressure3(mavlink_message_t& message);
1290
    void _handleHighLatency2(mavlink_message_t& message);
1291 1292
    void _handleAttitudeWorker(double rollRadians, double pitchRadians, double yawRadians);
    void _handleAttitude(mavlink_message_t& message);
1293
    void _handleAttitudeQuaternion(mavlink_message_t& message);
DonLakeFlyer's avatar
DonLakeFlyer committed
1294
    void _handleAttitudeTarget(mavlink_message_t& message);
1295
    void _handleDistanceSensor(mavlink_message_t& message);
1296
    void _handleEstimatorStatus(mavlink_message_t& message);
Don Gagne's avatar
Don Gagne committed
1297
    void _handleStatusText(mavlink_message_t& message, bool longVersion);
1298
    void _handleOrbitExecutionStatus(const mavlink_message_t& message);
1299
    void _handleMessageInterval(const mavlink_message_t& message);
Gus Grubba's avatar
Gus Grubba committed
1300
    void _handleGimbalOrientation(const mavlink_message_t& message);
1301 1302
    // ArduPilot dialect messages
#if !defined(NO_ARDUPILOT_DIALECT)
1303
    void _handleCameraFeedback(const mavlink_message_t& message);
1304 1305
    void _handleWind(mavlink_message_t& message);
#endif
1306
    void _handleCameraImageCaptured(const mavlink_message_t& message);
1307
    void _handleADSBVehicle(const mavlink_message_t& message);
1308
    void _missionManagerError(int errorCode, const QString& errorMsg);
1309
    void _geoFenceManagerError(int errorCode, const QString& errorMsg);
1310
    void _rallyPointManagerError(int errorCode, const QString& errorMsg);
1311 1312
    void _mapTrajectoryStart(void);
    void _mapTrajectoryStop(void);
1313
    void _linkActiveChanged(LinkInterface* link, bool active, int vehicleID);
1314 1315
    void _say(const QString& text);
    QString _vehicleIdSpeech(void);
1316 1317 1318
    void _handleMavlinkLoggingData(mavlink_message_t& message);
    void _handleMavlinkLoggingDataAcked(mavlink_message_t& message);
    void _ackMavlinkLogData(uint16_t sequence);
1319
    void _sendNextQueuedMavCommand(void);
1320
    void _updatePriorityLink(bool updateActive, bool sendCommand);
1321
    void _commonInit(void);
DonLakeFlyer's avatar
DonLakeFlyer committed
1322
    void _startPlanRequest(void);
1323
    void _setupAutoDisarmSignalling(void);
DonLakeFlyer's avatar
DonLakeFlyer committed
1324
    void _setCapabilities(uint64_t capabilityBits);
DonLakeFlyer's avatar
DonLakeFlyer committed
1325 1326
    void _updateArmed(bool armed);
    bool _apmArmingNotRequired(void);
1327
    void _pidTuningAdjustRates(bool setRatesForTuning);
1328 1329
    void _handleUnsupportedRequestAutopilotCapabilities(void);
    void _handleUnsupportedRequestProtocolVersion(void);
Don Gagne's avatar
Don Gagne committed
1330

1331
    int     _id;                    ///< Mavlink system id
1332
    int     _defaultComponentId;
1333
    bool    _active;
1334
    bool    _offlineEditingVehicle; ///< This Vehicle is a "disconnected" vehicle for ui use while offline editing
dogmaphobic's avatar
dogmaphobic committed
1335

1336
    MAV_AUTOPILOT       _firmwareType;
1337
    MAV_TYPE            _vehicleType;
1338
    FirmwarePlugin*     _firmwarePlugin;
1339
    QObject*            _firmwarePluginInstanceData;
1340
    AutoPilotPlugin*    _autopilotPlugin;
Don Gagne's avatar
Don Gagne committed
1341
    MAVLinkProtocol*    _mavlink;
1342
    bool                _soloFirmware;
1343
    QGCToolbox*         _toolbox;
1344
    SettingsManager*    _settingsManager;
dogmaphobic's avatar
dogmaphobic committed
1345

Don Gagne's avatar
Don Gagne committed
1346
    QList<LinkInterface*> _links;
dogmaphobic's avatar
dogmaphobic committed
1347

1348
    JoystickMode_t  _joystickMode;
1349
    bool            _joystickEnabled;
dogmaphobic's avatar
dogmaphobic committed
1350

1351
    UAS* _uas;
dogmaphobic's avatar
dogmaphobic committed
1352

1353
    QGeoCoordinate  _coordinate;
1354
    QGeoCoordinate  _homePosition;
dogmaphobic's avatar
dogmaphobic committed
1355

1356 1357 1358 1359 1360 1361 1362 1363 1364
    UASInterface*   _mav;
    int             _currentMessageCount;
    int             _messageCount;
    int             _currentErrorCount;
    int             _currentWarningCount;
    int             _currentNormalCount;
    MessageType_t   _currentMessageType;
    QString         _latestError;
    int             _updateCount;
dogmaphobic's avatar
dogmaphobic committed
1365
    QString         _formatedMessage;
Don Gagne's avatar
Don Gagne committed
1366 1367
    int             _rcRSSI;
    double          _rcRSSIstore;
Don Gagne's avatar
Don Gagne committed
1368
    bool            _autoDisconnect;    ///< true: Automatically disconnect vehicle when last connection goes away or lost heartbeat
Don Gagne's avatar
Don Gagne committed
1369
    bool            _flying;
1370
    bool            _landing;
1371
    bool            _vtolInFwdFlight;
1372 1373 1374 1375
    uint32_t        _onboardControlSensorsPresent;
    uint32_t        _onboardControlSensorsEnabled;
    uint32_t        _onboardControlSensorsHealth;
    uint32_t        _onboardControlSensorsUnhealthy;
1376 1377
    bool            _gpsRawIntMessageAvailable;
    bool            _globalPositionIntMessageAvailable;
DonLakeFlyer's avatar
DonLakeFlyer committed
1378 1379
    double          _defaultCruiseSpeed;
    double          _defaultHoverSpeed;
Gus Grubba's avatar
Gus Grubba committed
1380 1381 1382 1383 1384
    int             _telemetryRRSSI;
    int             _telemetryLRSSI;
    uint32_t        _telemetryRXErrors;
    uint32_t        _telemetryFixed;
    uint32_t        _telemetryTXBuffer;
1385 1386
    int             _telemetryLNoise;
    int             _telemetryRNoise;
1387
    bool            _mavlinkProtocolRequestComplete;
1388
    unsigned        _maxProtoVersion;
1389
    bool            _vehicleCapabilitiesKnown;
1390
    uint64_t        _capabilityBits;
1391
    bool            _highLatencyLink;
1392
    bool            _receivingAttitudeQuaternion;
dogmaphobic's avatar
dogmaphobic committed
1393

1394 1395
    QGCCameraManager* _cameras;

1396
    typedef struct {
1397 1398 1399 1400 1401 1402
        int         component;
        bool        commandInt; // true: use COMMAND_INT, false: use COMMAND_LONG
        MAV_CMD     command;
        MAV_FRAME   frame;
        double      rgParam[7];
        bool        showError;
1403 1404 1405 1406 1407 1408
    } MavCommandQueueEntry_t;

    QList<MavCommandQueueEntry_t>   _mavCommandQueue;
    QTimer                          _mavCommandAckTimer;
    int                             _mavCommandRetryCount;
    static const int                _mavCommandMaxRetryCount = 3;
1409
    static const int                _mavCommandAckTimeoutMSecs = 3000;
DonLakeFlyer's avatar
DonLakeFlyer committed
1410
    static const int                _mavCommandAckTimeoutMSecsHighLatency = 120000;
1411

Don Gagne's avatar
Don Gagne committed
1412 1413 1414 1415
    QString             _prearmError;
    QTimer              _prearmErrorTimer;
    static const int    _prearmErrorTimeoutMSecs = 35 * 1000;   ///< Take away prearm error after 35 seconds

1416 1417 1418 1419
    // Lost connection handling
    bool                _connectionLost;
    bool                _connectionLostEnabled;

DonLakeFlyer's avatar
DonLakeFlyer committed
1420 1421
    bool                _initialPlanRequestComplete;

Don Gagne's avatar
Don Gagne committed
1422
    MissionManager*     _missionManager;
1423
    bool                _missionManagerInitialRequestSent;
1424

1425
    GeoFenceManager*    _geoFenceManager;
1426 1427 1428 1429
    bool                _geoFenceManagerInitialRequestSent;

    RallyPointManager*  _rallyPointManager;
    bool                _rallyPointManagerInitialRequestSent;
1430

1431 1432
    ParameterManager*   _parameterManager;

1433
#if defined(QGC_AIRMAP_ENABLED)
1434
    AirspaceVehicleManager* _airspaceVehicleManager;
1435
#endif
dogmaphobic's avatar
dogmaphobic committed
1436

Don Gagne's avatar
Don Gagne committed
1437 1438 1439
    bool    _armed;         ///< true: vehicle is armed
    uint8_t _base_mode;     ///< base_mode from HEARTBEAT
    uint32_t _custom_mode;  ///< custom_mode from HEARTBEAT
1440 1441 1442 1443 1444 1445

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

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

1449 1450
    static const int _sendMessageMultipleRetries = 5;
    static const int _sendMessageMultipleIntraMessageDelay = 500;
dogmaphobic's avatar
dogmaphobic committed
1451

1452 1453
    QTimer  _sendMultipleTimer;
    int     _nextSendMessageMultipleIndex;
dogmaphobic's avatar
dogmaphobic committed
1454

1455
    QTime               _flightTimer;
1456 1457 1458 1459 1460
    QTimer              _mapTrajectoryTimer;
    QmlObjectListModel  _mapTrajectoryList;
    QGeoCoordinate      _mapTrajectoryLastCoordinate;
    bool                _mapTrajectoryHaveFirstCoordinate;
    static const int    _mapTrajectoryMsecsBetweenPoints = 1000;
1461

1462 1463
    QmlObjectListModel  _cameraTriggerPoints;

1464 1465
    QmlObjectListModel              _adsbVehicles;
    QMap<uint32_t, ADSBVehicle*>    _adsbICAOMap;
1466
    QMap<QString, ADSBVehicle*>     _trafficVehicleMap;
1467
    QTimer                          _adsbTimer;
1468

1469
    // Toolbox references
dogmaphobic's avatar
dogmaphobic committed
1470 1471 1472 1473 1474
    FirmwarePluginManager*      _firmwarePluginManager;
    JoystickManager*            _joystickManager;

    int                         _flowImageIndex;

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

1477 1478 1479 1480 1481 1482 1483
    uint                _messagesReceived;
    uint                _messagesSent;
    uint                _messagesLost;
    uint8_t             _messageSeq;
    uint8_t             _compID;
    bool                _heardFrom;

Gus Grubba's avatar
Gus Grubba committed
1484 1485 1486 1487 1488 1489
    float               _curGimbalRoll  = 0.0f;
    float               _curGimbalPitch = 0.0f;
    float               _curGinmbalYaw  = 0.0f;
    bool                _haveGimbalData = false;
    Joystick*           _activeJoystick = nullptr;

Don Gagne's avatar
Don Gagne committed
1490 1491 1492
    int _firmwareMajorVersion;
    int _firmwareMinorVersion;
    int _firmwarePatchVersion;
1493 1494 1495
    int _firmwareCustomMajorVersion;
    int _firmwareCustomMinorVersion;
    int _firmwareCustomPatchVersion;
1496
    FIRMWARE_VERSION_TYPE _firmwareVersionType;
Don Gagne's avatar
Don Gagne committed
1497

1498
    QString _gitHash;
Gus Grubba's avatar
Gus Grubba committed
1499
    quint64 _uid;
1500

1501
    int _lastAnnouncedLowBatteryPercent;
1502

1503
    SharedLinkInterfacePointer _priorityLink;  // We always keep a reference to the priority link to manage shutdown ordering
1504
    bool _priorityLinkCommanded;
1505

1506 1507 1508 1509 1510
    uint64_t    _mavlinkSentCount       = 0;
    uint64_t    _mavlinkReceivedCount   = 0;
    uint64_t    _mavlinkLossCount       = 0;
    float       _mavlinkLossPercent     = 0.0f;

1511 1512
    QMap<QString, QTime> _noisySpokenPrearmMap; ///< Used to prevent PreArm messages from being spoken too often

1513 1514 1515 1516 1517 1518
    // Orbit status values
    bool            _orbitActive;
    QGCMapCircle    _orbitMapCircle;
    QTimer          _orbitTelemetryTimer;
    static const int _orbitTelemetryTimeoutMsecs = 3000; // No telemetry for this amount and orbit will go inactive

1519 1520 1521 1522 1523 1524
    // PID Tuning telemetry mode
    bool            _pidTuningTelemetryMode;
    bool            _pidTuningWaitingForRates;
    QList<int>      _pidTuningMessages;
    QMap<int, int>  _pidTuningMessageRatesUsecs;

Don Gagne's avatar
Don Gagne committed
1525 1526 1527 1528 1529
    // FactGroup facts

    Fact _rollFact;
    Fact _pitchFact;
    Fact _headingFact;
DonLakeFlyer's avatar
DonLakeFlyer committed
1530 1531 1532
    Fact _rollRateFact;
    Fact _pitchRateFact;
    Fact _yawRateFact;
Don Gagne's avatar
Don Gagne committed
1533 1534 1535 1536 1537
    Fact _groundSpeedFact;
    Fact _airSpeedFact;
    Fact _climbRateFact;
    Fact _altitudeRelativeFact;
    Fact _altitudeAMSLFact;
1538
    Fact _flightDistanceFact;
1539
    Fact _flightTimeFact;
1540
    Fact _distanceToHomeFact;
1541
    Fact _headingToNextWPFact;
1542
    Fact _headingToHomeFact;
1543
    Fact _distanceToGCSFact;
1544
    Fact _hobbsFact;
1545
    Fact _throttlePctFact;
Don Gagne's avatar
Don Gagne committed
1546

1547
    VehicleGPSFactGroup             _gpsFactGroup;
DonLakeFlyer's avatar
DonLakeFlyer committed
1548 1549
    VehicleBatteryFactGroup         _battery1FactGroup;
    VehicleBatteryFactGroup         _battery2FactGroup;
1550 1551 1552 1553 1554 1555
    VehicleWindFactGroup            _windFactGroup;
    VehicleVibrationFactGroup       _vibrationFactGroup;
    VehicleTemperatureFactGroup     _temperatureFactGroup;
    VehicleClockFactGroup           _clockFactGroup;
    VehicleSetpointFactGroup        _setpointFactGroup;
    VehicleDistanceSensorFactGroup  _distanceSensorFactGroup;
1556
    VehicleEstimatorStatusFactGroup _estimatorStatusFactGroup;
Don Gagne's avatar
Don Gagne committed
1557 1558 1559 1560

    static const char* _rollFactName;
    static const char* _pitchFactName;
    static const char* _headingFactName;
DonLakeFlyer's avatar
DonLakeFlyer committed
1561 1562 1563
    static const char* _rollRateFactName;
    static const char* _pitchRateFactName;
    static const char* _yawRateFactName;
Don Gagne's avatar
Don Gagne committed
1564 1565 1566 1567 1568
    static const char* _groundSpeedFactName;
    static const char* _airSpeedFactName;
    static const char* _climbRateFactName;
    static const char* _altitudeRelativeFactName;
    static const char* _altitudeAMSLFactName;
1569
    static const char* _flightDistanceFactName;
1570
    static const char* _flightTimeFactName;
1571
    static const char* _distanceToHomeFactName;
1572
    static const char* _headingToNextWPFactName;
1573
    static const char* _headingToHomeFactName;
1574
    static const char* _distanceToGCSFactName;
1575
    static const char* _hobbsFactName;
1576
    static const char* _throttlePctFactName;
Don Gagne's avatar
Don Gagne committed
1577

Don Gagne's avatar
Don Gagne committed
1578
    static const char* _gpsFactGroupName;
DonLakeFlyer's avatar
DonLakeFlyer committed
1579 1580
    static const char* _battery1FactGroupName;
    static const char* _battery2FactGroupName;
Don Gagne's avatar
Don Gagne committed
1581
    static const char* _windFactGroupName;
1582
    static const char* _vibrationFactGroupName;
1583
    static const char* _temperatureFactGroupName;
dheideman's avatar
dheideman committed
1584
    static const char* _clockFactGroupName;
1585
    static const char* _distanceSensorFactGroupName;
1586
    static const char* _estimatorStatusFactGroupName;
Don Gagne's avatar
Don Gagne committed
1587 1588 1589

    static const int _vehicleUIUpdateRateMSecs = 100;

1590
    // Settings keys
1591 1592
    static const char* _settingsGroup;
    static const char* _joystickModeSettingsKey;
1593
    static const char* _joystickEnabledSettingsKey;
Don Gagne's avatar
Don Gagne committed
1594

1595
};