Vehicle.h 85.1 KB
Newer Older
1 2
/****************************************************************************
 *
Gus Grubba's avatar
Gus Grubba committed
3
 * (c) 2009-2020 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org>
4 5 6 7 8
 *
 * 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 <QElapsedTimer>
13
#include <QObject>
14
#include <QVariantList>
15
#include <QGeoCoordinate>
16

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

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

43 44 45
#if defined(QGC_AIRMAP_ENABLED)
class AirspaceVehicleManager;
#endif
46 47 48

Q_DECLARE_LOGGING_CATEGORY(VehicleLog)

Don Gagne's avatar
Don Gagne committed
49 50
class Vehicle;

51 52 53 54 55
class VehicleDistanceSensorFactGroup : public FactGroup
{
    Q_OBJECT

public:
56
    VehicleDistanceSensorFactGroup(QObject* parent = nullptr);
57

58 59 60 61 62 63 64 65 66 67
    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)
68

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

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

private:
    Fact _rotationNoneFact;
93
    Fact _rotationYaw45Fact;
94
    Fact _rotationYaw90Fact;
95
    Fact _rotationYaw135Fact;
96
    Fact _rotationYaw180Fact;
97
    Fact _rotationYaw225Fact;
98
    Fact _rotationYaw270Fact;
99 100 101
    Fact _rotationYaw315Fact;
    Fact _rotationPitch90Fact;
    Fact _rotationPitch270Fact;
102 103
};

DonLakeFlyer's avatar
DonLakeFlyer committed
104 105 106 107 108
class VehicleSetpointFactGroup : public FactGroup
{
    Q_OBJECT

public:
109
    VehicleSetpointFactGroup(QObject* parent = nullptr);
DonLakeFlyer's avatar
DonLakeFlyer committed
110 111 112 113 114 115 116 117

    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)

118 119 120 121 122 123
    Fact* roll      () { return &_rollFact; }
    Fact* pitch     () { return &_pitchFact; }
    Fact* yaw       () { return &_yawFact; }
    Fact* rollRate  () { return &_rollRateFact; }
    Fact* pitchRate () { return &_pitchRateFact; }
    Fact* yawRate   () { return &_yawRateFact; }
DonLakeFlyer's avatar
DonLakeFlyer committed
124 125 126 127 128 129 130 131 132 133 134 135 136 137 138 139 140

    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;
};

141 142 143 144 145
class VehicleVibrationFactGroup : public FactGroup
{
    Q_OBJECT

public:
146
    VehicleVibrationFactGroup(QObject* parent = nullptr);
147 148 149 150 151 152 153 154

    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)

155 156 157 158 159 160
    Fact* xAxis         () { return &_xAxisFact; }
    Fact* yAxis         () { return &_yAxisFact; }
    Fact* zAxis         () { return &_zAxisFact; }
    Fact* clipCount1    () { return &_clipCount1Fact; }
    Fact* clipCount2    () { return &_clipCount2Fact; }
    Fact* clipCount3    () { return &_clipCount3Fact; }
161 162 163 164 165 166 167 168 169 170 171 172 173 174 175 176 177

    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
178 179 180 181 182
class VehicleWindFactGroup : public FactGroup
{
    Q_OBJECT

public:
183
    VehicleWindFactGroup(QObject* parent = nullptr);
Don Gagne's avatar
Don Gagne committed
184 185 186 187 188

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

189 190 191
    Fact* direction     () { return &_directionFact; }
    Fact* speed         () { return &_speedFact; }
    Fact* verticalSpeed () { return &_verticalSpeedFact; }
Don Gagne's avatar
Don Gagne committed
192 193 194 195 196 197 198 199 200 201 202

    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
203 204 205 206 207
class VehicleGPSFactGroup : public FactGroup
{
    Q_OBJECT

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

210 211
    Q_PROPERTY(Fact* lat                READ lat                CONSTANT)
    Q_PROPERTY(Fact* lon                READ lon                CONSTANT)
212
    Q_PROPERTY(Fact* mgrs               READ mgrs               CONSTANT)
Don Gagne's avatar
Don Gagne committed
213 214 215 216 217 218
    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)

219 220 221 222 223 224 225 226
    Fact* lat               () { return &_latFact; }
    Fact* lon               () { return &_lonFact; }
    Fact* mgrs              () { return &_mgrsFact; }
    Fact* hdop              () { return &_hdopFact; }
    Fact* vdop              () { return &_vdopFact; }
    Fact* courseOverGround  () { return &_courseOverGroundFact; }
    Fact* count             () { return &_countFact; }
    Fact* lock              () { return &_lockFact; }
Don Gagne's avatar
Don Gagne committed
227

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

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

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

    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)
260
    Q_PROPERTY(Fact* instantPower       READ instantPower       CONSTANT)
261 262
    Q_PROPERTY(Fact* timeRemaining      READ timeRemaining      CONSTANT)
    Q_PROPERTY(Fact* chargeState        READ chargeState        CONSTANT)
263

264 265 266 267 268 269 270 271
    Fact* voltage                   () { return &_voltageFact; }
    Fact* percentRemaining          () { return &_percentRemainingFact; }
    Fact* mahConsumed               () { return &_mahConsumedFact; }
    Fact* current                   () { return &_currentFact; }
    Fact* temperature               () { return &_temperatureFact; }
    Fact* instantPower              () { return &_instantPowerFact; }
    Fact* timeRemaining             () { return &_timeRemainingFact; }
    Fact* chargeState               () { return &_chargeStateFact; }
Don Gagne's avatar
Don Gagne committed
272 273 274 275 276 277

    static const char* _voltageFactName;
    static const char* _percentRemainingFactName;
    static const char* _mahConsumedFactName;
    static const char* _currentFactName;
    static const char* _temperatureFactName;
278
    static const char* _instantPowerFactName;
279 280
    static const char* _timeRemainingFactName;
    static const char* _chargeStateFactName;
Don Gagne's avatar
Don Gagne committed
281

282 283
    static const char* _settingsGroup;

Don Gagne's avatar
Don Gagne committed
284
private:
285 286 287 288 289
    Fact            _voltageFact;
    Fact            _percentRemainingFact;
    Fact            _mahConsumedFact;
    Fact            _currentFact;
    Fact            _temperatureFact;
290
    Fact            _instantPowerFact;
291 292
    Fact            _timeRemainingFact;
    Fact            _chargeStateFact;
Don Gagne's avatar
Don Gagne committed
293 294
};

295 296 297 298 299
class VehicleTemperatureFactGroup : public FactGroup
{
    Q_OBJECT

public:
300
    VehicleTemperatureFactGroup(QObject* parent = nullptr);
301 302 303 304 305

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

306 307 308
    Fact* temperature1 () { return &_temperature1Fact; }
    Fact* temperature2 () { return &_temperature2Fact; }
    Fact* temperature3 () { return &_temperature3Fact; }
309 310 311 312 313 314 315 316 317 318 319 320 321 322 323

    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
324 325 326 327 328
class VehicleClockFactGroup : public FactGroup
{
    Q_OBJECT

public:
329
    VehicleClockFactGroup(QObject* parent = nullptr);
dheideman's avatar
dheideman committed
330 331 332 333

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

334 335
    Fact* currentTime () { return &_currentTimeFact; }
    Fact* currentDate () { return &_currentDateFact; }
dheideman's avatar
dheideman committed
336 337 338 339 340 341 342

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

    static const char* _settingsGroup;

private slots:
343
    void _updateAllValues() override;
dheideman's avatar
dheideman committed
344 345 346 347 348 349

private:
    Fact            _currentTimeFact;
    Fact            _currentDateFact;
};

350 351 352 353 354 355 356 357 358 359 360 361 362 363 364 365 366 367 368 369 370 371 372 373 374 375 376 377
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)

378 379 380 381 382 383 384 385 386 387 388 389 390 391 392 393 394 395 396 397
    Fact* goodAttitudeEstimate          () { return &_goodAttitudeEstimateFact; }
    Fact* goodHorizVelEstimate          () { return &_goodHorizVelEstimateFact; }
    Fact* goodVertVelEstimate           () { return &_goodVertVelEstimateFact; }
    Fact* goodHorizPosRelEstimate       () { return &_goodHorizPosRelEstimateFact; }
    Fact* goodHorizPosAbsEstimate       () { return &_goodHorizPosAbsEstimateFact; }
    Fact* goodVertPosAbsEstimate        () { return &_goodVertPosAbsEstimateFact; }
    Fact* goodVertPosAGLEstimate        () { return &_goodVertPosAGLEstimateFact; }
    Fact* goodConstPosModeEstimate      () { return &_goodConstPosModeEstimateFact; }
    Fact* goodPredHorizPosRelEstimate   () { return &_goodPredHorizPosRelEstimateFact; }
    Fact* goodPredHorizPosAbsEstimate   () { return &_goodPredHorizPosAbsEstimateFact; }
    Fact* gpsGlitch                     () { return &_gpsGlitchFact; }
    Fact* accelError                    () { return &_accelErrorFact; }
    Fact* velRatio                      () { return &_velRatioFact; }
    Fact* horizPosRatio                 () { return &_horizPosRatioFact; }
    Fact* vertPosRatio                  () { return &_vertPosRatioFact; }
    Fact* magRatio                      () { return &_magRatioFact; }
    Fact* haglRatio                     () { return &_haglRatioFact; }
    Fact* tasRatio                      () { return &_tasRatioFact; }
    Fact* horizPosAccuracy              () { return &_horizPosAccuracyFact; }
    Fact* vertPosAccuracy               () { return &_vertPosAccuracyFact; }
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

    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.*/
469 470
        } mavlink_estimator_status_t;
    };
471 472 473
#endif
};

Don Gagne's avatar
Don Gagne committed
474
class Vehicle : public FactGroup
475 476
{
    Q_OBJECT
dogmaphobic's avatar
dogmaphobic committed
477

478
public:
479 480
    Vehicle(LinkInterface*          link,
            int                     vehicleId,
481
            int                     defaultComponentId,
482 483 484 485
            MAV_AUTOPILOT           firmwareType,
            MAV_TYPE                vehicleType,
            FirmwarePluginManager*  firmwarePluginManager,
            JoystickManager*        joystickManager);
486

487 488 489 490
    // The following is used to create a disconnected Vehicle for use while offline editing.
    Vehicle(MAV_AUTOPILOT           firmwareType,
            MAV_TYPE                vehicleType,
            FirmwarePluginManager*  firmwarePluginManager,
491
            QObject*                parent = nullptr);
492

493
    ~Vehicle();
dogmaphobic's avatar
dogmaphobic committed
494

495 496 497 498 499
    /// 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,
500
        SysStatusSensorAbsolutePressure =       MAV_SYS_STATUS_SENSOR_ABSOLUTE_PRESSURE,
501 502 503 504 505 506 507 508 509 510 511 512 513 514 515 516 517 518 519 520 521 522 523 524 525
        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)

526 527 528 529 530 531 532
    enum CheckList {
        CheckListNotSetup = 0,
        CheckListPassed,
        CheckListFailed,
    };
    Q_ENUM(CheckList)

533 534 535 536
    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)
537
    Q_PROPERTY(QGeoCoordinate       armedPosition           READ armedPosition                                          NOTIFY armedPositionChanged)
538
    Q_PROPERTY(bool                 armed                   READ armed                  WRITE setArmed                  NOTIFY armedChanged)
539
    Q_PROPERTY(bool                 autoDisarm              READ autoDisarm                                             NOTIFY autoDisarmChanged)
540
    Q_PROPERTY(bool                 flightModeSetAvailable  READ flightModeSetAvailable                                 CONSTANT)
541
    Q_PROPERTY(QStringList          flightModes             READ flightModes                                            NOTIFY flightModesChanged)
542
    Q_PROPERTY(QStringList          extraJoystickFlightModes READ extraJoystickFlightModes                              NOTIFY flightModesChanged)
543 544
    Q_PROPERTY(QString              flightMode              READ flightMode             WRITE setFlightMode             NOTIFY flightModeChanged)
    Q_PROPERTY(bool                 hilMode                 READ hilMode                WRITE setHilMode                NOTIFY hilModeChanged)
545
    Q_PROPERTY(TrajectoryPoints*    trajectoryPoints        MEMBER _trajectoryPoints                                    CONSTANT)
546
    Q_PROPERTY(QmlObjectListModel*  cameraTriggerPoints     READ cameraTriggerPoints                                    CONSTANT)
547 548 549 550 551 552 553 554 555 556 557 558 559 560 561 562 563
    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)
564 565
    Q_PROPERTY(bool                 px4Firmware             READ px4Firmware                                            NOTIFY firmwareTypeChanged)
    Q_PROPERTY(bool                 apmFirmware             READ apmFirmware                                            NOTIFY firmwareTypeChanged)
566 567 568 569 570 571 572
    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)
573 574 575 576 577
    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)
578
    Q_PROPERTY(bool        supportsThrottleModeCenterZero   READ supportsThrottleModeCenterZero                         CONSTANT)
579
    Q_PROPERTY(bool                supportsNegativeThrust   READ supportsNegativeThrust                                 CONSTANT)
580
    Q_PROPERTY(bool                 supportsJSButton        READ supportsJSButton                                       CONSTANT)
581
    Q_PROPERTY(bool                 supportsRadio           READ supportsRadio                                          CONSTANT)
582
    Q_PROPERTY(bool               supportsMotorInterference READ supportsMotorInterference                              CONSTANT)
583 584
    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
585 586 587
    Q_PROPERTY(int                  motorCount              READ motorCount                                             CONSTANT)
    Q_PROPERTY(bool                 coaxialMotors           READ coaxialMotors                                          CONSTANT)
    Q_PROPERTY(bool                 xConfigMotors           READ xConfigMotors                                          CONSTANT)
588
    Q_PROPERTY(bool                 isOfflineEditingVehicle READ isOfflineEditingVehicle                                CONSTANT)
589 590
    Q_PROPERTY(QString              brandImageIndoor        READ brandImageIndoor                                       NOTIFY firmwareTypeChanged)
    Q_PROPERTY(QString              brandImageOutdoor       READ brandImageOutdoor                                      NOTIFY firmwareTypeChanged)
591
    Q_PROPERTY(QStringList          unhealthySensors        READ unhealthySensors                                       NOTIFY unhealthySensorsChanged)
592 593 594
    Q_PROPERTY(int                  sensorsPresentBits      READ sensorsPresentBits                                     NOTIFY sensorsPresentBitsChanged)
    Q_PROPERTY(int                  sensorsEnabledBits      READ sensorsEnabledBits                                     NOTIFY sensorsEnabledBitsChanged)
    Q_PROPERTY(int                  sensorsHealthBits       READ sensorsHealthBits                                      NOTIFY sensorsHealthBitsChanged)
595
    Q_PROPERTY(int                  sensorsUnhealthyBits    READ sensorsUnhealthyBits                                   NOTIFY sensorsUnhealthyBitsChanged) ///< Combination of enabled and health
596
    Q_PROPERTY(QString              missionFlightMode       READ missionFlightMode                                      CONSTANT)
597
    Q_PROPERTY(QString              pauseFlightMode         READ pauseFlightMode                                        CONSTANT)
598
    Q_PROPERTY(QString              rtlFlightMode           READ rtlFlightMode                                          CONSTANT)
DonLakeFlyer's avatar
DonLakeFlyer committed
599 600
    Q_PROPERTY(QString              smartRTLFlightMode      READ smartRTLFlightMode                                     CONSTANT)
    Q_PROPERTY(bool                 supportsSmartRTL        READ supportsSmartRTL                                       CONSTANT)
601
    Q_PROPERTY(QString              landFlightMode          READ landFlightMode                                         CONSTANT)
602
    Q_PROPERTY(QString              takeControlFlightMode   READ takeControlFlightMode                                  CONSTANT)
603
    Q_PROPERTY(QString              followFlightMode        READ followFlightMode                                       CONSTANT)
604 605
    Q_PROPERTY(QString              firmwareTypeString      READ firmwareTypeString                                     NOTIFY firmwareTypeChanged)
    Q_PROPERTY(QString              vehicleTypeString       READ vehicleTypeString                                      NOTIFY vehicleTypeChanged)
606 607 608
    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
609 610 611 612 613
    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)
614 615
    Q_PROPERTY(int                  telemetryLNoise         READ telemetryLNoise                                        NOTIFY telemetryLNoiseChanged)
    Q_PROPERTY(int                  telemetryRNoise         READ telemetryRNoise                                        NOTIFY telemetryRNoiseChanged)
616
    Q_PROPERTY(QVariantList         toolBarIndicators       READ toolBarIndicators                                      NOTIFY toolBarIndicatorsChanged)
Don Gagne's avatar
Don Gagne committed
617
    Q_PROPERTY(bool              initialPlanRequestComplete READ initialPlanRequestComplete                             NOTIFY initialPlanRequestCompleteChanged)
Gus Grubba's avatar
Gus Grubba committed
618
    Q_PROPERTY(QVariantList         staticCameraList        READ staticCameraList                                       CONSTANT)
619
    Q_PROPERTY(QGCCameraManager*    dynamicCameras          READ dynamicCameras                                         NOTIFY dynamicCamerasChanged)
620
    Q_PROPERTY(QString              hobbsMeter              READ hobbsMeter                                             NOTIFY hobbsMeterChanged)
621
    Q_PROPERTY(bool                 vtolInFwdFlight         READ vtolInFwdFlight        WRITE setVtolInFwdFlight        NOTIFY vtolInFwdFlightChanged)
622
    Q_PROPERTY(bool                 highLatencyLink         READ highLatencyLink                                        NOTIFY highLatencyLinkChanged)
623
    Q_PROPERTY(bool                 supportsTerrainFrame    READ supportsTerrainFrame                                   NOTIFY firmwareTypeChanged)
624
    Q_PROPERTY(QString              priorityLinkName        READ priorityLinkName       WRITE setPriorityLinkByName     NOTIFY priorityLinkNameChanged)
625
    Q_PROPERTY(QVariantList         links                   READ links                                                  NOTIFY linksChanged)
626
    Q_PROPERTY(LinkInterface*       priorityLink            READ priorityLink                                           NOTIFY priorityLinkNameChanged)
627 628 629 630
    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
631 632 633 634
    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)
635
    Q_PROPERTY(bool                 isROIEnabled            READ isROIEnabled                                           NOTIFY isROIEnabledChanged)
636
    Q_PROPERTY(CheckList            checkListState          READ checkListState         WRITE setCheckListState         NOTIFY checkListStateChanged)
637

638 639 640 641
    // The following properties relate to Orbit status
    Q_PROPERTY(bool             orbitActive     READ orbitActive        NOTIFY orbitActiveChanged)
    Q_PROPERTY(QGCMapCircle*    orbitMapCircle  READ orbitMapCircle     CONSTANT)

642
    // Vehicle state used for guided control
Don Gagne's avatar
Don Gagne committed
643 644 645 646 647 648
    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
Gus Grubba's avatar
Gus Grubba committed
649
    Q_PROPERTY(bool     roiModeSupported        READ roiModeSupported                               CONSTANT)                   ///< Orbit mode is supported by this vehicle
Don Gagne's avatar
Don Gagne committed
650 651
    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
652

Gus Grubba's avatar
Gus Grubba committed
653 654
    Q_PROPERTY(ParameterManager*        parameterManager    READ parameterManager   CONSTANT)
    Q_PROPERTY(VehicleObjectAvoidance*  objectAvoidance     READ objectAvoidance    CONSTANT)
655

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

677 678 679 680 681 682 683 684 685
    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
686

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

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

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

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

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

    /// Command vehicle to land at current location
712
    Q_INVOKABLE void guidedModeLand();
Don Gagne's avatar
Don Gagne committed
713 714

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

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

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

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

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

Gus Grubba's avatar
Gus Grubba committed
733 734 735
    /// Command vehicle to keep given point as ROI
    ///     @param centerCoord ROI coordinates
    Q_INVOKABLE void guidedModeROI(const QGeoCoordinate& centerCoord);
736
    Q_INVOKABLE void stopGuidedModeROI();
Gus Grubba's avatar
Gus Grubba committed
737

Don Gagne's avatar
Don Gagne committed
738 739
    /// Command vehicle to pause at current location. If vehicle supports guide mode, vehicle will be left
    /// in guided mode after pause.
740
    Q_INVOKABLE void pauseVehicle();
Don Gagne's avatar
Don Gagne committed
741 742

    /// Command vehicle to kill all motors no matter what state
743
    Q_INVOKABLE void emergencyStop();
Don Gagne's avatar
Don Gagne committed
744

745
    /// Command vehicle to abort landing
746
    Q_INVOKABLE void abortLanding(double climbOutAltitude);
747

748
    Q_INVOKABLE void startMission();
749

750 751 752
    /// Alter the current mission item on the vehicle
    Q_INVOKABLE void setCurrentMissionSequence(int seq);

753 754 755
    /// Reboot vehicle
    Q_INVOKABLE void rebootVehicle();

dogmaphobic's avatar
dogmaphobic committed
756 757 758
    /// Clear Messages
    Q_INVOKABLE void clearMessages();

759
    Q_INVOKABLE void triggerCamera();
Don Gagne's avatar
Don Gagne committed
760
    Q_INVOKABLE void sendPlan(QString planFile);
Don Gagne's avatar
Don Gagne committed
761

762 763 764 765 766
    /// 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
767 768 769
    /// Test motor
    ///     @param motor Motor number, 1-based
    ///     @param percent 0-no power, 100-full power
770 771
    ///     @param timeoutSec Disabled motor after this amount of time
    Q_INVOKABLE void motorTest(int motor, int percent, int timeoutSecs);
Don Gagne's avatar
Don Gagne committed
772

Don Gagne's avatar
Don Gagne committed
773 774
    Q_INVOKABLE void setPIDTuningTelemetryMode(bool pidTuning);

Gus Grubba's avatar
Gus Grubba committed
775 776 777 778
    Q_INVOKABLE void gimbalControlValue (double pitch, double yaw);
    Q_INVOKABLE void gimbalPitchStep    (int direction);
    Q_INVOKABLE void gimbalYawStep      (int direction);
    Q_INVOKABLE void centerGimbal       ();
779

780
#if !defined(NO_ARDUPILOT_DIALECT)
781
    Q_INVOKABLE void flashBootloader();
782 783
#endif

784 785 786 787 788 789
    bool    guidedModeSupported     () const;
    bool    pauseVehicleSupported   () const;
    bool    orbitModeSupported      () const;
    bool    roiModeSupported        () const;
    bool    takeoffVehicleSupported () const;
    QString gotoFlightMode          () const;
Don Gagne's avatar
Don Gagne committed
790

791
    // Property accessors
Don Gagne's avatar
Don Gagne committed
792

793 794
    QGeoCoordinate coordinate() { return _coordinate; }
    QGeoCoordinate armedPosition    () { return _armedPosition; }
dogmaphobic's avatar
dogmaphobic committed
795

796
    typedef enum {
797
        JoystickModeRC,         ///< Joystick emulates an RC Transmitter
798 799 800 801 802 803
        JoystickModeAttitude,
        JoystickModePosition,
        JoystickModeForce,
        JoystickModeVelocity,
        JoystickModeMax
    } JoystickMode_t;
dogmaphobic's avatar
dogmaphobic committed
804

Gus Grubba's avatar
Gus Grubba committed
805
    void updateFlightDistance(double distance);
806

807
    int joystickMode();
808
    void setJoystickMode(int mode);
dogmaphobic's avatar
dogmaphobic committed
809

810
    /// List of joystick mode names
811
    QStringList joystickModes();
dogmaphobic's avatar
dogmaphobic committed
812

813
    bool joystickEnabled();
814
    void setJoystickEnabled(bool enabled);
dogmaphobic's avatar
dogmaphobic committed
815

816
    // Is vehicle active with respect to current active vehicle in QGC
817
    bool active();
818
    void setActive(bool active);
dogmaphobic's avatar
dogmaphobic committed
819

820
    // Property accesors
821 822 823 824
    int id() { return _id; }
    MAV_AUTOPILOT firmwareType() const { return _firmwareType; }
    MAV_TYPE vehicleType() const { return _vehicleType; }
    Q_INVOKABLE QString vehicleTypeName() const;
dogmaphobic's avatar
dogmaphobic committed
825

Patrick José Pereira's avatar
Patrick José Pereira committed
826
    /// Returns the highest quality link available to the Vehicle. If you need to hold a reference to this link use
827
    /// LinkManager::sharedLinkInterfaceForGet to get QSharedPointer for link.
828
    LinkInterface* priorityLink() { return _priorityLink.data(); }
829 830 831 832 833

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

834 835 836
    /// 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
837

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

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

Don Gagne's avatar
Don Gagne committed
844
    /// Provides access to the Firmware Plugin for this Vehicle
845
    FirmwarePlugin* firmwarePlugin() { return _firmwarePlugin; }
dogmaphobic's avatar
dogmaphobic committed
846

847 848 849
    MissionManager*     missionManager()    { return _missionManager; }
    GeoFenceManager*    geoFenceManager()   { return _geoFenceManager; }
    RallyPointManager*  rallyPointManager() { return _rallyPointManager; }
dogmaphobic's avatar
dogmaphobic committed
850

851
    QGeoCoordinate homePosition();
dogmaphobic's avatar
dogmaphobic committed
852

Gus Grubba's avatar
Gus Grubba committed
853 854
    bool armed      () { return _armed; }
    void setArmed   (bool armed);
Don Gagne's avatar
Don Gagne committed
855

856 857 858 859
    bool flightModeSetAvailable             ();
    QStringList flightModes                 ();
    QStringList extraJoystickFlightModes    ();
    QString flightMode                      () const;
860
    void setFlightMode                      (const QString& flightMode);
Don Gagne's avatar
Don Gagne committed
861

862 863
    QString priorityLinkName() const;
    QVariantList links() const;
864 865
    void setPriorityLinkByName(const QString& priorityLinkName);

866
    bool hilMode();
Don Gagne's avatar
Don Gagne committed
867
    void setHilMode(bool hilMode);
dogmaphobic's avatar
dogmaphobic committed
868

869 870 871 872 873
    bool fixedWing() const;
    bool multiRotor() const;
    bool vtol() const;
    bool rover() const;
    bool sub() const;
874

875 876 877 878 879 880
    bool supportsThrottleModeCenterZero () const;
    bool supportsNegativeThrust         ();
    bool supportsRadio                  () const;
    bool supportsJSButton               () const;
    bool supportsMotorInterference      () const;
    bool supportsTerrainFrame           () const;
881

Don Gagne's avatar
Don Gagne committed
882 883
    void setGuidedMode(bool guidedMode);

884
    QString prearmError() const { return _prearmError; }
Don Gagne's avatar
Don Gagne committed
885 886
    void setPrearmError(const QString& prearmError);

887
    QmlObjectListModel* cameraTriggerPoints () { return &_cameraTriggerPoints; }
dogmaphobic's avatar
dogmaphobic committed
888 889 890

    int  flowImageIndex() { return _flowImageIndex; }

891 892 893 894
    //-- Mavlink Logging
    void startMavlinkLog();
    void stopMavlinkLog();

895 896 897
    /// 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
898 899
    ///     @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
900

901 902 903 904 905 906
    typedef enum {
        MessageNone,
        MessageNormal,
        MessageWarning,
        MessageError
    } MessageType_t;
dogmaphobic's avatar
dogmaphobic committed
907

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

967 968 969
    /// Get the maximum MAVLink protocol version supported
    /// @return the maximum version
    unsigned        maxProtoVersion         () const { return _maxProtoVersion; }
970

971 972 973 974 975 976 977 978 979 980 981 982 983 984 985 986 987 988 989 990 991 992 993 994 995 996 997 998 999
    Fact* roll                              () { return &_rollFact; }
    Fact* pitch                             () { return &_pitchFact; }
    Fact* heading                           () { return &_headingFact; }
    Fact* rollRate                          () { return &_rollRateFact; }
    Fact* pitchRate                         () { return &_pitchRateFact; }
    Fact* yawRate                           () { return &_yawRateFact; }
    Fact* airSpeed                          () { return &_airSpeedFact; }
    Fact* groundSpeed                       () { return &_groundSpeedFact; }
    Fact* climbRate                         () { return &_climbRateFact; }
    Fact* altitudeRelative                  () { return &_altitudeRelativeFact; }
    Fact* altitudeAMSL                      () { return &_altitudeAMSLFact; }
    Fact* flightDistance                    () { return &_flightDistanceFact; }
    Fact* distanceToHome                    () { return &_distanceToHomeFact; }
    Fact* headingToNextWP                   () { return &_headingToNextWPFact; }
    Fact* headingToHome                     () { return &_headingToHomeFact; }
    Fact* distanceToGCS                     () { return &_distanceToGCSFact; }
    Fact* hobbs                             () { return &_hobbsFact; }
    Fact* throttlePct                       () { return &_throttlePctFact; }

    FactGroup* gpsFactGroup                 () { return &_gpsFactGroup; }
    FactGroup* battery1FactGroup            () { return &_battery1FactGroup; }
    FactGroup* battery2FactGroup            () { return &_battery2FactGroup; }
    FactGroup* windFactGroup                () { return &_windFactGroup; }
    FactGroup* vibrationFactGroup           () { return &_vibrationFactGroup; }
    FactGroup* temperatureFactGroup         () { return &_temperatureFactGroup; }
    FactGroup* clockFactGroup               () { return &_clockFactGroup; }
    FactGroup* setpointFactGroup            () { return &_setpointFactGroup; }
    FactGroup* distanceSensorFactGroup      () { return &_distanceSensorFactGroup; }
    FactGroup* estimatorStatusFactGroup     () { return &_estimatorStatusFactGroup; }
Don Gagne's avatar
Don Gagne committed
1000

1001
    void setConnectionLostEnabled(bool connectionLostEnabled);
1002

Gus Grubba's avatar
Gus Grubba committed
1003 1004 1005
    ParameterManager*       parameterManager() { return _parameterManager; }
    ParameterManager*       parameterManager() const { return _parameterManager; }
    VehicleObjectAvoidance* objectAvoidance()  { return _objectAvoidance; }
dogmaphobic's avatar
dogmaphobic committed
1006

Don Gagne's avatar
Don Gagne committed
1007 1008
    static const int cMaxRcChannels = 18;

Don Gagne's avatar
Don Gagne committed
1009
    bool containsLink(LinkInterface* link) { return _links.contains(link); }
1010 1011 1012 1013 1014 1015

    /// 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
1016
    /// Signals: mavCommandResult on success or failure
1017
    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);
1018
    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
1019

1020
    /// Same as sendMavCommand but available from Qml.
1021 1022 1023 1024 1025 1026 1027 1028 1029 1030 1031 1032 1033
    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));
    }
1034

1035 1036 1037 1038 1039 1040 1041 1042
    int firmwareMajorVersion() const { return _firmwareMajorVersion; }
    int firmwareMinorVersion() const { return _firmwareMinorVersion; }
    int firmwarePatchVersion() const { return _firmwarePatchVersion; }
    int firmwareVersionType() const { return _firmwareVersionType; }
    int firmwareCustomMajorVersion() const { return _firmwareCustomMajorVersion; }
    int firmwareCustomMinorVersion() const { return _firmwareCustomMinorVersion; }
    int firmwareCustomPatchVersion() const { return _firmwareCustomPatchVersion; }
    QString firmwareVersionTypeString() const;
1043
    void setFirmwareVersion(int majorVersion, int minorVersion, int patchVersion, FIRMWARE_VERSION_TYPE versionType = FIRMWARE_VERSION_TYPE_OFFICIAL);
1044
    void setFirmwareCustomVersion(int majorVersion, int minorVersion, int patchVersion);
1045
    static const int versionNotSetValue = -1;
Don Gagne's avatar
Don Gagne committed
1046

1047 1048
    QString gitHash() const { return _gitHash; }
    quint64 vehicleUID() const { return _uid; }
Gus Grubba's avatar
Gus Grubba committed
1049
    QString vehicleUIDStr();
1050

1051
    bool soloFirmware() const { return _soloFirmware; }
1052 1053
    void setSoloFirmware(bool soloFirmware);

1054
    int defaultComponentId() { return _defaultComponentId; }
1055 1056 1057

    /// Sets the default component id for an offline editing vehicle
    void setOfflineEditingDefaultComponentId(int defaultComponentId);
Don Gagne's avatar
Don Gagne committed
1058

Don Gagne's avatar
Don Gagne committed
1059
    /// @return -1 = Unknown, Number of motors on vehicle
1060
    int motorCount();
Don Gagne's avatar
Don Gagne committed
1061 1062

    /// @return true: Motors are coaxial like an X8 config, false: Quadcopter for example
1063
    bool coaxialMotors();
Don Gagne's avatar
Don Gagne committed
1064 1065

    /// @return true: X confiuration, false: Plus configuration
1066
    bool xConfigMotors();
Don Gagne's avatar
Don Gagne committed
1067

1068
    /// @return Firmware plugin instance data associated with this Vehicle
1069
    QObject* firmwarePluginInstanceData() { return _firmwarePluginInstanceData; }
1070 1071 1072 1073 1074

    /// 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);

1075 1076 1077 1078
    QString vehicleImageOpaque  () const;
    QString vehicleImageOutline () const;
    QString vehicleImageCompass () const;

1079
    const QVariantList&         toolBarIndicators   ();
1080
    const QVariantList&         staticCameraList    () const;
1081

1082 1083
    bool capabilitiesKnown      () const { return _vehicleCapabilitiesKnown; }
    uint64_t capabilityBits     () const { return _capabilityBits; }    // Change signalled by capabilityBitsChanged
1084

1085
    QGCCameraManager*           dynamicCameras      () { return _cameras; }
1086
    QString                     hobbsMeter          ();
1087

1088
    /// @true: When flying a mission the vehicle is always facing towards the next waypoint
1089
    bool vehicleYawsToNextWaypointInMission() const;
1090

DonLakeFlyer's avatar
DonLakeFlyer committed
1091 1092
    /// 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;
1093
    bool initialPlanRequestComplete() const { return _initialPlanRequestComplete; }
DonLakeFlyer's avatar
DonLakeFlyer committed
1094

1095
    void forceInitialPlanRequestComplete();
1096

1097 1098
    void _setFlying(bool flying);
    void _setLanding(bool landing);
DonLakeFlyer's avatar
DonLakeFlyer committed
1099
    void _setHomePosition(QGeoCoordinate& homeCoord);
1100
    void _setMaxProtoVersion (unsigned version);
DonLakeFlyer's avatar
DonLakeFlyer committed
1101

1102 1103 1104
    /// Vehicle is about to be deleted
    void prepareDelete();

1105 1106 1107 1108 1109
    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
1110 1111 1112 1113
    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; }
1114
    bool        isROIEnabled            () { return _isROIEnabled; }
Gus Grubba's avatar
Gus Grubba committed
1115

1116 1117 1118
    CheckList   checkListState          () { return _checkListState; }
    void        setCheckListState       (CheckList cl)  { _checkListState = cl; emit checkListStateChanged(); }

Gus Grubba's avatar
Gus Grubba committed
1119 1120 1121
public slots:
    void setVtolInFwdFlight             (bool vtolInFwdFlight);

1122
signals:
1123 1124 1125 1126 1127 1128 1129
    void allLinksInactive               (Vehicle* vehicle);
    void coordinateChanged              (QGeoCoordinate coordinate);
    void joystickModeChanged            (int mode);
    void joystickEnabledChanged         (bool enabled);
    void activeChanged                  (bool active);
    void mavlinkMessageReceived         (const mavlink_message_t& message);
    void homePositionChanged            (const QGeoCoordinate& homePosition);
1130
    void armedPositionChanged();
1131 1132 1133
    void armedChanged                   (bool armed);
    void flightModeChanged              (const QString& flightMode);
    void hilModeChanged                 (bool hilMode);
1134
    /** @brief HIL actuator controls (replaces HIL controls) */
1135 1136 1137 1138 1139 1140 1141 1142 1143 1144 1145 1146 1147 1148 1149 1150 1151 1152
    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);
    void connectionLostChanged          (bool connectionLost);
    void connectionLostEnabledChanged   (bool connectionLostEnabled);
    void autoDisconnectChanged          (bool autoDisconnectChanged);
    void flyingChanged                  (bool flying);
    void landingChanged                 (bool landing);
    void guidedModeChanged              (bool guidedMode);
    void vtolInFwdFlightChanged         (bool vtolInFwdFlight);
    void prearmErrorChanged             (const QString& prearmError);
    void soloFirmwareChanged            (bool soloFirmware);
    void unhealthySensorsChanged        ();
    void defaultCruiseSpeedChanged      (double cruiseSpeed);
    void defaultHoverSpeedChanged       (double hoverSpeed);
    void firmwareTypeChanged            ();
    void vehicleTypeChanged             ();
    void dynamicCamerasChanged          ();
    void hobbsMeterChanged              ();
    void capabilitiesKnownChanged       (bool capabilitiesKnown);
Don Gagne's avatar
Don Gagne committed
1153
    void initialPlanRequestCompleteChanged(bool initialPlanRequestComplete);
1154 1155 1156 1157 1158 1159 1160 1161 1162 1163 1164 1165
    void capabilityBitsChanged          (uint64_t capabilityBits);
    void toolBarIndicatorsChanged       ();
    void highLatencyLinkChanged         (bool highLatencyLink);
    void priorityLinkNameChanged        (const QString& priorityLinkName);
    void linksChanged                   ();
    void linksPropertiesChanged         ();
    void textMessageReceived            (int uasid, int componentid, int severity, QString text);
    void checkListStateChanged          ();

    void messagesReceivedChanged        ();
    void messagesSentChanged            ();
    void messagesLostChanged            ();
1166

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

1170 1171 1172 1173 1174 1175 1176 1177 1178 1179 1180 1181 1182 1183 1184 1185 1186 1187 1188 1189 1190 1191 1192 1193 1194 1195 1196 1197 1198
    void messageTypeChanged             ();
    void newMessageCountChanged         ();
    void messageCountChanged            ();
    void formatedMessagesChanged        ();
    void formatedMessageChanged         ();
    void latestErrorChanged             ();
    void longitudeChanged               ();
    void currentConfigChanged           ();
    void flowImageIndexChanged          ();
    void rcRSSIChanged                  (int rcRSSI);
    void telemetryRRSSIChanged          (int value);
    void telemetryLRSSIChanged          (int value);
    void telemetryRXErrorsChanged       (unsigned int value);
    void telemetryFixedChanged          (unsigned int value);
    void telemetryTXBufferChanged       (unsigned int value);
    void telemetryLNoiseChanged         (int value);
    void telemetryRNoiseChanged         (int value);
    void autoDisarmChanged              ();
    void flightModesChanged             ();
    void sensorsPresentBitsChanged      (int sensorsPresentBits);
    void sensorsEnabledBitsChanged      (int sensorsEnabledBits);
    void sensorsHealthBitsChanged       (int sensorsHealthBits);
    void sensorsUnhealthyBitsChanged    (int sensorsUnhealthyBits);
    void orbitActiveChanged             (bool orbitActive);

    void firmwareVersionChanged         ();
    void firmwareCustomVersionChanged   ();
    void gitHashChanged                 (QString hash);
    void vehicleUIDChanged              ();
1199

Don Gagne's avatar
Don Gagne committed
1200 1201 1202
    /// New RC channel values
    ///     @param channelCount Number of available channels, cMaxRcChannels max
    ///     @param pwmValues -1 signals channel not available
1203
    void rcChannelsChanged              (int channelCount, int pwmValues[cMaxRcChannels]);
Don Gagne's avatar
Don Gagne committed
1204 1205

    /// Remote control RSSI changed  (0% - 100%)
1206
    void remoteControlRSSIChanged       (uint8_t rssi);
Don Gagne's avatar
Don Gagne committed
1207

1208 1209 1210 1211
    void mavlinkRawImu                  (mavlink_message_t message);
    void mavlinkScaledImu1              (mavlink_message_t message);
    void mavlinkScaledImu2              (mavlink_message_t message);
    void mavlinkScaledImu3              (mavlink_message_t message);
1212

1213
    // Mavlink Log Download
1214
    void mavlinkLogData                 (Vehicle* vehicle, uint8_t target_system, uint8_t target_component, uint16_t sequence, uint8_t first_message, QByteArray data, bool acked);
1215

1216 1217 1218 1219 1220 1221
    /// 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
1222
    void mavCommandResult               (int vehicleId, int component, int command, int result, bool noReponseFromVehicle);
1223

1224
    // MAVlink Serial Data
1225
    void mavlinkSerialControl           (uint8_t device, uint8_t flags, uint16_t timeout, uint32_t baudrate, QByteArray data);
1226

1227
    // MAVLink protocol version
1228 1229
    void requestProtocolVersion         (unsigned version);
    void mavlinkStatusChanged           ();
Gus Grubba's avatar
Gus Grubba committed
1230

1231 1232 1233 1234 1235
    void gimbalRollChanged              ();
    void gimbalPitchChanged             ();
    void gimbalYawChanged               ();
    void gimbalDataChanged              ();
    void isROIEnabledChanged            ();
1236

1237
private slots:
1238 1239 1240 1241 1242 1243 1244 1245
    void _mavlinkMessageReceived        (LinkInterface* link, mavlink_message_t message);
    void _linkInactiveOrDeleted         (LinkInterface* link);
    void _sendMessageOnLink             (LinkInterface* link, mavlink_message_t message);
    void _sendMessageMultipleNext       ();
    void _parametersReady               (bool parametersReady);
    void _remoteControlRSSIChanged      (uint8_t rssi);
    void _handleFlightModeChanged       (const QString& flightMode);
    void _announceArmedChanged          (bool armed);
1246 1247 1248 1249
    void _offlineFirmwareTypeSettingChanged(QVariant value);
    void _offlineVehicleTypeSettingChanged(QVariant value);
    void _offlineCruiseSpeedSettingChanged(QVariant value);
    void _offlineHoverSpeedSettingChanged(QVariant value);
1250
    void _updateHighLatencyLink         (bool sendCommand = true);
1251

1252 1253
    void _handleTextMessage             (int newCount);
    void _handletextMessageReceived     (UASMessage* message);
dogmaphobic's avatar
dogmaphobic committed
1254
    /** @brief A new camera image has arrived */
1255 1256 1257 1258 1259 1260 1261 1262 1263 1264 1265 1266 1267 1268 1269 1270 1271 1272 1273
    void _imageReady                    (UASInterface* uas);
    void _prearmErrorTimeout            ();
    void _missionLoadComplete           ();
    void _geoFenceLoadComplete          ();
    void _rallyPointLoadComplete        ();
    void _sendMavCommandAgain           ();
    void _clearCameraTriggerPoints      ();
    void _updateDistanceHeadingToHome   ();
    void _updateHeadingToNextWP         ();
    void _updateDistanceToGCS           ();
    void _updateHobbsMeter              ();
    void _vehicleParamLoaded            (bool ready);
    void _sendQGCTimeToVehicle          ();
    void _mavlinkMessageStatus          (int uasId, uint64_t totalSent, uint64_t totalReceived, uint64_t totalLoss, float lossPercent);

    void _trafficUpdate                 (bool alert, QString traffic_id, QString vehicle_id, QGeoCoordinate location, float heading);
    void _orbitTelemetryTimeout         ();
    void _protocolVersionTimeOut        ();
    void _updateFlightTime              ();
1274

1275
private:
1276 1277 1278 1279 1280 1281 1282 1283 1284 1285 1286 1287 1288 1289 1290 1291 1292 1293 1294 1295 1296 1297 1298 1299 1300 1301 1302 1303 1304 1305 1306 1307 1308 1309 1310 1311 1312 1313 1314 1315 1316
    bool _containsLink                  (LinkInterface* link);
    void _addLink                       (LinkInterface* link);
    void _joystickChanged               (Joystick* joystick);
    void _loadSettings                  ();
    void _saveSettings                  ();
    void _startJoystick                 (bool start);
    void _handlePing                    (LinkInterface* link, mavlink_message_t& message);
    void _handleHomePosition            (mavlink_message_t& message);
    void _handleHeartbeat               (mavlink_message_t& message);
    void _handleRadioStatus             (mavlink_message_t& message);
    void _handleRCChannels              (mavlink_message_t& message);
    void _handleRCChannelsRaw           (mavlink_message_t& message);
    void _handleBatteryStatus           (mavlink_message_t& message);
    void _handleSysStatus               (mavlink_message_t& message);
    void _handleWindCov                 (mavlink_message_t& message);
    void _handleVibration               (mavlink_message_t& message);
    void _handleExtendedSysState        (mavlink_message_t& message);
    void _handleCommandAck              (mavlink_message_t& message);
    void _handleCommandLong             (mavlink_message_t& message);
    void _handleAutopilotVersion        (LinkInterface* link, mavlink_message_t& message);
    void _handleProtocolVersion         (LinkInterface* link, mavlink_message_t& message);
    void _handleHilActuatorControls     (mavlink_message_t& message);
    void _handleGpsRawInt               (mavlink_message_t& message);
    void _handleGlobalPositionInt       (mavlink_message_t& message);
    void _handleAltitude                (mavlink_message_t& message);
    void _handleVfrHud                  (mavlink_message_t& message);
    void _handleScaledPressure          (mavlink_message_t& message);
    void _handleScaledPressure2         (mavlink_message_t& message);
    void _handleScaledPressure3         (mavlink_message_t& message);
    void _handleHighLatency2            (mavlink_message_t& message);
    void _handleAttitudeWorker          (double rollRadians, double pitchRadians, double yawRadians);
    void _handleAttitude                (mavlink_message_t& message);
    void _handleAttitudeQuaternion      (mavlink_message_t& message);
    void _handleAttitudeTarget          (mavlink_message_t& message);
    void _handleDistanceSensor          (mavlink_message_t& message);
    void _handleEstimatorStatus         (mavlink_message_t& message);
    void _handleStatusText              (mavlink_message_t& message, bool longVersion);
    void _handleOrbitExecutionStatus    (const mavlink_message_t& message);
    void _handleMessageInterval         (const mavlink_message_t& message);
    void _handleGimbalOrientation       (const mavlink_message_t& message);
    void _handleObstacleDistance        (const mavlink_message_t& message);
1317 1318
    // ArduPilot dialect messages
#if !defined(NO_ARDUPILOT_DIALECT)
1319 1320
    void _handleCameraFeedback          (const mavlink_message_t& message);
    void _handleWind                    (mavlink_message_t& message);
1321
#endif
1322 1323 1324 1325 1326 1327 1328 1329 1330 1331 1332 1333 1334 1335 1336 1337 1338 1339 1340 1341 1342 1343 1344 1345 1346 1347
    void _handleCameraImageCaptured     (const mavlink_message_t& message);
    void _handleADSBVehicle             (const mavlink_message_t& message);
    void _missionManagerError           (int errorCode, const QString& errorMsg);
    void _geoFenceManagerError          (int errorCode, const QString& errorMsg);
    void _rallyPointManagerError        (int errorCode, const QString& errorMsg);
    void _linkActiveChanged             (LinkInterface* link, bool active, int vehicleID);
    void _say                           (const QString& text);
    QString _vehicleIdSpeech            ();
    void _handleMavlinkLoggingData      (mavlink_message_t& message);
    void _handleMavlinkLoggingDataAcked (mavlink_message_t& message);
    void _ackMavlinkLogData             (uint16_t sequence);
    void _sendNextQueuedMavCommand      ();
    void _updatePriorityLink            (bool updateActive, bool sendCommand);
    void _commonInit                    ();
    void _startPlanRequest              ();
    void _setupAutoDisarmSignalling     ();
    void _setCapabilities               (uint64_t capabilityBits);
    void _updateArmed                   (bool armed);
    bool _apmArmingNotRequired          ();
    void _pidTuningAdjustRates          (bool setRatesForTuning);
    void _handleUnsupportedRequestAutopilotCapabilities();
    void _handleUnsupportedRequestProtocolVersion();
    void _initializeCsv                 ();
    void _writeCsvLine                  ();
    void _flightTimerStart              ();
    void _flightTimerStop               ();
1348
    void _batteryStatusWorker           (int batteryId, double voltage, double current, double batteryRemainingPct);
Don Gagne's avatar
Don Gagne committed
1349

1350
    int     _id;                    ///< Mavlink system id
1351
    int     _defaultComponentId;
1352
    bool    _active;
1353
    bool    _offlineEditingVehicle; ///< This Vehicle is a "disconnected" vehicle for ui use while offline editing
dogmaphobic's avatar
dogmaphobic committed
1354

1355
    MAV_AUTOPILOT       _firmwareType;
1356
    MAV_TYPE            _vehicleType;
1357
    FirmwarePlugin*     _firmwarePlugin;
1358
    QObject*            _firmwarePluginInstanceData;
1359
    AutoPilotPlugin*    _autopilotPlugin;
Don Gagne's avatar
Don Gagne committed
1360
    MAVLinkProtocol*    _mavlink;
1361
    bool                _soloFirmware;
1362
    QGCToolbox*         _toolbox;
1363
    SettingsManager*    _settingsManager;
dogmaphobic's avatar
dogmaphobic committed
1364

1365 1366
    QTimer              _csvLogTimer;
    QFile               _csvLogFile;
1367

Don Gagne's avatar
Don Gagne committed
1368
    QList<LinkInterface*> _links;
dogmaphobic's avatar
dogmaphobic committed
1369

1370
    JoystickMode_t  _joystickMode;
1371
    bool            _joystickEnabled;
dogmaphobic's avatar
dogmaphobic committed
1372

1373
    UAS* _uas;
dogmaphobic's avatar
dogmaphobic committed
1374

1375
    QGeoCoordinate  _coordinate;
1376
    QGeoCoordinate  _homePosition;
1377
    QGeoCoordinate  _armedPosition;
dogmaphobic's avatar
dogmaphobic committed
1378

1379 1380 1381 1382 1383 1384 1385 1386 1387
    UASInterface*   _mav;
    int             _currentMessageCount;
    int             _messageCount;
    int             _currentErrorCount;
    int             _currentWarningCount;
    int             _currentNormalCount;
    MessageType_t   _currentMessageType;
    QString         _latestError;
    int             _updateCount;
dogmaphobic's avatar
dogmaphobic committed
1388
    QString         _formatedMessage;
Don Gagne's avatar
Don Gagne committed
1389 1390
    int             _rcRSSI;
    double          _rcRSSIstore;
Don Gagne's avatar
Don Gagne committed
1391
    bool            _autoDisconnect;    ///< true: Automatically disconnect vehicle when last connection goes away or lost heartbeat
Don Gagne's avatar
Don Gagne committed
1392
    bool            _flying;
1393
    bool            _landing;
1394
    bool            _vtolInFwdFlight;
1395 1396 1397 1398
    uint32_t        _onboardControlSensorsPresent;
    uint32_t        _onboardControlSensorsEnabled;
    uint32_t        _onboardControlSensorsHealth;
    uint32_t        _onboardControlSensorsUnhealthy;
1399 1400
    bool            _gpsRawIntMessageAvailable;
    bool            _globalPositionIntMessageAvailable;
DonLakeFlyer's avatar
DonLakeFlyer committed
1401 1402
    double          _defaultCruiseSpeed;
    double          _defaultHoverSpeed;
Gus Grubba's avatar
Gus Grubba committed
1403 1404 1405 1406 1407
    int             _telemetryRRSSI;
    int             _telemetryLRSSI;
    uint32_t        _telemetryRXErrors;
    uint32_t        _telemetryFixed;
    uint32_t        _telemetryTXBuffer;
1408 1409
    int             _telemetryLNoise;
    int             _telemetryRNoise;
1410
    bool            _mavlinkProtocolRequestComplete;
1411
    unsigned        _maxProtoVersion;
1412
    bool            _vehicleCapabilitiesKnown;
1413
    uint64_t        _capabilityBits;
1414
    bool            _highLatencyLink;
1415
    bool            _receivingAttitudeQuaternion;
1416
    CheckList       _checkListState = CheckListNotSetup;
dogmaphobic's avatar
dogmaphobic committed
1417

1418 1419
    QGCCameraManager* _cameras;

1420
    typedef struct {
1421 1422 1423 1424 1425 1426
        int         component;
        bool        commandInt; // true: use COMMAND_INT, false: use COMMAND_LONG
        MAV_CMD     command;
        MAV_FRAME   frame;
        double      rgParam[7];
        bool        showError;
1427 1428 1429 1430 1431 1432
    } MavCommandQueueEntry_t;

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

Don Gagne's avatar
Don Gagne committed
1436 1437 1438 1439
    QString             _prearmError;
    QTimer              _prearmErrorTimer;
    static const int    _prearmErrorTimeoutMSecs = 35 * 1000;   ///< Take away prearm error after 35 seconds

1440 1441 1442 1443
    // Lost connection handling
    bool                _connectionLost;
    bool                _connectionLostEnabled;

DonLakeFlyer's avatar
DonLakeFlyer committed
1444 1445
    bool                _initialPlanRequestComplete;

Don Gagne's avatar
Don Gagne committed
1446
    MissionManager*     _missionManager;
1447
    bool                _missionManagerInitialRequestSent;
1448

1449
    GeoFenceManager*    _geoFenceManager;
1450 1451 1452 1453
    bool                _geoFenceManagerInitialRequestSent;

    RallyPointManager*  _rallyPointManager;
    bool                _rallyPointManagerInitialRequestSent;
1454

Gus Grubba's avatar
Gus Grubba committed
1455 1456
    ParameterManager*       _parameterManager   = nullptr;
    VehicleObjectAvoidance* _objectAvoidance    = nullptr;
1457

1458
#if defined(QGC_AIRMAP_ENABLED)
1459
    AirspaceVehicleManager* _airspaceVehicleManager;
1460
#endif
dogmaphobic's avatar
dogmaphobic committed
1461

Don Gagne's avatar
Don Gagne committed
1462 1463 1464
    bool    _armed;         ///< true: vehicle is armed
    uint8_t _base_mode;     ///< base_mode from HEARTBEAT
    uint32_t _custom_mode;  ///< custom_mode from HEARTBEAT
1465 1466 1467 1468 1469 1470

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

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

1474 1475
    static const int _sendMessageMultipleRetries = 5;
    static const int _sendMessageMultipleIntraMessageDelay = 500;
dogmaphobic's avatar
dogmaphobic committed
1476

1477 1478
    QTimer  _sendMultipleTimer;
    int     _nextSendMessageMultipleIndex;
dogmaphobic's avatar
dogmaphobic committed
1479

1480
    QTime                           _flightTimer;
DonLakeFlyer's avatar
DonLakeFlyer committed
1481
    QTimer                          _flightTimeUpdater;
1482 1483
    TrajectoryPoints*               _trajectoryPoints;
    QmlObjectListModel              _cameraTriggerPoints;
1484
    //QMap<QString, ADSBVehicle*>     _trafficVehicleMap;
1485

1486
    // Toolbox references
dogmaphobic's avatar
dogmaphobic committed
1487 1488 1489 1490 1491
    FirmwarePluginManager*      _firmwarePluginManager;
    JoystickManager*            _joystickManager;

    int                         _flowImageIndex;

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

1494 1495 1496 1497 1498 1499 1500
    uint                _messagesReceived;
    uint                _messagesSent;
    uint                _messagesLost;
    uint8_t             _messageSeq;
    uint8_t             _compID;
    bool                _heardFrom;

Gus Grubba's avatar
Gus Grubba committed
1501 1502 1503 1504
    float               _curGimbalRoll  = 0.0f;
    float               _curGimbalPitch = 0.0f;
    float               _curGinmbalYaw  = 0.0f;
    bool                _haveGimbalData = false;
1505
    bool                _isROIEnabled   = false;
Gus Grubba's avatar
Gus Grubba committed
1506 1507
    Joystick*           _activeJoystick = nullptr;

Don Gagne's avatar
Don Gagne committed
1508 1509 1510
    int _firmwareMajorVersion;
    int _firmwareMinorVersion;
    int _firmwarePatchVersion;
1511 1512 1513
    int _firmwareCustomMajorVersion;
    int _firmwareCustomMinorVersion;
    int _firmwareCustomPatchVersion;
1514
    FIRMWARE_VERSION_TYPE _firmwareVersionType;
Don Gagne's avatar
Don Gagne committed
1515

1516
    QString _gitHash;
Gus Grubba's avatar
Gus Grubba committed
1517
    quint64 _uid;
1518

1519
    QElapsedTimer   _lastBatteryAnnouncement;
1520
    int     _lastAnnouncedLowBatteryPercent;
1521

1522
    SharedLinkInterfacePointer _priorityLink;  // We always keep a reference to the priority link to manage shutdown ordering
1523
    bool _priorityLinkCommanded;
1524

1525 1526 1527 1528 1529
    uint64_t    _mavlinkSentCount       = 0;
    uint64_t    _mavlinkReceivedCount   = 0;
    uint64_t    _mavlinkLossCount       = 0;
    float       _mavlinkLossPercent     = 0.0f;

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

1532 1533 1534 1535 1536 1537
    // Orbit status values
    bool            _orbitActive;
    QGCMapCircle    _orbitMapCircle;
    QTimer          _orbitTelemetryTimer;
    static const int _orbitTelemetryTimeoutMsecs = 3000; // No telemetry for this amount and orbit will go inactive

1538 1539 1540 1541 1542 1543
    // PID Tuning telemetry mode
    bool            _pidTuningTelemetryMode;
    bool            _pidTuningWaitingForRates;
    QList<int>      _pidTuningMessages;
    QMap<int, int>  _pidTuningMessageRatesUsecs;

Don Gagne's avatar
Don Gagne committed
1544 1545 1546 1547 1548
    // FactGroup facts

    Fact _rollFact;
    Fact _pitchFact;
    Fact _headingFact;
DonLakeFlyer's avatar
DonLakeFlyer committed
1549 1550 1551
    Fact _rollRateFact;
    Fact _pitchRateFact;
    Fact _yawRateFact;
Don Gagne's avatar
Don Gagne committed
1552 1553 1554 1555 1556
    Fact _groundSpeedFact;
    Fact _airSpeedFact;
    Fact _climbRateFact;
    Fact _altitudeRelativeFact;
    Fact _altitudeAMSLFact;
1557
    Fact _flightDistanceFact;
1558
    Fact _flightTimeFact;
1559
    Fact _distanceToHomeFact;
1560
    Fact _headingToNextWPFact;
1561
    Fact _headingToHomeFact;
1562
    Fact _distanceToGCSFact;
1563
    Fact _hobbsFact;
1564
    Fact _throttlePctFact;
Don Gagne's avatar
Don Gagne committed
1565

1566
    VehicleGPSFactGroup             _gpsFactGroup;
DonLakeFlyer's avatar
DonLakeFlyer committed
1567 1568
    VehicleBatteryFactGroup         _battery1FactGroup;
    VehicleBatteryFactGroup         _battery2FactGroup;
1569 1570 1571 1572 1573 1574
    VehicleWindFactGroup            _windFactGroup;
    VehicleVibrationFactGroup       _vibrationFactGroup;
    VehicleTemperatureFactGroup     _temperatureFactGroup;
    VehicleClockFactGroup           _clockFactGroup;
    VehicleSetpointFactGroup        _setpointFactGroup;
    VehicleDistanceSensorFactGroup  _distanceSensorFactGroup;
1575
    VehicleEstimatorStatusFactGroup _estimatorStatusFactGroup;
Don Gagne's avatar
Don Gagne committed
1576 1577 1578 1579

    static const char* _rollFactName;
    static const char* _pitchFactName;
    static const char* _headingFactName;
DonLakeFlyer's avatar
DonLakeFlyer committed
1580 1581 1582
    static const char* _rollRateFactName;
    static const char* _pitchRateFactName;
    static const char* _yawRateFactName;
Don Gagne's avatar
Don Gagne committed
1583 1584 1585 1586 1587
    static const char* _groundSpeedFactName;
    static const char* _airSpeedFactName;
    static const char* _climbRateFactName;
    static const char* _altitudeRelativeFactName;
    static const char* _altitudeAMSLFactName;
1588
    static const char* _flightDistanceFactName;
1589
    static const char* _flightTimeFactName;
1590
    static const char* _distanceToHomeFactName;
1591
    static const char* _headingToNextWPFactName;
1592
    static const char* _headingToHomeFactName;
1593
    static const char* _distanceToGCSFactName;
1594
    static const char* _hobbsFactName;
1595
    static const char* _throttlePctFactName;
Don Gagne's avatar
Don Gagne committed
1596

Don Gagne's avatar
Don Gagne committed
1597
    static const char* _gpsFactGroupName;
DonLakeFlyer's avatar
DonLakeFlyer committed
1598 1599
    static const char* _battery1FactGroupName;
    static const char* _battery2FactGroupName;
Don Gagne's avatar
Don Gagne committed
1600
    static const char* _windFactGroupName;
1601
    static const char* _vibrationFactGroupName;
1602
    static const char* _temperatureFactGroupName;
dheideman's avatar
dheideman committed
1603
    static const char* _clockFactGroupName;
1604
    static const char* _distanceSensorFactGroupName;
1605
    static const char* _estimatorStatusFactGroupName;
Don Gagne's avatar
Don Gagne committed
1606 1607 1608

    static const int _vehicleUIUpdateRateMSecs = 100;

1609
    // Settings keys
1610 1611
    static const char* _settingsGroup;
    static const char* _joystickModeSettingsKey;
1612
    static const char* _joystickEnabledSettingsKey;
Don Gagne's avatar
Don Gagne committed
1613

1614
};