Vehicle.h 86.8 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 13 14
// Ignore warnings from mavlink headers for both GCC/Clang and MSVC
#ifdef __GNUC__

15 16 17
#if __GNUC__ > 8
#pragma GCC diagnostic push
#pragma GCC diagnostic ignored "-Waddress-of-packed-member"
18 19 20 21 22 23 24 25 26 27
#elif defined(__clang__)
#pragma clang diagnostic push
#pragma clang diagnostic ignored "-Waddress-of-packed-member"
#else
#pragma GCC diagnostic push
#pragma GCC diagnostic ignored "-Wall"
#endif

#else
#pragma warning(push, 0)
28 29
#endif

30
#include <QElapsedTimer>
31
#include <QObject>
32
#include <QVariantList>
33
#include <QGeoCoordinate>
34
#include <QTime>
35

Don Gagne's avatar
Don Gagne committed
36
#include "FactGroup.h"
37 38
#include "LinkInterface.h"
#include "QGCMAVLink.h"
39
#include "QmlObjectListModel.h"
Don Gagne's avatar
Don Gagne committed
40
#include "MAVLinkProtocol.h"
dogmaphobic's avatar
dogmaphobic committed
41
#include "UASMessageHandler.h"
42
#include "SettingsFact.h"
43
#include "QGCMapCircle.h"
44
#include "TerrainFactGroup.h"
45

46 47
class UAS;
class UASInterface;
48
class FirmwarePlugin;
49
class FirmwarePluginManager;
50
class AutoPilotPlugin;
Don Gagne's avatar
Don Gagne committed
51
class MissionManager;
52
class GeoFenceManager;
53
class RallyPointManager;
54
class ParameterManager;
55
class JoystickManager;
dogmaphobic's avatar
dogmaphobic committed
56
class UASMessage;
57
class SettingsManager;
58
class QGCCameraManager;
Gus Grubba's avatar
Gus Grubba committed
59
class Joystick;
Gus Grubba's avatar
Gus Grubba committed
60
class VehicleObjectAvoidance;
61
class TrajectoryPoints;
62
class TerrainProtocolHandler;
Gus Grubba's avatar
Gus Grubba committed
63

64 65 66
#if defined(QGC_AIRMAP_ENABLED)
class AirspaceVehicleManager;
#endif
67 68 69

Q_DECLARE_LOGGING_CATEGORY(VehicleLog)

Don Gagne's avatar
Don Gagne committed
70 71
class Vehicle;

72 73 74 75 76
class VehicleDistanceSensorFactGroup : public FactGroup
{
    Q_OBJECT

public:
77
    VehicleDistanceSensorFactGroup(QObject* parent = nullptr);
78

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

90 91 92 93 94 95 96 97 98 99
    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; }
100

101
    static const char* _rotationNoneFactName;
102
    static const char* _rotationYaw45FactName;
103
    static const char* _rotationYaw90FactName;
104
    static const char* _rotationYaw135FactName;
105
    static const char* _rotationYaw180FactName;
106
    static const char* _rotationYaw225FactName;
107
    static const char* _rotationYaw270FactName;
108 109 110
    static const char* _rotationYaw315FactName;
    static const char* _rotationPitch90FactName;
    static const char* _rotationPitch270FactName;
111 112 113

private:
    Fact _rotationNoneFact;
114
    Fact _rotationYaw45Fact;
115
    Fact _rotationYaw90Fact;
116
    Fact _rotationYaw135Fact;
117
    Fact _rotationYaw180Fact;
118
    Fact _rotationYaw225Fact;
119
    Fact _rotationYaw270Fact;
120 121 122
    Fact _rotationYaw315Fact;
    Fact _rotationPitch90Fact;
    Fact _rotationPitch270Fact;
123 124
};

DonLakeFlyer's avatar
DonLakeFlyer committed
125 126 127 128 129
class VehicleSetpointFactGroup : public FactGroup
{
    Q_OBJECT

public:
130
    VehicleSetpointFactGroup(QObject* parent = nullptr);
DonLakeFlyer's avatar
DonLakeFlyer committed
131 132 133 134 135 136 137 138

    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)

139 140 141 142 143 144
    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
145 146 147 148 149 150 151 152 153 154 155 156 157 158 159 160 161

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

162 163 164 165 166
class VehicleVibrationFactGroup : public FactGroup
{
    Q_OBJECT

public:
167
    VehicleVibrationFactGroup(QObject* parent = nullptr);
168 169 170 171 172 173 174 175

    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)

176 177 178 179 180 181
    Fact* xAxis         () { return &_xAxisFact; }
    Fact* yAxis         () { return &_yAxisFact; }
    Fact* zAxis         () { return &_zAxisFact; }
    Fact* clipCount1    () { return &_clipCount1Fact; }
    Fact* clipCount2    () { return &_clipCount2Fact; }
    Fact* clipCount3    () { return &_clipCount3Fact; }
182 183 184 185 186 187 188 189 190 191 192 193 194 195 196 197 198

    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
199 200 201 202 203
class VehicleWindFactGroup : public FactGroup
{
    Q_OBJECT

public:
204
    VehicleWindFactGroup(QObject* parent = nullptr);
Don Gagne's avatar
Don Gagne committed
205 206 207 208 209

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

210 211 212
    Fact* direction     () { return &_directionFact; }
    Fact* speed         () { return &_speedFact; }
    Fact* verticalSpeed () { return &_verticalSpeedFact; }
Don Gagne's avatar
Don Gagne committed
213 214 215 216 217 218 219 220 221 222 223

    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
224 225 226 227 228
class VehicleGPSFactGroup : public FactGroup
{
    Q_OBJECT

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

231 232
    Q_PROPERTY(Fact* lat                READ lat                CONSTANT)
    Q_PROPERTY(Fact* lon                READ lon                CONSTANT)
233
    Q_PROPERTY(Fact* mgrs               READ mgrs               CONSTANT)
Don Gagne's avatar
Don Gagne committed
234 235 236 237 238 239
    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)

240 241 242 243 244 245 246 247
    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
248

249 250
    static const char* _latFactName;
    static const char* _lonFactName;
251
    static const char* _mgrsFactName;
Don Gagne's avatar
Don Gagne committed
252 253 254 255 256 257
    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
258
private:
259 260
    Fact        _latFact;
    Fact        _lonFact;
261
    Fact        _mgrsFact;
Don Gagne's avatar
Don Gagne committed
262 263 264 265 266
    Fact        _hdopFact;
    Fact        _vdopFact;
    Fact        _courseOverGroundFact;
    Fact        _countFact;
    Fact        _lockFact;
Don Gagne's avatar
Don Gagne committed
267
};
Don Gagne's avatar
Don Gagne committed
268

Don Gagne's avatar
Don Gagne committed
269 270 271 272 273
class VehicleBatteryFactGroup : public FactGroup
{
    Q_OBJECT

public:
274
    VehicleBatteryFactGroup(QObject* parent = nullptr);
Don Gagne's avatar
Don Gagne committed
275 276 277 278 279 280

    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)
281
    Q_PROPERTY(Fact* instantPower       READ instantPower       CONSTANT)
282 283
    Q_PROPERTY(Fact* timeRemaining      READ timeRemaining      CONSTANT)
    Q_PROPERTY(Fact* chargeState        READ chargeState        CONSTANT)
284

285 286 287 288 289 290 291 292
    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
293 294 295 296 297 298

    static const char* _voltageFactName;
    static const char* _percentRemainingFactName;
    static const char* _mahConsumedFactName;
    static const char* _currentFactName;
    static const char* _temperatureFactName;
299
    static const char* _instantPowerFactName;
300 301
    static const char* _timeRemainingFactName;
    static const char* _chargeStateFactName;
Don Gagne's avatar
Don Gagne committed
302

303 304
    static const char* _settingsGroup;

Don Gagne's avatar
Don Gagne committed
305
private:
306 307 308 309 310
    Fact            _voltageFact;
    Fact            _percentRemainingFact;
    Fact            _mahConsumedFact;
    Fact            _currentFact;
    Fact            _temperatureFact;
311
    Fact            _instantPowerFact;
312 313
    Fact            _timeRemainingFact;
    Fact            _chargeStateFact;
Don Gagne's avatar
Don Gagne committed
314 315
};

316 317 318 319 320
class VehicleTemperatureFactGroup : public FactGroup
{
    Q_OBJECT

public:
321
    VehicleTemperatureFactGroup(QObject* parent = nullptr);
322 323 324 325 326

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

327 328 329
    Fact* temperature1 () { return &_temperature1Fact; }
    Fact* temperature2 () { return &_temperature2Fact; }
    Fact* temperature3 () { return &_temperature3Fact; }
330 331 332 333 334 335 336 337 338 339 340 341 342 343 344

    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
345 346 347 348 349
class VehicleClockFactGroup : public FactGroup
{
    Q_OBJECT

public:
350
    VehicleClockFactGroup(QObject* parent = nullptr);
dheideman's avatar
dheideman committed
351 352 353 354

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

355 356
    Fact* currentTime () { return &_currentTimeFact; }
    Fact* currentDate () { return &_currentDateFact; }
dheideman's avatar
dheideman committed
357 358 359 360 361 362 363

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

    static const char* _settingsGroup;

private slots:
364
    void _updateAllValues() override;
dheideman's avatar
dheideman committed
365 366 367 368 369 370

private:
    Fact            _currentTimeFact;
    Fact            _currentDateFact;
};

371 372 373 374 375 376 377 378 379 380 381 382 383 384 385 386 387 388 389 390 391 392 393 394 395 396 397 398
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)

399 400 401 402 403 404 405 406 407 408 409 410 411 412 413 414 415 416 417 418
    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; }
419 420 421 422 423 424 425 426 427 428 429 430 431 432 433 434 435 436 437 438 439 440 441 442 443 444 445 446 447 448 449 450 451 452 453 454 455 456 457 458 459 460 461 462 463 464 465 466 467 468 469 470 471 472 473 474 475 476 477 478 479 480 481 482 483 484 485 486 487 488 489

    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.*/
490 491
        } mavlink_estimator_status_t;
    };
492 493 494
#endif
};

Don Gagne's avatar
Don Gagne committed
495
class Vehicle : public FactGroup
496 497
{
    Q_OBJECT
dogmaphobic's avatar
dogmaphobic committed
498

499
public:
500 501
    Vehicle(LinkInterface*          link,
            int                     vehicleId,
502
            int                     defaultComponentId,
503 504 505 506
            MAV_AUTOPILOT           firmwareType,
            MAV_TYPE                vehicleType,
            FirmwarePluginManager*  firmwarePluginManager,
            JoystickManager*        joystickManager);
507

508 509 510 511
    // The following is used to create a disconnected Vehicle for use while offline editing.
    Vehicle(MAV_AUTOPILOT           firmwareType,
            MAV_TYPE                vehicleType,
            FirmwarePluginManager*  firmwarePluginManager,
512
            QObject*                parent = nullptr);
513

514
    ~Vehicle();
dogmaphobic's avatar
dogmaphobic committed
515

516 517 518 519 520
    /// 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,
521
        SysStatusSensorAbsolutePressure =       MAV_SYS_STATUS_SENSOR_ABSOLUTE_PRESSURE,
522 523 524 525 526 527 528 529 530 531 532 533 534 535 536 537 538 539 540 541 542 543 544 545 546
        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)

547 548 549 550 551 552 553
    enum CheckList {
        CheckListNotSetup = 0,
        CheckListPassed,
        CheckListFailed,
    };
    Q_ENUM(CheckList)

554 555 556 557
    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)
558
    Q_PROPERTY(QGeoCoordinate       armedPosition           READ armedPosition                                          NOTIFY armedPositionChanged)
559
    Q_PROPERTY(bool                 armed                   READ armed                  WRITE setArmed                  NOTIFY armedChanged)
560
    Q_PROPERTY(bool                 autoDisarm              READ autoDisarm                                             NOTIFY autoDisarmChanged)
561
    Q_PROPERTY(bool                 flightModeSetAvailable  READ flightModeSetAvailable                                 CONSTANT)
562
    Q_PROPERTY(QStringList          flightModes             READ flightModes                                            NOTIFY flightModesChanged)
563
    Q_PROPERTY(QStringList          extraJoystickFlightModes READ extraJoystickFlightModes                              NOTIFY flightModesChanged)
564
    Q_PROPERTY(QString              flightMode              READ flightMode             WRITE setFlightMode             NOTIFY flightModeChanged)
565
    Q_PROPERTY(TrajectoryPoints*    trajectoryPoints        MEMBER _trajectoryPoints                                    CONSTANT)
566
    Q_PROPERTY(QmlObjectListModel*  cameraTriggerPoints     READ cameraTriggerPoints                                    CONSTANT)
567 568 569 570 571 572 573 574 575 576 577 578 579 580 581 582 583
    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)
584 585
    Q_PROPERTY(bool                 px4Firmware             READ px4Firmware                                            NOTIFY firmwareTypeChanged)
    Q_PROPERTY(bool                 apmFirmware             READ apmFirmware                                            NOTIFY firmwareTypeChanged)
586 587 588 589 590 591 592
    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)
593 594 595 596 597
    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)
598
    Q_PROPERTY(bool        supportsThrottleModeCenterZero   READ supportsThrottleModeCenterZero                         CONSTANT)
599
    Q_PROPERTY(bool                supportsNegativeThrust   READ supportsNegativeThrust                                 CONSTANT)
600
    Q_PROPERTY(bool                 supportsJSButton        READ supportsJSButton                                       CONSTANT)
601
    Q_PROPERTY(bool                 supportsRadio           READ supportsRadio                                          CONSTANT)
602
    Q_PROPERTY(bool               supportsMotorInterference READ supportsMotorInterference                              CONSTANT)
603 604
    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
605 606 607
    Q_PROPERTY(int                  motorCount              READ motorCount                                             CONSTANT)
    Q_PROPERTY(bool                 coaxialMotors           READ coaxialMotors                                          CONSTANT)
    Q_PROPERTY(bool                 xConfigMotors           READ xConfigMotors                                          CONSTANT)
608
    Q_PROPERTY(bool                 isOfflineEditingVehicle READ isOfflineEditingVehicle                                CONSTANT)
609 610
    Q_PROPERTY(QString              brandImageIndoor        READ brandImageIndoor                                       NOTIFY firmwareTypeChanged)
    Q_PROPERTY(QString              brandImageOutdoor       READ brandImageOutdoor                                      NOTIFY firmwareTypeChanged)
611
    Q_PROPERTY(QStringList          unhealthySensors        READ unhealthySensors                                       NOTIFY unhealthySensorsChanged)
612 613 614
    Q_PROPERTY(int                  sensorsPresentBits      READ sensorsPresentBits                                     NOTIFY sensorsPresentBitsChanged)
    Q_PROPERTY(int                  sensorsEnabledBits      READ sensorsEnabledBits                                     NOTIFY sensorsEnabledBitsChanged)
    Q_PROPERTY(int                  sensorsHealthBits       READ sensorsHealthBits                                      NOTIFY sensorsHealthBitsChanged)
615
    Q_PROPERTY(int                  sensorsUnhealthyBits    READ sensorsUnhealthyBits                                   NOTIFY sensorsUnhealthyBitsChanged) ///< Combination of enabled and health
616
    Q_PROPERTY(QString              missionFlightMode       READ missionFlightMode                                      CONSTANT)
617
    Q_PROPERTY(QString              pauseFlightMode         READ pauseFlightMode                                        CONSTANT)
618
    Q_PROPERTY(QString              rtlFlightMode           READ rtlFlightMode                                          CONSTANT)
DonLakeFlyer's avatar
DonLakeFlyer committed
619 620
    Q_PROPERTY(QString              smartRTLFlightMode      READ smartRTLFlightMode                                     CONSTANT)
    Q_PROPERTY(bool                 supportsSmartRTL        READ supportsSmartRTL                                       CONSTANT)
621
    Q_PROPERTY(QString              landFlightMode          READ landFlightMode                                         CONSTANT)
622
    Q_PROPERTY(QString              takeControlFlightMode   READ takeControlFlightMode                                  CONSTANT)
623
    Q_PROPERTY(QString              followFlightMode        READ followFlightMode                                       CONSTANT)
624 625
    Q_PROPERTY(QString              firmwareTypeString      READ firmwareTypeString                                     NOTIFY firmwareTypeChanged)
    Q_PROPERTY(QString              vehicleTypeString       READ vehicleTypeString                                      NOTIFY vehicleTypeChanged)
626 627 628
    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
629 630 631 632 633
    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)
634 635
    Q_PROPERTY(int                  telemetryLNoise         READ telemetryLNoise                                        NOTIFY telemetryLNoiseChanged)
    Q_PROPERTY(int                  telemetryRNoise         READ telemetryRNoise                                        NOTIFY telemetryRNoiseChanged)
636 637
    Q_PROPERTY(QVariantList         toolIndicators          READ toolIndicators                                         NOTIFY toolIndicatorsChanged)
    Q_PROPERTY(QVariantList         modeIndicators          READ modeIndicators                                         NOTIFY modeIndicatorsChanged)
Don Gagne's avatar
Don Gagne committed
638
    Q_PROPERTY(bool              initialPlanRequestComplete READ initialPlanRequestComplete                             NOTIFY initialPlanRequestCompleteChanged)
Gus Grubba's avatar
Gus Grubba committed
639
    Q_PROPERTY(QVariantList         staticCameraList        READ staticCameraList                                       CONSTANT)
640
    Q_PROPERTY(QGCCameraManager*    dynamicCameras          READ dynamicCameras                                         NOTIFY dynamicCamerasChanged)
641
    Q_PROPERTY(QString              hobbsMeter              READ hobbsMeter                                             NOTIFY hobbsMeterChanged)
642
    Q_PROPERTY(bool                 vtolInFwdFlight         READ vtolInFwdFlight        WRITE setVtolInFwdFlight        NOTIFY vtolInFwdFlightChanged)
643
    Q_PROPERTY(bool                 highLatencyLink         READ highLatencyLink                                        NOTIFY highLatencyLinkChanged)
644
    Q_PROPERTY(bool                 supportsTerrainFrame    READ supportsTerrainFrame                                   NOTIFY capabilityBitsChanged)
645
    Q_PROPERTY(QString              priorityLinkName        READ priorityLinkName       WRITE setPriorityLinkByName     NOTIFY priorityLinkNameChanged)
646
    Q_PROPERTY(QVariantList         links                   READ links                                                  NOTIFY linksChanged)
647
    Q_PROPERTY(LinkInterface*       priorityLink            READ priorityLink                                           NOTIFY priorityLinkNameChanged)
648 649 650 651
    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
652 653 654 655
    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)
656
    Q_PROPERTY(bool                 isROIEnabled            READ isROIEnabled                                           NOTIFY isROIEnabledChanged)
657
    Q_PROPERTY(CheckList            checkListState          READ checkListState         WRITE setCheckListState         NOTIFY checkListStateChanged)
658

659 660 661 662
    // The following properties relate to Orbit status
    Q_PROPERTY(bool             orbitActive     READ orbitActive        NOTIFY orbitActiveChanged)
    Q_PROPERTY(QGCMapCircle*    orbitMapCircle  READ orbitMapCircle     CONSTANT)

663
    // Vehicle state used for guided control
Don Gagne's avatar
Don Gagne committed
664 665 666 667 668 669
    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
670
    Q_PROPERTY(bool     roiModeSupported        READ roiModeSupported                               CONSTANT)                   ///< Orbit mode is supported by this vehicle
Don Gagne's avatar
Don Gagne committed
671 672
    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
673

Gus Grubba's avatar
Gus Grubba committed
674 675
    Q_PROPERTY(ParameterManager*        parameterManager    READ parameterManager   CONSTANT)
    Q_PROPERTY(VehicleObjectAvoidance*  objectAvoidance     READ objectAvoidance    CONSTANT)
676

Don Gagne's avatar
Don Gagne committed
677 678 679 680 681
    // 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
682 683 684
    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
685 686 687 688 689
    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)
690
    Q_PROPERTY(Fact* flightDistance     READ flightDistance     CONSTANT)
691
    Q_PROPERTY(Fact* distanceToHome     READ distanceToHome     CONSTANT)
692
    Q_PROPERTY(Fact* missionItemIndex   READ missionItemIndex   CONSTANT)
693
    Q_PROPERTY(Fact* headingToNextWP    READ headingToNextWP    CONSTANT)
694
    Q_PROPERTY(Fact* headingToHome      READ headingToHome      CONSTANT)
695
    Q_PROPERTY(Fact* distanceToGCS      READ distanceToGCS      CONSTANT)
696
    Q_PROPERTY(Fact* hobbs              READ hobbs              CONSTANT)
697
    Q_PROPERTY(Fact* throttlePct        READ throttlePct        CONSTANT)
Don Gagne's avatar
Don Gagne committed
698

699 700 701 702 703 704 705 706 707
    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)
708
    Q_PROPERTY(FactGroup* terrain           READ terrainFactGroup           CONSTANT)
Don Gagne's avatar
Don Gagne committed
709

710 711 712 713 714 715 716 717 718
    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
719 720
    Q_PROPERTY(quint64  vehicleUID                  READ vehicleUID                 NOTIFY vehicleUIDChanged)
    Q_PROPERTY(QString  vehicleUIDStr               READ vehicleUIDStr              NOTIFY vehicleUIDChanged)
721

722 723
    /// Resets link status counters
    Q_INVOKABLE void resetCounters  ();
724

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

Gus Grubba's avatar
Gus Grubba committed
728
    Q_INVOKABLE void virtualTabletJoystickValue(double roll, double pitch, double yaw, double thrust);
729
    Q_INVOKABLE void disconnectInactiveVehicle();
Don Gagne's avatar
Don Gagne committed
730

Don Gagne's avatar
Don Gagne committed
731
    /// Command vehicle to return to launch
DonLakeFlyer's avatar
DonLakeFlyer committed
732
    Q_INVOKABLE void guidedModeRTL(bool smartRTL);
Don Gagne's avatar
Don Gagne committed
733 734

    /// Command vehicle to land at current location
735
    Q_INVOKABLE void guidedModeLand();
Don Gagne's avatar
Don Gagne committed
736 737

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

740
    /// @return The minimum takeoff altitude (relative) for guided takeoff.
741
    Q_INVOKABLE double minimumTakeoffAltitude();
742

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

746 747 748
    /// 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
749

750
    /// Command vehicle to orbit given center point
DonLakeFlyer's avatar
DonLakeFlyer committed
751
    ///     @param centerCoord Orit around this point
752
    ///     @param radius Distance from vehicle to centerCoord
DonLakeFlyer's avatar
DonLakeFlyer committed
753 754
    ///     @param amslAltitude Desired vehicle altitude
    Q_INVOKABLE void guidedModeOrbit(const QGeoCoordinate& centerCoord, double radius, double amslAltitude);
755

Gus Grubba's avatar
Gus Grubba committed
756 757 758
    /// Command vehicle to keep given point as ROI
    ///     @param centerCoord ROI coordinates
    Q_INVOKABLE void guidedModeROI(const QGeoCoordinate& centerCoord);
759
    Q_INVOKABLE void stopGuidedModeROI();
Gus Grubba's avatar
Gus Grubba committed
760

Don Gagne's avatar
Don Gagne committed
761 762
    /// Command vehicle to pause at current location. If vehicle supports guide mode, vehicle will be left
    /// in guided mode after pause.
763
    Q_INVOKABLE void pauseVehicle();
Don Gagne's avatar
Don Gagne committed
764 765

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

768
    /// Command vehicle to abort landing
769
    Q_INVOKABLE void abortLanding(double climbOutAltitude);
770

771
    Q_INVOKABLE void startMission();
772

773 774 775
    /// Alter the current mission item on the vehicle
    Q_INVOKABLE void setCurrentMissionSequence(int seq);

776 777 778
    /// Reboot vehicle
    Q_INVOKABLE void rebootVehicle();

dogmaphobic's avatar
dogmaphobic committed
779 780 781
    /// Clear Messages
    Q_INVOKABLE void clearMessages();

782
    Q_INVOKABLE void triggerCamera();
Don Gagne's avatar
Don Gagne committed
783
    Q_INVOKABLE void sendPlan(QString planFile);
Don Gagne's avatar
Don Gagne committed
784

785 786 787 788 789
    /// 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
790 791 792
    /// Test motor
    ///     @param motor Motor number, 1-based
    ///     @param percent 0-no power, 100-full power
793 794
    ///     @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
795

Don Gagne's avatar
Don Gagne committed
796 797
    Q_INVOKABLE void setPIDTuningTelemetryMode(bool pidTuning);

Gus Grubba's avatar
Gus Grubba committed
798 799 800 801
    Q_INVOKABLE void gimbalControlValue (double pitch, double yaw);
    Q_INVOKABLE void gimbalPitchStep    (int direction);
    Q_INVOKABLE void gimbalYawStep      (int direction);
    Q_INVOKABLE void centerGimbal       ();
802

DoinLakeFlyer's avatar
DoinLakeFlyer committed
803 804 805 806 807 808 809
    /// Sends PARAM_MAP_RC message to vehicle
    Q_INVOKABLE void sendParamMapRC(const QString& paramName, double scale, double centerValue, int tuningID, double minValue, double maxValue);

    /// Clears all PARAM_MAP_RC settings from vehicle
    Q_INVOKABLE void clearAllParamMapRC(void);


810
#if !defined(NO_ARDUPILOT_DIALECT)
811
    Q_INVOKABLE void flashBootloader();
812 813
#endif

814 815 816 817 818 819
    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
820

821
    // Property accessors
Don Gagne's avatar
Don Gagne committed
822

823 824
    QGeoCoordinate coordinate() { return _coordinate; }
    QGeoCoordinate armedPosition    () { return _armedPosition; }
dogmaphobic's avatar
dogmaphobic committed
825

826
    typedef enum {
827
        JoystickModeRC,         ///< Joystick emulates an RC Transmitter
828 829 830 831 832 833
        JoystickModeAttitude,
        JoystickModePosition,
        JoystickModeForce,
        JoystickModeVelocity,
        JoystickModeMax
    } JoystickMode_t;
dogmaphobic's avatar
dogmaphobic committed
834

Gus Grubba's avatar
Gus Grubba committed
835
    void updateFlightDistance(double distance);
836

837
    int joystickMode();
838
    void setJoystickMode(int mode);
dogmaphobic's avatar
dogmaphobic committed
839

840
    /// List of joystick mode names
841
    QStringList joystickModes();
dogmaphobic's avatar
dogmaphobic committed
842

843
    bool joystickEnabled();
844
    void setJoystickEnabled(bool enabled);
dogmaphobic's avatar
dogmaphobic committed
845

846
    // Is vehicle active with respect to current active vehicle in QGC
847
    bool active();
848
    void setActive(bool active);
dogmaphobic's avatar
dogmaphobic committed
849

850
    // Property accesors
851 852 853 854
    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
855

Patrick José Pereira's avatar
Patrick José Pereira committed
856
    /// Returns the highest quality link available to the Vehicle. If you need to hold a reference to this link use
857
    /// LinkManager::sharedLinkInterfaceForGet to get QSharedPointer for link.
858
    LinkInterface* priorityLink() { return _priorityLink.data(); }
859 860 861 862 863

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

864 865 866
    /// 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
867

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

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

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

877 878 879
    MissionManager*     missionManager()    { return _missionManager; }
    GeoFenceManager*    geoFenceManager()   { return _geoFenceManager; }
    RallyPointManager*  rallyPointManager() { return _rallyPointManager; }
dogmaphobic's avatar
dogmaphobic committed
880

881
    QGeoCoordinate homePosition();
dogmaphobic's avatar
dogmaphobic committed
882

Gus Grubba's avatar
Gus Grubba committed
883 884
    bool armed      () { return _armed; }
    void setArmed   (bool armed);
Don Gagne's avatar
Don Gagne committed
885

886 887 888 889
    bool flightModeSetAvailable             ();
    QStringList flightModes                 ();
    QStringList extraJoystickFlightModes    ();
    QString flightMode                      () const;
890
    void setFlightMode                      (const QString& flightMode);
Don Gagne's avatar
Don Gagne committed
891

892 893
    QString priorityLinkName() const;
    QVariantList links() const;
894 895
    void setPriorityLinkByName(const QString& priorityLinkName);

896 897 898 899 900
    bool fixedWing() const;
    bool multiRotor() const;
    bool vtol() const;
    bool rover() const;
    bool sub() const;
901

902 903 904 905 906 907
    bool supportsThrottleModeCenterZero () const;
    bool supportsNegativeThrust         ();
    bool supportsRadio                  () const;
    bool supportsJSButton               () const;
    bool supportsMotorInterference      () const;
    bool supportsTerrainFrame           () const;
908

Don Gagne's avatar
Don Gagne committed
909 910
    void setGuidedMode(bool guidedMode);

911
    QString prearmError() const { return _prearmError; }
Don Gagne's avatar
Don Gagne committed
912 913
    void setPrearmError(const QString& prearmError);

914
    QmlObjectListModel* cameraTriggerPoints () { return &_cameraTriggerPoints; }
dogmaphobic's avatar
dogmaphobic committed
915 916 917

    int  flowImageIndex() { return _flowImageIndex; }

918 919 920 921
    //-- Mavlink Logging
    void startMavlinkLog();
    void stopMavlinkLog();

922 923 924
    /// 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
925 926
    ///     @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
927

928 929 930 931 932 933
    typedef enum {
        MessageNone,
        MessageNormal,
        MessageWarning,
        MessageError
    } MessageType_t;
dogmaphobic's avatar
dogmaphobic committed
934

935 936 937 938 939 940 941 942 943
    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; }
944 945 946
    float           latitude                () { return static_cast<float>(_coordinate.latitude()); }
    float           longitude               () { return static_cast<float>(_coordinate.longitude()); }
    bool            mavPresent              () { return _mav != nullptr; }
947 948 949 950 951 952 953 954 955 956
    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; }
957
    bool            landing                 () const { return _landing; }
958
    bool            guidedMode              () const;
959
    bool            vtolInFwdFlight         () const { return _vtolInFwdFlight; }
960 961 962
    uint8_t         baseMode                () const { return _base_mode; }
    uint32_t        customMode              () const { return _custom_mode; }
    bool            isOfflineEditingVehicle () const { return _offlineEditingVehicle; }
963 964
    QString         brandImageIndoor        () const;
    QString         brandImageOutdoor       () const;
965
    QStringList     unhealthySensors        () const;
966 967 968 969
    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); }
970
    QString         missionFlightMode       () const;
971
    QString         pauseFlightMode         () const;
972
    QString         rtlFlightMode           () const;
DonLakeFlyer's avatar
DonLakeFlyer committed
973 974
    QString         smartRTLFlightMode      () const;
    bool            supportsSmartRTL        () const;
975
    QString         landFlightMode          () const;
976
    QString         takeControlFlightMode   () const;
977
    QString         followFlightMode        () const;
DonLakeFlyer's avatar
DonLakeFlyer committed
978 979
    double          defaultCruiseSpeed      () const { return _defaultCruiseSpeed; }
    double          defaultHoverSpeed       () const { return _defaultHoverSpeed; }
980
    QString         firmwareTypeString      () const;
Gus Grubba's avatar
Gus Grubba committed
981 982 983 984 985 986
    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; }
987 988
    int             telemetryLNoise         () { return _telemetryLNoise; }
    int             telemetryRNoise         () { return _telemetryRNoise; }
989
    bool            autoDisarm              ();
990
    bool            highLatencyLink         () const { return _highLatencyLink; }
991 992 993
    bool            orbitActive             () const { return _orbitActive; }
    QGCMapCircle*   orbitMapCircle          () { return &_orbitMapCircle; }

994 995 996
    /// Get the maximum MAVLink protocol version supported
    /// @return the maximum version
    unsigned        maxProtoVersion         () const { return _maxProtoVersion; }
997

998 999 1000 1001 1002 1003 1004 1005 1006 1007 1008 1009 1010
    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; }
1011
    Fact* missionItemIndex                  () { return &_missionItemIndexFact; }
1012 1013 1014 1015 1016 1017 1018 1019 1020 1021 1022 1023 1024 1025 1026 1027
    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; }
1028
    FactGroup* terrainFactGroup             () { return &_terrainFactGroup; }
Don Gagne's avatar
Don Gagne committed
1029

1030
    void setConnectionLostEnabled(bool connectionLostEnabled);
1031

Gus Grubba's avatar
Gus Grubba committed
1032 1033 1034
    ParameterManager*       parameterManager() { return _parameterManager; }
    ParameterManager*       parameterManager() const { return _parameterManager; }
    VehicleObjectAvoidance* objectAvoidance()  { return _objectAvoidance; }
dogmaphobic's avatar
dogmaphobic committed
1035

Don Gagne's avatar
Don Gagne committed
1036 1037
    static const int cMaxRcChannels = 18;

Don Gagne's avatar
Don Gagne committed
1038
    bool containsLink(LinkInterface* link) { return _links.contains(link); }
1039 1040 1041 1042 1043 1044

    /// 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
1045
    /// Signals: mavCommandResult on success or failure
1046
    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);
1047
    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
1048

1049
    /// Same as sendMavCommand but available from Qml.
1050 1051 1052 1053 1054 1055 1056 1057 1058 1059 1060 1061 1062
    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));
    }
1063

1064 1065 1066 1067 1068 1069 1070 1071
    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;
1072
    void setFirmwareVersion(int majorVersion, int minorVersion, int patchVersion, FIRMWARE_VERSION_TYPE versionType = FIRMWARE_VERSION_TYPE_OFFICIAL);
1073
    void setFirmwareCustomVersion(int majorVersion, int minorVersion, int patchVersion);
1074
    static const int versionNotSetValue = -1;
Don Gagne's avatar
Don Gagne committed
1075

1076 1077
    QString gitHash() const { return _gitHash; }
    quint64 vehicleUID() const { return _uid; }
Gus Grubba's avatar
Gus Grubba committed
1078
    QString vehicleUIDStr();
1079

1080
    bool soloFirmware() const { return _soloFirmware; }
1081 1082
    void setSoloFirmware(bool soloFirmware);

1083
    int defaultComponentId() { return _defaultComponentId; }
1084 1085 1086

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

Don Gagne's avatar
Don Gagne committed
1088
    /// @return -1 = Unknown, Number of motors on vehicle
1089
    int motorCount();
Don Gagne's avatar
Don Gagne committed
1090 1091

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

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

1097
    /// @return Firmware plugin instance data associated with this Vehicle
1098
    QObject* firmwarePluginInstanceData() { return _firmwarePluginInstanceData; }
1099 1100 1101 1102 1103

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

1104 1105 1106 1107
    QString vehicleImageOpaque  () const;
    QString vehicleImageOutline () const;
    QString vehicleImageCompass () const;

1108 1109
    const QVariantList&         toolIndicators      ();
    const QVariantList&         modeIndicators      ();
1110
    const QVariantList&         staticCameraList    () const;
1111

1112
    bool capabilitiesKnown      () const { return _capabilityBitsKnown; }
1113
    uint64_t capabilityBits     () const { return _capabilityBits; }    // Change signalled by capabilityBitsChanged
1114

1115
    QGCCameraManager*           dynamicCameras      () { return _cameras; }
1116
    QString                     hobbsMeter          ();
1117

1118
    /// @true: When flying a mission the vehicle is always facing towards the next waypoint
1119
    bool vehicleYawsToNextWaypointInMission() const;
1120

DonLakeFlyer's avatar
DonLakeFlyer committed
1121 1122
    /// 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;
1123
    bool initialPlanRequestComplete() const { return _initialPlanRequestComplete; }
DonLakeFlyer's avatar
DonLakeFlyer committed
1124

1125
    void forceInitialPlanRequestComplete();
1126

1127 1128
    void _setFlying(bool flying);
    void _setLanding(bool landing);
DonLakeFlyer's avatar
DonLakeFlyer committed
1129
    void _setHomePosition(QGeoCoordinate& homeCoord);
1130 1131
    void _setMaxProtoVersion(unsigned version);
    void _setMaxProtoVersionFromBothSources();
DonLakeFlyer's avatar
DonLakeFlyer committed
1132

1133 1134 1135
    /// Vehicle is about to be deleted
    void prepareDelete();

1136 1137 1138 1139 1140
    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
1141 1142 1143 1144
    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; }
1145
    bool        isROIEnabled            () { return _isROIEnabled; }
Gus Grubba's avatar
Gus Grubba committed
1146

1147 1148 1149
    CheckList   checkListState          () { return _checkListState; }
    void        setCheckListState       (CheckList cl)  { _checkListState = cl; emit checkListStateChanged(); }

Gus Grubba's avatar
Gus Grubba committed
1150 1151 1152
public slots:
    void setVtolInFwdFlight             (bool vtolInFwdFlight);

1153
signals:
1154 1155 1156 1157 1158 1159 1160
    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);
1161
    void armedPositionChanged();
1162 1163 1164 1165 1166 1167 1168 1169 1170 1171 1172 1173 1174 1175 1176 1177 1178 1179 1180
    void armedChanged                   (bool armed);
    void flightModeChanged              (const QString& flightMode);
    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
1181
    void initialPlanRequestCompleteChanged(bool initialPlanRequestComplete);
1182
    void capabilityBitsChanged          (uint64_t capabilityBits);
1183 1184
    void toolIndicatorsChanged          ();
    void modeIndicatorsChanged          ();
1185 1186 1187 1188 1189 1190 1191 1192 1193 1194
    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            ();
1195

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

1199 1200 1201 1202 1203 1204 1205 1206 1207 1208 1209 1210 1211 1212 1213 1214 1215 1216 1217 1218 1219 1220 1221 1222 1223 1224 1225 1226 1227
    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              ();
1228

Don Gagne's avatar
Don Gagne committed
1229 1230 1231
    /// New RC channel values
    ///     @param channelCount Number of available channels, cMaxRcChannels max
    ///     @param pwmValues -1 signals channel not available
1232
    void rcChannelsChanged              (int channelCount, int pwmValues[cMaxRcChannels]);
Don Gagne's avatar
Don Gagne committed
1233 1234

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

1237 1238 1239 1240
    void mavlinkRawImu                  (mavlink_message_t message);
    void mavlinkScaledImu1              (mavlink_message_t message);
    void mavlinkScaledImu2              (mavlink_message_t message);
    void mavlinkScaledImu3              (mavlink_message_t message);
1241

1242
    // Mavlink Log Download
1243
    void mavlinkLogData                 (Vehicle* vehicle, uint8_t target_system, uint8_t target_component, uint16_t sequence, uint8_t first_message, QByteArray data, bool acked);
1244

1245 1246 1247 1248 1249 1250
    /// 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
1251
    void mavCommandResult               (int vehicleId, int component, int command, int result, bool noReponseFromVehicle);
1252

1253
    // MAVlink Serial Data
1254
    void mavlinkSerialControl           (uint8_t device, uint8_t flags, uint16_t timeout, uint32_t baudrate, QByteArray data);
1255

1256
    // MAVLink protocol version
1257 1258
    void requestProtocolVersion         (unsigned version);
    void mavlinkStatusChanged           ();
Gus Grubba's avatar
Gus Grubba committed
1259

1260 1261 1262 1263 1264
    void gimbalRollChanged              ();
    void gimbalPitchChanged             ();
    void gimbalYawChanged               ();
    void gimbalDataChanged              ();
    void isROIEnabledChanged            ();
1265

1266
private slots:
1267 1268 1269 1270 1271 1272 1273 1274
    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);
1275 1276 1277 1278
    void _offlineFirmwareTypeSettingChanged(QVariant value);
    void _offlineVehicleTypeSettingChanged(QVariant value);
    void _offlineCruiseSpeedSettingChanged(QVariant value);
    void _offlineHoverSpeedSettingChanged(QVariant value);
1279
    void _updateHighLatencyLink         (bool sendCommand = true);
1280

1281 1282
    void _handleTextMessage             (int newCount);
    void _handletextMessageReceived     (UASMessage* message);
dogmaphobic's avatar
dogmaphobic committed
1283
    /** @brief A new camera image has arrived */
1284 1285 1286 1287 1288 1289 1290 1291
    void _imageReady                    (UASInterface* uas);
    void _prearmErrorTimeout            ();
    void _missionLoadComplete           ();
    void _geoFenceLoadComplete          ();
    void _rallyPointLoadComplete        ();
    void _sendMavCommandAgain           ();
    void _clearCameraTriggerPoints      ();
    void _updateDistanceHeadingToHome   ();
1292
    void _updateMissionItemIndex        ();
1293 1294 1295 1296 1297 1298 1299 1300 1301 1302 1303
    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              ();
1304

1305
private:
1306 1307 1308 1309 1310 1311 1312 1313 1314 1315 1316 1317 1318 1319 1320 1321 1322 1323 1324 1325 1326 1327 1328 1329 1330 1331 1332 1333 1334 1335 1336 1337 1338 1339 1340
    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 _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);
1341
    void _handleStatusText              (mavlink_message_t& message);
1342 1343 1344 1345
    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);
1346 1347
    // ArduPilot dialect messages
#if !defined(NO_ARDUPILOT_DIALECT)
1348 1349
    void _handleCameraFeedback          (const mavlink_message_t& message);
    void _handleWind                    (mavlink_message_t& message);
1350
#endif
1351 1352 1353 1354 1355 1356 1357 1358 1359 1360 1361 1362 1363 1364 1365 1366 1367 1368 1369 1370 1371 1372 1373 1374 1375 1376
    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               ();
1377
    void _batteryStatusWorker           (int batteryId, double voltage, double current, double batteryRemainingPct);
1378 1379
    void _chunkedStatusTextTimeout      (void);
    void _chunkedStatusTextCompleted    (uint8_t compId);
Don Gagne's avatar
Don Gagne committed
1380

1381
    int     _id;                    ///< Mavlink system id
1382
    int     _defaultComponentId;
1383
    bool    _active;
1384
    bool    _offlineEditingVehicle; ///< This Vehicle is a "disconnected" vehicle for ui use while offline editing
dogmaphobic's avatar
dogmaphobic committed
1385

1386
    MAV_AUTOPILOT       _firmwareType;
1387
    MAV_TYPE            _vehicleType;
1388
    FirmwarePlugin*     _firmwarePlugin;
1389
    QObject*            _firmwarePluginInstanceData;
1390
    AutoPilotPlugin*    _autopilotPlugin;
Don Gagne's avatar
Don Gagne committed
1391
    MAVLinkProtocol*    _mavlink;
1392
    bool                _soloFirmware;
1393
    QGCToolbox*         _toolbox;
1394
    SettingsManager*    _settingsManager;
dogmaphobic's avatar
dogmaphobic committed
1395

1396 1397
    QTimer              _csvLogTimer;
    QFile               _csvLogFile;
1398

Don Gagne's avatar
Don Gagne committed
1399
    QList<LinkInterface*> _links;
dogmaphobic's avatar
dogmaphobic committed
1400

1401
    JoystickMode_t  _joystickMode;
1402
    bool            _joystickEnabled;
dogmaphobic's avatar
dogmaphobic committed
1403

1404
    UAS* _uas;
dogmaphobic's avatar
dogmaphobic committed
1405

1406
    QGeoCoordinate  _coordinate;
1407
    QGeoCoordinate  _homePosition;
1408
    QGeoCoordinate  _armedPosition;
dogmaphobic's avatar
dogmaphobic committed
1409

1410 1411 1412 1413 1414 1415 1416 1417 1418
    UASInterface*   _mav;
    int             _currentMessageCount;
    int             _messageCount;
    int             _currentErrorCount;
    int             _currentWarningCount;
    int             _currentNormalCount;
    MessageType_t   _currentMessageType;
    QString         _latestError;
    int             _updateCount;
dogmaphobic's avatar
dogmaphobic committed
1419
    QString         _formatedMessage;
Don Gagne's avatar
Don Gagne committed
1420 1421
    int             _rcRSSI;
    double          _rcRSSIstore;
Don Gagne's avatar
Don Gagne committed
1422
    bool            _autoDisconnect;    ///< true: Automatically disconnect vehicle when last connection goes away or lost heartbeat
Don Gagne's avatar
Don Gagne committed
1423
    bool            _flying;
1424
    bool            _landing;
1425
    bool            _vtolInFwdFlight;
1426 1427 1428 1429
    uint32_t        _onboardControlSensorsPresent;
    uint32_t        _onboardControlSensorsEnabled;
    uint32_t        _onboardControlSensorsHealth;
    uint32_t        _onboardControlSensorsUnhealthy;
1430 1431
    bool            _gpsRawIntMessageAvailable;
    bool            _globalPositionIntMessageAvailable;
DonLakeFlyer's avatar
DonLakeFlyer committed
1432 1433
    double          _defaultCruiseSpeed;
    double          _defaultHoverSpeed;
Gus Grubba's avatar
Gus Grubba committed
1434 1435 1436 1437 1438
    int             _telemetryRRSSI;
    int             _telemetryLRSSI;
    uint32_t        _telemetryRXErrors;
    uint32_t        _telemetryFixed;
    uint32_t        _telemetryTXBuffer;
1439 1440
    int             _telemetryLNoise;
    int             _telemetryRNoise;
1441 1442 1443 1444
    bool            _mavlinkProtocolRequestComplete =           false;
    unsigned        _mavlinkProtocolRequestMaxProtoVersion =    0;
    unsigned        _maxProtoVersion =                          0;
    bool            _capabilityBitsKnown =                      false;
1445
    uint64_t        _capabilityBits;
1446
    bool            _highLatencyLink;
1447
    bool            _receivingAttitudeQuaternion;
1448
    CheckList       _checkListState = CheckListNotSetup;
dogmaphobic's avatar
dogmaphobic committed
1449

1450 1451
    QGCCameraManager* _cameras;

1452
    typedef struct {
1453 1454 1455 1456 1457 1458
        int         component;
        bool        commandInt; // true: use COMMAND_INT, false: use COMMAND_LONG
        MAV_CMD     command;
        MAV_FRAME   frame;
        double      rgParam[7];
        bool        showError;
1459 1460 1461 1462 1463
    } MavCommandQueueEntry_t;

    QList<MavCommandQueueEntry_t>   _mavCommandQueue;
    QTimer                          _mavCommandAckTimer;
    int                             _mavCommandRetryCount;
1464
    int                             _capabilitiesRetryCount =               0;
1465
    QElapsedTimer                   _capabilitiesRetryElapsed;
1466 1467
    static const int                _mavCommandMaxRetryCount =              3;
    static const int                _mavCommandAckTimeoutMSecs =            3000;
DonLakeFlyer's avatar
DonLakeFlyer committed
1468
    static const int                _mavCommandAckTimeoutMSecsHighLatency = 120000;
1469

Don Gagne's avatar
Don Gagne committed
1470 1471 1472 1473
    QString             _prearmError;
    QTimer              _prearmErrorTimer;
    static const int    _prearmErrorTimeoutMSecs = 35 * 1000;   ///< Take away prearm error after 35 seconds

1474 1475 1476 1477
    // Lost connection handling
    bool                _connectionLost;
    bool                _connectionLostEnabled;

DonLakeFlyer's avatar
DonLakeFlyer committed
1478 1479
    bool                _initialPlanRequestComplete;

Don Gagne's avatar
Don Gagne committed
1480
    MissionManager*     _missionManager;
1481
    bool                _missionManagerInitialRequestSent;
1482

1483
    GeoFenceManager*    _geoFenceManager;
1484 1485 1486 1487
    bool                _geoFenceManagerInitialRequestSent;

    RallyPointManager*  _rallyPointManager;
    bool                _rallyPointManagerInitialRequestSent;
1488

Gus Grubba's avatar
Gus Grubba committed
1489 1490
    ParameterManager*       _parameterManager   = nullptr;
    VehicleObjectAvoidance* _objectAvoidance    = nullptr;
1491

1492
#if defined(QGC_AIRMAP_ENABLED)
1493
    AirspaceVehicleManager* _airspaceVehicleManager;
1494
#endif
dogmaphobic's avatar
dogmaphobic committed
1495

Don Gagne's avatar
Don Gagne committed
1496 1497 1498
    bool    _armed;         ///< true: vehicle is armed
    uint8_t _base_mode;     ///< base_mode from HEARTBEAT
    uint32_t _custom_mode;  ///< custom_mode from HEARTBEAT
1499 1500 1501 1502 1503 1504

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

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

1508 1509
    static const int _sendMessageMultipleRetries = 5;
    static const int _sendMessageMultipleIntraMessageDelay = 500;
dogmaphobic's avatar
dogmaphobic committed
1510

1511 1512
    QTimer  _sendMultipleTimer;
    int     _nextSendMessageMultipleIndex;
dogmaphobic's avatar
dogmaphobic committed
1513

1514
    QElapsedTimer                   _flightTimer;
DonLakeFlyer's avatar
DonLakeFlyer committed
1515
    QTimer                          _flightTimeUpdater;
1516 1517
    TrajectoryPoints*               _trajectoryPoints;
    QmlObjectListModel              _cameraTriggerPoints;
1518
    //QMap<QString, ADSBVehicle*>     _trafficVehicleMap;
1519

1520
    // Toolbox references
dogmaphobic's avatar
dogmaphobic committed
1521 1522 1523 1524 1525
    FirmwarePluginManager*      _firmwarePluginManager;
    JoystickManager*            _joystickManager;

    int                         _flowImageIndex;

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

1528 1529 1530 1531 1532 1533 1534
    uint                _messagesReceived;
    uint                _messagesSent;
    uint                _messagesLost;
    uint8_t             _messageSeq;
    uint8_t             _compID;
    bool                _heardFrom;

Gus Grubba's avatar
Gus Grubba committed
1535 1536 1537 1538
    float               _curGimbalRoll  = 0.0f;
    float               _curGimbalPitch = 0.0f;
    float               _curGinmbalYaw  = 0.0f;
    bool                _haveGimbalData = false;
1539
    bool                _isROIEnabled   = false;
Gus Grubba's avatar
Gus Grubba committed
1540 1541
    Joystick*           _activeJoystick = nullptr;

1542
    bool _checkLatestStableFWDone = false;
Don Gagne's avatar
Don Gagne committed
1543 1544 1545
    int _firmwareMajorVersion;
    int _firmwareMinorVersion;
    int _firmwarePatchVersion;
1546 1547 1548
    int _firmwareCustomMajorVersion;
    int _firmwareCustomMinorVersion;
    int _firmwareCustomPatchVersion;
1549
    FIRMWARE_VERSION_TYPE _firmwareVersionType;
Don Gagne's avatar
Don Gagne committed
1550

1551
    QString _gitHash;
Gus Grubba's avatar
Gus Grubba committed
1552
    quint64 _uid;
1553

1554
    QElapsedTimer   _lastBatteryAnnouncement;
1555
    int     _lastAnnouncedLowBatteryPercent;
1556

1557
    SharedLinkInterfacePointer _priorityLink;  // We always keep a reference to the priority link to manage shutdown ordering
1558
    bool _priorityLinkCommanded;
1559

1560 1561 1562 1563 1564
    uint64_t    _mavlinkSentCount       = 0;
    uint64_t    _mavlinkReceivedCount   = 0;
    uint64_t    _mavlinkLossCount       = 0;
    float       _mavlinkLossPercent     = 0.0f;

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

1567 1568 1569 1570 1571 1572
    // Orbit status values
    bool            _orbitActive;
    QGCMapCircle    _orbitMapCircle;
    QTimer          _orbitTelemetryTimer;
    static const int _orbitTelemetryTimeoutMsecs = 3000; // No telemetry for this amount and orbit will go inactive

1573 1574 1575 1576 1577 1578
    // PID Tuning telemetry mode
    bool            _pidTuningTelemetryMode;
    bool            _pidTuningWaitingForRates;
    QList<int>      _pidTuningMessages;
    QMap<int, int>  _pidTuningMessageRatesUsecs;

1579 1580 1581 1582 1583 1584 1585 1586 1587
    // Chunked status text support
    typedef struct {
        uint16_t    chunkId;
        uint8_t     severity;
        QStringList rgMessageChunks;
    } ChunkedStatusTextInfo_t;
    QMap<uint8_t /* compId */, ChunkedStatusTextInfo_t> _chunkedStatusTextInfoMap;
    QTimer _chunkedStatusTextTimer;

Don Gagne's avatar
Don Gagne committed
1588 1589 1590 1591 1592
    // FactGroup facts

    Fact _rollFact;
    Fact _pitchFact;
    Fact _headingFact;
DonLakeFlyer's avatar
DonLakeFlyer committed
1593 1594 1595
    Fact _rollRateFact;
    Fact _pitchRateFact;
    Fact _yawRateFact;
Don Gagne's avatar
Don Gagne committed
1596 1597 1598 1599 1600
    Fact _groundSpeedFact;
    Fact _airSpeedFact;
    Fact _climbRateFact;
    Fact _altitudeRelativeFact;
    Fact _altitudeAMSLFact;
1601
    Fact _flightDistanceFact;
1602
    Fact _flightTimeFact;
1603
    Fact _distanceToHomeFact;
1604
    Fact _missionItemIndexFact;
1605
    Fact _headingToNextWPFact;
1606
    Fact _headingToHomeFact;
1607
    Fact _distanceToGCSFact;
1608
    Fact _hobbsFact;
1609
    Fact _throttlePctFact;
Don Gagne's avatar
Don Gagne committed
1610

1611
    VehicleGPSFactGroup             _gpsFactGroup;
DonLakeFlyer's avatar
DonLakeFlyer committed
1612 1613
    VehicleBatteryFactGroup         _battery1FactGroup;
    VehicleBatteryFactGroup         _battery2FactGroup;
1614 1615 1616 1617 1618 1619
    VehicleWindFactGroup            _windFactGroup;
    VehicleVibrationFactGroup       _vibrationFactGroup;
    VehicleTemperatureFactGroup     _temperatureFactGroup;
    VehicleClockFactGroup           _clockFactGroup;
    VehicleSetpointFactGroup        _setpointFactGroup;
    VehicleDistanceSensorFactGroup  _distanceSensorFactGroup;
1620
    VehicleEstimatorStatusFactGroup _estimatorStatusFactGroup;
1621 1622 1623
    TerrainFactGroup                _terrainFactGroup;

    TerrainProtocolHandler* _terrainProtocolHandler = nullptr;
Don Gagne's avatar
Don Gagne committed
1624 1625 1626 1627

    static const char* _rollFactName;
    static const char* _pitchFactName;
    static const char* _headingFactName;
DonLakeFlyer's avatar
DonLakeFlyer committed
1628 1629 1630
    static const char* _rollRateFactName;
    static const char* _pitchRateFactName;
    static const char* _yawRateFactName;
Don Gagne's avatar
Don Gagne committed
1631 1632 1633 1634 1635
    static const char* _groundSpeedFactName;
    static const char* _airSpeedFactName;
    static const char* _climbRateFactName;
    static const char* _altitudeRelativeFactName;
    static const char* _altitudeAMSLFactName;
1636
    static const char* _flightDistanceFactName;
1637
    static const char* _flightTimeFactName;
1638
    static const char* _distanceToHomeFactName;
1639
    static const char* _missionItemIndexFactName;
1640
    static const char* _headingToNextWPFactName;
1641
    static const char* _headingToHomeFactName;
1642
    static const char* _distanceToGCSFactName;
1643
    static const char* _hobbsFactName;
1644
    static const char* _throttlePctFactName;
Don Gagne's avatar
Don Gagne committed
1645

Don Gagne's avatar
Don Gagne committed
1646
    static const char* _gpsFactGroupName;
DonLakeFlyer's avatar
DonLakeFlyer committed
1647 1648
    static const char* _battery1FactGroupName;
    static const char* _battery2FactGroupName;
Don Gagne's avatar
Don Gagne committed
1649
    static const char* _windFactGroupName;
1650
    static const char* _vibrationFactGroupName;
1651
    static const char* _temperatureFactGroupName;
dheideman's avatar
dheideman committed
1652
    static const char* _clockFactGroupName;
1653
    static const char* _distanceSensorFactGroupName;
1654
    static const char* _estimatorStatusFactGroupName;
1655
    static const char* _terrainFactGroupName;
Don Gagne's avatar
Don Gagne committed
1656 1657 1658

    static const int _vehicleUIUpdateRateMSecs = 100;

1659
    // Settings keys
1660 1661
    static const char* _settingsGroup;
    static const char* _joystickModeSettingsKey;
1662
    static const char* _joystickEnabledSettingsKey;
Don Gagne's avatar
Don Gagne committed
1663

1664
};