Newer
Older
/****************************************************************************
*
* (c) 2009-2016 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org>
*
* QGroundControl is licensed according to the terms in the file
* COPYING.md in the root of the source code directory.
*
****************************************************************************/
#include "LinkInterface.h"
#include "QGCMAVLink.h"
#include "QmlObjectListModel.h"
class UAS;
class UASInterface;
#if defined(QGC_AIRMAP_ENABLED)
class AirspaceVehicleManager;
#endif
Q_DECLARE_LOGGING_CATEGORY(VehicleLog)
class VehicleDistanceSensorFactGroup : public FactGroup
{
Q_OBJECT
public:
VehicleDistanceSensorFactGroup(QObject* parent = nullptr);
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)
Fact* rotationNone (void) { return &_rotationNoneFact; }
Fact* rotationYaw45 (void) { return &_rotationYaw45Fact; }
Fact* rotationYaw90 (void) { return &_rotationYaw90Fact; }
Fact* rotationYaw135 (void) { return &_rotationYaw90Fact; }
Fact* rotationYaw180 (void) { return &_rotationYaw180Fact; }
Fact* rotationYaw225 (void) { return &_rotationYaw180Fact; }
Fact* rotationYaw270 (void) { return &_rotationYaw270Fact; }
Fact* rotationYaw315 (void) { return &_rotationYaw315Fact; }
Fact* rotationPitch90 (void) { return &_rotationPitch90Fact; }
Fact* rotationPitch270 (void) { return &_rotationPitch270Fact; }
bool idSet(void) { return _idSet; }
void setIdSet(bool idSet) { _idSet = idSet; }
uint8_t id(void) { return _id; }
void setId(uint8_t id) { _id = id; }
static const char* _rotationNoneFactName;
static const char* _rotationYaw45FactName;
static const char* _rotationYaw90FactName;
static const char* _rotationYaw135FactName;
static const char* _rotationYaw180FactName;
static const char* _rotationYaw225FactName;
static const char* _rotationYaw270FactName;
static const char* _rotationYaw315FactName;
static const char* _rotationPitch90FactName;
static const char* _rotationPitch270FactName;
private:
Fact _rotationNoneFact;
Fact _rotationYaw180Fact;
Fact _rotationYaw270Fact;
Fact _rotationYaw315Fact;
Fact _rotationPitch90Fact;
Fact _rotationPitch270Fact;
bool _idSet; // true: _id is set to seen sensor id
uint8_t _id; // The id for the sensor being tracked. Current support for only a single sensor.
class VehicleSetpointFactGroup : public FactGroup
{
Q_OBJECT
public:
VehicleSetpointFactGroup(QObject* parent = nullptr);
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131
132
133
134
135
136
137
138
139
140
141
142
143
Q_PROPERTY(Fact* roll READ roll CONSTANT)
Q_PROPERTY(Fact* pitch READ pitch CONSTANT)
Q_PROPERTY(Fact* yaw READ yaw CONSTANT)
Q_PROPERTY(Fact* rollRate READ rollRate CONSTANT)
Q_PROPERTY(Fact* pitchRate READ pitchRate CONSTANT)
Q_PROPERTY(Fact* yawRate READ yawRate CONSTANT)
Fact* roll (void) { return &_rollFact; }
Fact* pitch (void) { return &_pitchFact; }
Fact* yaw (void) { return &_yawFact; }
Fact* rollRate (void) { return &_rollRateFact; }
Fact* pitchRate (void) { return &_pitchRateFact; }
Fact* yawRate (void) { return &_yawRateFact; }
static const char* _rollFactName;
static const char* _pitchFactName;
static const char* _yawFactName;
static const char* _rollRateFactName;
static const char* _pitchRateFactName;
static const char* _yawRateFactName;
private:
Fact _rollFact;
Fact _pitchFact;
Fact _yawFact;
Fact _rollRateFact;
Fact _pitchRateFact;
Fact _yawRateFact;
};
class VehicleVibrationFactGroup : public FactGroup
{
Q_OBJECT
public:
VehicleVibrationFactGroup(QObject* parent = nullptr);
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)
Fact* xAxis (void) { return &_xAxisFact; }
Fact* yAxis (void) { return &_yAxisFact; }
Fact* zAxis (void) { return &_zAxisFact; }
Fact* clipCount1 (void) { return &_clipCount1Fact; }
Fact* clipCount2 (void) { return &_clipCount2Fact; }
Fact* clipCount3 (void) { return &_clipCount3Fact; }
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;
};
class VehicleWindFactGroup : public FactGroup
{
Q_OBJECT
public:
VehicleWindFactGroup(QObject* parent = nullptr);
Q_PROPERTY(Fact* direction READ direction CONSTANT)
Q_PROPERTY(Fact* speed READ speed CONSTANT)
Q_PROPERTY(Fact* verticalSpeed READ verticalSpeed CONSTANT)
Fact* direction (void) { return &_directionFact; }
Fact* speed (void) { return &_speedFact; }
Fact* verticalSpeed (void) { return &_verticalSpeedFact; }
static const char* _directionFactName;
static const char* _speedFactName;
static const char* _verticalSpeedFactName;
private:
Fact _directionFact;
Fact _speedFact;
Fact _verticalSpeedFact;
};
class VehicleGPSFactGroup : public FactGroup
{
Q_OBJECT
public:
VehicleGPSFactGroup(QObject* parent = nullptr);
Q_PROPERTY(Fact* lat READ lat CONSTANT)
Q_PROPERTY(Fact* lon READ lon CONSTANT)
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)
Fact* lat (void) { return &_latFact; }
Fact* lon (void) { return &_lonFact; }
Fact* hdop (void) { return &_hdopFact; }
Fact* vdop (void) { return &_vdopFact; }
Fact* courseOverGround (void) { return &_courseOverGroundFact; }
Fact* count (void) { return &_countFact; }
Fact* lock (void) { return &_lockFact; }
static const char* _latFactName;
static const char* _lonFactName;
static const char* _hdopFactName;
static const char* _vdopFactName;
static const char* _courseOverGroundFactName;
static const char* _countFactName;
static const char* _lockFactName;
Fact _latFact;
Fact _lonFact;
Fact _hdopFact;
Fact _vdopFact;
Fact _courseOverGroundFact;
Fact _countFact;
Fact _lockFact;
class VehicleBatteryFactGroup : public FactGroup
{
Q_OBJECT
public:
VehicleBatteryFactGroup(QObject* parent = nullptr);
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)
Q_PROPERTY(Fact* cellCount READ cellCount CONSTANT)
Q_PROPERTY(Fact* instantPower READ instantPower CONSTANT)
Q_PROPERTY(Fact* timeRemaining READ timeRemaining CONSTANT)
Q_PROPERTY(Fact* chargeState READ chargeState CONSTANT)
Fact* voltage (void) { return &_voltageFact; }
Fact* percentRemaining (void) { return &_percentRemainingFact; }
Fact* mahConsumed (void) { return &_mahConsumedFact; }
Fact* current (void) { return &_currentFact; }
Fact* temperature (void) { return &_temperatureFact; }
Fact* cellCount (void) { return &_cellCountFact; }
Fact* instantPower (void) { return &_instantPowerFact; }
Fact* timeRemaining (void) { return &_timeRemainingFact; }
Fact* chargeState (void) { return &_chargeStateFact; }
static const char* _voltageFactName;
static const char* _percentRemainingFactName;
static const char* _mahConsumedFactName;
static const char* _currentFactName;
static const char* _temperatureFactName;
static const char* _cellCountFactName;
static const char* _instantPowerFactName;
static const char* _timeRemainingFactName;
static const char* _chargeStateFactName;
static const double _voltageUnavailable;
static const int _percentRemainingUnavailable;
static const int _mahConsumedUnavailable;
static const int _currentUnavailable;
static const double _temperatureUnavailable;
static const int _cellCountUnavailable;
static const double _instantPowerUnavailable;
Fact _voltageFact;
Fact _percentRemainingFact;
Fact _mahConsumedFact;
Fact _currentFact;
Fact _temperatureFact;
Fact _cellCountFact;
Fact _instantPowerFact;
Fact _timeRemainingFact;
Fact _chargeStateFact;
class VehicleTemperatureFactGroup : public FactGroup
{
Q_OBJECT
public:
VehicleTemperatureFactGroup(QObject* parent = nullptr);
Q_PROPERTY(Fact* temperature1 READ temperature1 CONSTANT)
Q_PROPERTY(Fact* temperature2 READ temperature2 CONSTANT)
Q_PROPERTY(Fact* temperature3 READ temperature3 CONSTANT)
Fact* temperature1 (void) { return &_temperature1Fact; }
Fact* temperature2 (void) { return &_temperature2Fact; }
Fact* temperature3 (void) { return &_temperature3Fact; }
static const char* _temperature1FactName;
static const char* _temperature2FactName;
static const char* _temperature3FactName;
static const char* _settingsGroup;
static const double _temperatureUnavailable;
private:
Fact _temperature1Fact;
Fact _temperature2Fact;
Fact _temperature3Fact;
};
class VehicleClockFactGroup : public FactGroup
{
Q_OBJECT
public:
VehicleClockFactGroup(QObject* parent = nullptr);
Q_PROPERTY(Fact* currentTime READ currentTime CONSTANT)
Q_PROPERTY(Fact* currentDate READ currentDate CONSTANT)
Fact* currentTime (void) { return &_currentTimeFact; }
Fact* currentDate (void) { return &_currentDateFact; }
static const char* _currentTimeFactName;
static const char* _currentDateFactName;
static const char* _settingsGroup;
private slots:
void _updateAllValues(void) override;
private:
Fact _currentTimeFact;
Fact _currentDateFact;
};
361
362
363
364
365
366
367
368
369
370
371
372
373
374
375
376
377
378
379
380
381
382
383
384
385
386
387
388
389
390
391
392
393
394
395
396
397
398
399
400
401
402
403
404
405
406
407
408
409
410
411
412
413
414
415
416
417
418
419
420
421
422
423
424
425
426
427
428
429
430
431
432
433
434
435
436
437
438
439
440
441
442
443
444
445
446
447
448
449
450
451
452
453
454
455
456
457
458
459
460
461
462
463
464
465
466
467
468
469
470
471
472
473
474
475
476
477
478
479
class VehicleEstimatorStatusFactGroup : public FactGroup
{
Q_OBJECT
public:
VehicleEstimatorStatusFactGroup(QObject* parent = nullptr);
Q_PROPERTY(Fact* goodAttitudeEstimate READ goodAttitudeEstimate CONSTANT)
Q_PROPERTY(Fact* goodHorizVelEstimate READ goodHorizVelEstimate CONSTANT)
Q_PROPERTY(Fact* goodVertVelEstimate READ goodVertVelEstimate CONSTANT)
Q_PROPERTY(Fact* goodHorizPosRelEstimate READ goodHorizPosRelEstimate CONSTANT)
Q_PROPERTY(Fact* goodHorizPosAbsEstimate READ goodHorizPosAbsEstimate CONSTANT)
Q_PROPERTY(Fact* goodVertPosAbsEstimate READ goodVertPosAbsEstimate CONSTANT)
Q_PROPERTY(Fact* goodVertPosAGLEstimate READ goodVertPosAGLEstimate CONSTANT)
Q_PROPERTY(Fact* goodConstPosModeEstimate READ goodConstPosModeEstimate CONSTANT)
Q_PROPERTY(Fact* goodPredHorizPosRelEstimate READ goodPredHorizPosRelEstimate CONSTANT)
Q_PROPERTY(Fact* goodPredHorizPosAbsEstimate READ goodPredHorizPosAbsEstimate CONSTANT)
Q_PROPERTY(Fact* gpsGlitch READ gpsGlitch CONSTANT)
Q_PROPERTY(Fact* accelError READ accelError CONSTANT)
Q_PROPERTY(Fact* velRatio READ velRatio CONSTANT)
Q_PROPERTY(Fact* horizPosRatio READ horizPosRatio CONSTANT)
Q_PROPERTY(Fact* vertPosRatio READ vertPosRatio CONSTANT)
Q_PROPERTY(Fact* magRatio READ magRatio CONSTANT)
Q_PROPERTY(Fact* haglRatio READ haglRatio CONSTANT)
Q_PROPERTY(Fact* tasRatio READ tasRatio CONSTANT)
Q_PROPERTY(Fact* horizPosAccuracy READ horizPosAccuracy CONSTANT)
Q_PROPERTY(Fact* vertPosAccuracy READ vertPosAccuracy CONSTANT)
Fact* goodAttitudeEstimate (void) { return &_goodAttitudeEstimateFact; }
Fact* goodHorizVelEstimate (void) { return &_goodHorizVelEstimateFact; }
Fact* goodVertVelEstimate (void) { return &_goodVertVelEstimateFact; }
Fact* goodHorizPosRelEstimate (void) { return &_goodHorizPosRelEstimateFact; }
Fact* goodHorizPosAbsEstimate (void) { return &_goodHorizPosAbsEstimateFact; }
Fact* goodVertPosAbsEstimate (void) { return &_goodVertPosAbsEstimateFact; }
Fact* goodVertPosAGLEstimate (void) { return &_goodVertPosAGLEstimateFact; }
Fact* goodConstPosModeEstimate (void) { return &_goodConstPosModeEstimateFact; }
Fact* goodPredHorizPosRelEstimate (void) { return &_goodPredHorizPosRelEstimateFact; }
Fact* goodPredHorizPosAbsEstimate (void) { return &_goodPredHorizPosAbsEstimateFact; }
Fact* gpsGlitch (void) { return &_gpsGlitchFact; }
Fact* accelError (void) { return &_accelErrorFact; }
Fact* velRatio (void) { return &_velRatioFact; }
Fact* horizPosRatio (void) { return &_horizPosRatioFact; }
Fact* vertPosRatio (void) { return &_vertPosRatioFact; }
Fact* magRatio (void) { return &_magRatioFact; }
Fact* haglRatio (void) { return &_haglRatioFact; }
Fact* tasRatio (void) { return &_tasRatioFact; }
Fact* horizPosAccuracy (void) { return &_horizPosAccuracyFact; }
Fact* vertPosAccuracy (void) { return &_vertPosAccuracyFact; }
static const char* _goodAttitudeEstimateFactName;
static const char* _goodHorizVelEstimateFactName;
static const char* _goodVertVelEstimateFactName;
static const char* _goodHorizPosRelEstimateFactName;
static const char* _goodHorizPosAbsEstimateFactName;
static const char* _goodVertPosAbsEstimateFactName;
static const char* _goodVertPosAGLEstimateFactName;
static const char* _goodConstPosModeEstimateFactName;
static const char* _goodPredHorizPosRelEstimateFactName;
static const char* _goodPredHorizPosAbsEstimateFactName;
static const char* _gpsGlitchFactName;
static const char* _accelErrorFactName;
static const char* _velRatioFactName;
static const char* _horizPosRatioFactName;
static const char* _vertPosRatioFactName;
static const char* _magRatioFactName;
static const char* _haglRatioFactName;
static const char* _tasRatioFactName;
static const char* _horizPosAccuracyFactName;
static const char* _vertPosAccuracyFactName;
private:
Fact _goodAttitudeEstimateFact;
Fact _goodHorizVelEstimateFact;
Fact _goodVertVelEstimateFact;
Fact _goodHorizPosRelEstimateFact;
Fact _goodHorizPosAbsEstimateFact;
Fact _goodVertPosAbsEstimateFact;
Fact _goodVertPosAGLEstimateFact;
Fact _goodConstPosModeEstimateFact;
Fact _goodPredHorizPosRelEstimateFact;
Fact _goodPredHorizPosAbsEstimateFact;
Fact _gpsGlitchFact;
Fact _accelErrorFact;
Fact _velRatioFact;
Fact _horizPosRatioFact;
Fact _vertPosRatioFact;
Fact _magRatioFact;
Fact _haglRatioFact;
Fact _tasRatioFact;
Fact _horizPosAccuracyFact;
Fact _vertPosAccuracyFact;
#if 0
typedef enum ESTIMATOR_STATUS_FLAGS
{
ESTIMATOR_ATTITUDE=1, /* True if the attitude estimate is good | */
ESTIMATOR_VELOCITY_HORIZ=2, /* True if the horizontal velocity estimate is good | */
ESTIMATOR_VELOCITY_VERT=4, /* True if the vertical velocity estimate is good | */
ESTIMATOR_POS_HORIZ_REL=8, /* True if the horizontal position (relative) estimate is good | */
ESTIMATOR_POS_HORIZ_ABS=16, /* True if the horizontal position (absolute) estimate is good | */
ESTIMATOR_POS_VERT_ABS=32, /* True if the vertical position (absolute) estimate is good | */
ESTIMATOR_POS_VERT_AGL=64, /* True if the vertical position (above ground) estimate is good | */
ESTIMATOR_CONST_POS_MODE=128, /* True if the EKF is in a constant position mode and is not using external measurements (eg GPS or optical flow) | */
ESTIMATOR_PRED_POS_HORIZ_REL=256, /* True if the EKF has sufficient data to enter a mode that will provide a (relative) position estimate | */
ESTIMATOR_PRED_POS_HORIZ_ABS=512, /* True if the EKF has sufficient data to enter a mode that will provide a (absolute) position estimate | */
ESTIMATOR_GPS_GLITCH=1024, /* True if the EKF has detected a GPS glitch | */
ESTIMATOR_ACCEL_ERROR=2048, /* True if the EKF has detected bad accelerometer data | */
typedef struct __mavlink_estimator_status_t {
uint64_t time_usec; /*< Timestamp (micros since boot or Unix epoch)*/
float vel_ratio; /*< Velocity innovation test ratio*/
float pos_horiz_ratio; /*< Horizontal position innovation test ratio*/
float pos_vert_ratio; /*< Vertical position innovation test ratio*/
float mag_ratio; /*< Magnetometer innovation test ratio*/
float hagl_ratio; /*< Height above terrain innovation test ratio*/
float tas_ratio; /*< True airspeed innovation test ratio*/
float pos_horiz_accuracy; /*< Horizontal position 1-STD accuracy relative to the EKF local origin (m)*/
float pos_vert_accuracy; /*< Vertical position 1-STD accuracy relative to the EKF local origin (m)*/
uint16_t flags; /*< Integer bitmask indicating which EKF outputs are valid. See definition for ESTIMATOR_STATUS_FLAGS.*/
Vehicle(LinkInterface* link,
int vehicleId,
MAV_AUTOPILOT firmwareType,
MAV_TYPE vehicleType,
FirmwarePluginManager* firmwarePluginManager,
JoystickManager* joystickManager);
// The following is used to create a disconnected Vehicle for use while offline editing.
Vehicle(MAV_AUTOPILOT firmwareType,
MAV_TYPE vehicleType,
FirmwarePluginManager* firmwarePluginManager,
QObject* parent = NULL);
/// 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,
SysStatusSensorAbsolutePressure = MAV_SYS_STATUS_SENSOR_ABSOLUTE_PRESSURE,
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)
Q_PROPERTY(int id READ id CONSTANT)
Q_PROPERTY(AutoPilotPlugin* autopilot MEMBER _autopilotPlugin CONSTANT)
Q_PROPERTY(QGeoCoordinate coordinate READ coordinate NOTIFY coordinateChanged)
Q_PROPERTY(QGeoCoordinate homePosition READ homePosition NOTIFY homePositionChanged)
Q_PROPERTY(bool armed READ armed WRITE setArmed NOTIFY armedChanged)
Q_PROPERTY(bool autoDisarm READ autoDisarm NOTIFY autoDisarmChanged)
Q_PROPERTY(bool flightModeSetAvailable READ flightModeSetAvailable CONSTANT)
Q_PROPERTY(QStringList flightModes READ flightModes NOTIFY flightModesChanged)
Q_PROPERTY(QString flightMode READ flightMode WRITE setFlightMode NOTIFY flightModeChanged)
Q_PROPERTY(bool hilMode READ hilMode WRITE setHilMode NOTIFY hilModeChanged)
Q_PROPERTY(QmlObjectListModel* trajectoryPoints READ trajectoryPoints CONSTANT)
Q_PROPERTY(QmlObjectListModel* cameraTriggerPoints READ cameraTriggerPoints CONSTANT)
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)
Q_PROPERTY(bool px4Firmware READ px4Firmware NOTIFY firmwareTypeChanged)
Q_PROPERTY(bool apmFirmware READ apmFirmware NOTIFY firmwareTypeChanged)
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)
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)
Q_PROPERTY(bool supportsThrottleModeCenterZero READ supportsThrottleModeCenterZero CONSTANT)
Q_PROPERTY(bool supportsNegativeThrust READ supportsNegativeThrust CONSTANT)
Q_PROPERTY(bool supportsJSButton READ supportsJSButton CONSTANT)
Q_PROPERTY(bool supportsRadio READ supportsRadio CONSTANT)
Q_PROPERTY(bool supportsMotorInterference READ supportsMotorInterference CONSTANT)
Q_PROPERTY(bool autoDisconnect MEMBER _autoDisconnect NOTIFY autoDisconnectChanged)
Q_PROPERTY(QString prearmError READ prearmError WRITE setPrearmError NOTIFY prearmErrorChanged)
Q_PROPERTY(int motorCount READ motorCount CONSTANT)
Q_PROPERTY(bool coaxialMotors READ coaxialMotors CONSTANT)
Q_PROPERTY(bool xConfigMotors READ xConfigMotors CONSTANT)
Q_PROPERTY(bool isOfflineEditingVehicle READ isOfflineEditingVehicle CONSTANT)
Q_PROPERTY(QString brandImageIndoor READ brandImageIndoor NOTIFY firmwareTypeChanged)
Q_PROPERTY(QString brandImageOutdoor READ brandImageOutdoor NOTIFY firmwareTypeChanged)
Q_PROPERTY(QStringList unhealthySensors READ unhealthySensors NOTIFY unhealthySensorsChanged)
Q_PROPERTY(int sensorsPresentBits READ sensorsPresentBits NOTIFY sensorsPresentBitsChanged)
Q_PROPERTY(int sensorsEnabledBits READ sensorsEnabledBits NOTIFY sensorsEnabledBitsChanged)
Q_PROPERTY(int sensorsHealthBits READ sensorsHealthBits NOTIFY sensorsHealthBitsChanged)
Q_PROPERTY(int sensorsUnhealthyBits READ sensorsUnhealthyBits NOTIFY sensorsUnhealthyBitsChanged) ///< Combination of enabled and health
Q_PROPERTY(QString missionFlightMode READ missionFlightMode CONSTANT)
Q_PROPERTY(QString pauseFlightMode READ pauseFlightMode CONSTANT)
Q_PROPERTY(QString rtlFlightMode READ rtlFlightMode CONSTANT)
Q_PROPERTY(QString landFlightMode READ landFlightMode CONSTANT)
Q_PROPERTY(QString takeControlFlightMode READ takeControlFlightMode CONSTANT)
Q_PROPERTY(QString firmwareTypeString READ firmwareTypeString NOTIFY firmwareTypeChanged)
Q_PROPERTY(QString vehicleTypeString READ vehicleTypeString NOTIFY vehicleTypeChanged)
Q_PROPERTY(QString vehicleImageOpaque READ vehicleImageOpaque CONSTANT)
Q_PROPERTY(QString vehicleImageOutline READ vehicleImageOutline CONSTANT)
Q_PROPERTY(QString vehicleImageCompass READ vehicleImageCompass CONSTANT)
Q_PROPERTY(int telemetryRRSSI READ telemetryRRSSI NOTIFY telemetryRRSSIChanged)
Q_PROPERTY(int telemetryLRSSI READ telemetryLRSSI NOTIFY telemetryLRSSIChanged)
Q_PROPERTY(unsigned int telemetryRXErrors READ telemetryRXErrors NOTIFY telemetryRXErrorsChanged)
Q_PROPERTY(unsigned int telemetryFixed READ telemetryFixed NOTIFY telemetryFixedChanged)
Q_PROPERTY(unsigned int telemetryTXBuffer READ telemetryTXBuffer NOTIFY telemetryTXBufferChanged)
Q_PROPERTY(int telemetryLNoise READ telemetryLNoise NOTIFY telemetryLNoiseChanged)
Q_PROPERTY(int telemetryRNoise READ telemetryRNoise NOTIFY telemetryRNoiseChanged)
Q_PROPERTY(QVariantList toolBarIndicators READ toolBarIndicators NOTIFY toolBarIndicatorsChanged)
Q_PROPERTY(QmlObjectListModel* adsbVehicles READ adsbVehicles CONSTANT)
Q_PROPERTY(bool initialPlanRequestComplete READ initialPlanRequestComplete NOTIFY initialPlanRequestCompleteChanged)
Q_PROPERTY(QVariantList staticCameraList READ staticCameraList CONSTANT)
Q_PROPERTY(QGCCameraManager* dynamicCameras READ dynamicCameras NOTIFY dynamicCamerasChanged)
Q_PROPERTY(QString hobbsMeter READ hobbsMeter NOTIFY hobbsMeterChanged)
Q_PROPERTY(bool vtolInFwdFlight READ vtolInFwdFlight WRITE setVtolInFwdFlight NOTIFY vtolInFwdFlightChanged)
Q_PROPERTY(bool highLatencyLink READ highLatencyLink NOTIFY highLatencyLinkChanged)
Q_PROPERTY(bool supportsTerrainFrame READ supportsTerrainFrame NOTIFY firmwareTypeChanged)
Q_PROPERTY(QString priorityLinkName READ priorityLinkName WRITE setPriorityLinkByName NOTIFY priorityLinkNameChanged)
Q_PROPERTY(QVariantList links READ links NOTIFY linksChanged)
Q_PROPERTY(LinkInterface* priorityLink READ priorityLink NOTIFY priorityLinkNameChanged)
// Vehicle state used for guided control
Q_PROPERTY(bool flying READ flying NOTIFY flyingChanged) ///< Vehicle is flying
Q_PROPERTY(bool landing READ landing NOTIFY landingChanged) ///< Vehicle is in landing pattern (DO_LAND_START)
Q_PROPERTY(bool guidedMode READ guidedMode WRITE setGuidedMode NOTIFY guidedModeChanged) ///< Vehicle is in Guided mode and can respond to guided commands
Q_PROPERTY(bool guidedModeSupported READ guidedModeSupported CONSTANT) ///< Guided mode commands are supported by this vehicle
Q_PROPERTY(bool pauseVehicleSupported READ pauseVehicleSupported CONSTANT) ///< Pause vehicle command is supported
Q_PROPERTY(bool orbitModeSupported READ orbitModeSupported CONSTANT) ///< Orbit mode is supported by this vehicle
Q_PROPERTY(bool takeoffVehicleSupported READ takeoffVehicleSupported CONSTANT) ///< Guided takeoff supported
Q_PROPERTY(ParameterManager* parameterManager READ parameterManager CONSTANT)
// FactGroup object model properties
Q_PROPERTY(Fact* roll READ roll CONSTANT)
Q_PROPERTY(Fact* pitch READ pitch CONSTANT)
Q_PROPERTY(Fact* heading READ heading CONSTANT)
Q_PROPERTY(Fact* rollRate READ rollRate CONSTANT)
Q_PROPERTY(Fact* pitchRate READ pitchRate CONSTANT)
Q_PROPERTY(Fact* yawRate READ yawRate CONSTANT)
Q_PROPERTY(Fact* groundSpeed READ groundSpeed CONSTANT)
Q_PROPERTY(Fact* airSpeed READ airSpeed CONSTANT)
Q_PROPERTY(Fact* climbRate READ climbRate CONSTANT)
Q_PROPERTY(Fact* altitudeRelative READ altitudeRelative CONSTANT)
Q_PROPERTY(Fact* altitudeAMSL READ altitudeAMSL CONSTANT)
Q_PROPERTY(Fact* flightDistance READ flightDistance CONSTANT)
Q_PROPERTY(Fact* distanceToHome READ distanceToHome CONSTANT)
Q_PROPERTY(Fact* hobbs READ hobbs CONSTANT)
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)
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)
Q_PROPERTY(quint64 vehicleUID READ vehicleUID NOTIFY vehicleUIDChanged)
Q_PROPERTY(QString vehicleUIDStr READ vehicleUIDStr NOTIFY vehicleUIDChanged)
/// Resets link status counters
Q_INVOKABLE void resetCounters ();
/// Returns the number of buttons which are reserved for firmware use in the MANUAL_CONTROL mavlink
/// message. For example PX4 Flight Stack reserves the first 8 buttons to simulate rc switches.
/// The remainder can be assigned to Vehicle actions.
/// @return -1: reserver all buttons, >0 number of buttons to reserve
Q_PROPERTY(int manualControlReservedButtonCount READ manualControlReservedButtonCount CONSTANT)
// Called when the message drop-down is invoked to clear current count
Q_INVOKABLE void resetMessages();
Q_INVOKABLE void virtualTabletJoystickValue(double roll, double pitch, double yaw, double thrust);
/// Command vehicle to return to launch
Q_INVOKABLE void guidedModeRTL(void);
/// Command vehicle to land at current location
Q_INVOKABLE void guidedModeLand(void);
/// Command vehicle to takeoff from current location
Q_INVOKABLE void guidedModeTakeoff(double altitudeRelative);
/// @return The minimum takeoff altitude (relative) for guided takeoff.
Q_INVOKABLE double minimumTakeoffAltitude(void);
/// Command vehicle to move to specified location (altitude is included and relative)
Q_INVOKABLE void guidedModeGotoLocation(const QGeoCoordinate& gotoCoord);
/// 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);
/// Command vehicle to orbit given center point
/// @param radius Distance from vehicle to centerCoord
/// @param amslAltitude Desired vehicle altitude
Q_INVOKABLE void guidedModeOrbit(const QGeoCoordinate& centerCoord, double radius, double amslAltitude);
/// Command vehicle to pause at current location. If vehicle supports guide mode, vehicle will be left
/// in guided mode after pause.
Q_INVOKABLE void pauseVehicle(void);
/// Command vehicle to kill all motors no matter what state
Q_INVOKABLE void emergencyStop(void);
/// Command vehicle to abort landing
Danny Schrader
committed
Q_INVOKABLE void abortLanding(double climbOutAltitude);
Q_INVOKABLE void startMission(void);
/// Alter the current mission item on the vehicle
Q_INVOKABLE void setCurrentMissionSequence(int seq);
/// Reboot vehicle
Q_INVOKABLE void rebootVehicle();
/// Clear Messages
Q_INVOKABLE void clearMessages();
#if 0
// Temporarily removed, waiting for new command implementation
/// Test motor
/// @param motor Motor number, 1-based
/// @param percent 0-no power, 100-full power
/// @param timeoutSecs Number of seconds for motor to run
Q_INVOKABLE void motorTest(int motor, int percent, int timeoutSecs);
bool guidedModeSupported (void) const;
bool pauseVehicleSupported (void) const;
bool orbitModeSupported (void) const;
bool takeoffVehicleSupported(void) const;
// Property accessors
QGeoCoordinate coordinate(void) { return _coordinate; }
JoystickModeRC, ///< Joystick emulates an RC Transmitter
JoystickModeAttitude,
JoystickModePosition,
JoystickModeForce,
JoystickModeVelocity,
JoystickModeMax
} JoystickMode_t;
int joystickMode(void);
void setJoystickMode(int mode);
/// List of joystick mode names
QStringList joystickModes(void);
bool joystickEnabled(void);
void setJoystickEnabled(bool enabled);
// Is vehicle active with respect to current active vehicle in QGC
bool active(void);
void setActive(bool active);
// Property accesors
int id(void) { return _id; }
MAV_AUTOPILOT firmwareType(void) const { return _firmwareType; }
MAV_TYPE vehicleType(void) const { return _vehicleType; }
Q_INVOKABLE QString vehicleTypeName(void) const;
/// Returns the highest quality link available to the Vehicle. If you need to hold a reference to this link use
/// LinkManager::sharedLinkInterfaceForGet to get QSharedPointer for link.
LinkInterface* priorityLink(void) { return _priorityLink.data(); }
/// Sends a message to the specified link
/// @return true: message sent, false: Link no longer connected
bool sendMessageOnLink(LinkInterface* link, mavlink_message_t message);
/// 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);
/// Provides access to uas from vehicle. Temporary workaround until UAS is fully phased out.
UAS* uas(void) { return _uas; }
/// Provides access to uas from vehicle. Temporary workaround until AutoPilotPlugin is fully phased out.
AutoPilotPlugin* autopilotPlugin(void) { return _autopilotPlugin; }
/// Provides access to the Firmware Plugin for this Vehicle
FirmwarePlugin* firmwarePlugin(void) { return _firmwarePlugin; }
int manualControlReservedButtonCount(void);
MissionManager* missionManager(void) { return _missionManager; }
GeoFenceManager* geoFenceManager(void) { return _geoFenceManager; }
RallyPointManager* rallyPointManager(void) { return _rallyPointManager; }
bool armed(void) { return _armed; }
void setArmed(bool armed);
bool flightModeSetAvailable(void);
QStringList flightModes(void);
void setFlightMode(const QString& flightMode);
void setPriorityLinkByName(const QString& priorityLinkName);
bool hilMode(void);
void setHilMode(bool hilMode);
bool fixedWing(void) const;
bool multiRotor(void) const;
bool supportsThrottleModeCenterZero (void) const;
bool supportsNegativeThrust (void) const;
bool supportsRadio (void) const;
bool supportsJSButton (void) const;
bool supportsMotorInterference (void) const;
bool supportsTerrainFrame (void) const;
QString prearmError(void) const { return _prearmError; }
void setPrearmError(const QString& prearmError);
QmlObjectListModel* trajectoryPoints(void) { return &_mapTrajectoryList; }
QmlObjectListModel* cameraTriggerPoints(void) { return &_cameraTriggerPoints; }
QmlObjectListModel* adsbVehicles(void) { return &_adsbVehicles; }
int flowImageIndex() { return _flowImageIndex; }
//-- Mavlink Logging
void startMavlinkLog();
void stopMavlinkLog();
/// 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
/// @param sendMultiple Send multiple time to guarantee Vehicle reception
void requestDataStream(MAV_DATA_STREAM stream, uint16_t rate, bool sendMultiple = true);
typedef enum {
MessageNone,
MessageNormal,
MessageWarning,
MessageError
} MessageType_t;
bool messageTypeNone () { return _currentMessageType == MessageNone; }
bool messageTypeNormal () { return _currentMessageType == MessageNormal; }
bool messageTypeWarning () { return _currentMessageType == MessageWarning; }
bool messageTypeError () { return _currentMessageType == MessageError; }
int newMessageCount () { return _currentMessageCount; }
int messageCount () { return _messageCount; }
QString formatedMessages ();
QString formatedMessage () { return _formatedMessage; }
QString latestError () { return _latestError; }
float latitude () { return _coordinate.latitude(); }
float longitude () { return _coordinate.longitude(); }
bool mavPresent () { return _mav != NULL; }
int rcRSSI () { return _rcRSSI; }
bool px4Firmware () const { return _firmwareType == MAV_AUTOPILOT_PX4; }
bool apmFirmware () const { return _firmwareType == MAV_AUTOPILOT_ARDUPILOTMEGA; }
bool genericFirmware () const { return !px4Firmware() && !apmFirmware(); }
bool connectionLost () const { return _connectionLost; }
bool connectionLostEnabled () const { return _connectionLostEnabled; }
uint messagesReceived () { return _messagesReceived; }
uint messagesSent () { return _messagesSent; }
uint messagesLost () { return _messagesLost; }
bool flying () const { return _flying; }
bool landing () const { return _landing; }
bool vtolInFwdFlight () const { return _vtolInFwdFlight; }
uint8_t baseMode () const { return _base_mode; }
uint32_t customMode () const { return _custom_mode; }
bool isOfflineEditingVehicle () const { return _offlineEditingVehicle; }
QString brandImageIndoor () const;
QString brandImageOutdoor () const;
QStringList unhealthySensors () const;
int sensorsPresentBits () const { return _onboardControlSensorsPresent; }
int sensorsEnabledBits () const { return _onboardControlSensorsEnabled; }
int sensorsHealthBits () const { return _onboardControlSensorsHealth; }
int sensorsUnhealthyBits () const { return _onboardControlSensorsUnhealthy; }
QString missionFlightMode () const;
QString takeControlFlightMode () const;
double defaultCruiseSpeed () const { return _defaultCruiseSpeed; }
double defaultHoverSpeed () const { return _defaultHoverSpeed; }
QString firmwareTypeString () const;
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; }
int telemetryLNoise () { return _telemetryLNoise; }
int telemetryRNoise () { return _telemetryRNoise; }
bool highLatencyLink () const { return _highLatencyLink; }
/// Get the maximum MAVLink protocol version supported
/// @return the maximum version
unsigned maxProtoVersion () const { return _maxProtoVersion; }
Fact* roll (void) { return &_rollFact; }
Fact* pitch (void) { return &_pitchFact; }
Fact* heading (void) { return &_headingFact; }
Fact* rollRate (void) { return &_rollRateFact; }
Fact* pitchRate (void) { return &_pitchRateFact; }
Fact* yawRate (void) { return &_yawRateFact; }
Fact* airSpeed (void) { return &_airSpeedFact; }
Fact* groundSpeed (void) { return &_groundSpeedFact; }
Fact* climbRate (void) { return &_climbRateFact; }
Fact* altitudeRelative (void) { return &_altitudeRelativeFact; }
Fact* altitudeAMSL (void) { return &_altitudeAMSLFact; }
Fact* flightDistance (void) { return &_flightDistanceFact; }
Fact* distanceToHome (void) { return &_distanceToHomeFact; }
Fact* hobbs (void) { return &_hobbsFact; }
FactGroup* gpsFactGroup (void) { return &_gpsFactGroup; }
FactGroup* battery1FactGroup (void) { return &_battery1FactGroup; }
FactGroup* battery2FactGroup (void) { return &_battery2FactGroup; }
FactGroup* windFactGroup (void) { return &_windFactGroup; }
FactGroup* vibrationFactGroup (void) { return &_vibrationFactGroup; }
FactGroup* temperatureFactGroup (void) { return &_temperatureFactGroup; }
FactGroup* clockFactGroup (void) { return &_clockFactGroup; }
FactGroup* setpointFactGroup (void) { return &_setpointFactGroup; }
FactGroup* distanceSensorFactGroup (void) { return &_distanceSensorFactGroup; }
FactGroup* estimatorStatusFactGroup (void) { return &_estimatorStatusFactGroup; }
void setConnectionLostEnabled(bool connectionLostEnabled);
ParameterManager* parameterManager(void) { return _parameterManager; }
ParameterManager* parameterManager(void) const { return _parameterManager; }
bool containsLink(LinkInterface* link) { return _links.contains(link); }
/// 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
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);
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);
/// Same as sendMavCommand but available from Qml.
Q_INVOKABLE void sendCommand(int component, int command, bool showError, double param1 = 0.0f, double param2 = 0.0f, double param3 = 0.0f, double param4 = 0.0f, double param5 = 0.0f, double param6 = 0.0f, double param7 = 0.0f)
{ sendMavCommand(component, (MAV_CMD)command, showError, param1, param2, param3, param4, param5, param6, param7); }
int firmwareMajorVersion(void) const { return _firmwareMajorVersion; }
int firmwareMinorVersion(void) const { return _firmwareMinorVersion; }
int firmwarePatchVersion(void) const { return _firmwarePatchVersion; }
int firmwareVersionType(void) const { return _firmwareVersionType; }
int firmwareCustomMajorVersion(void) const { return _firmwareCustomMajorVersion; }
int firmwareCustomMinorVersion(void) const { return _firmwareCustomMinorVersion; }
int firmwareCustomPatchVersion(void) const { return _firmwareCustomPatchVersion; }
QString firmwareVersionTypeString(void) const;
void setFirmwareVersion(int majorVersion, int minorVersion, int patchVersion, FIRMWARE_VERSION_TYPE versionType = FIRMWARE_VERSION_TYPE_OFFICIAL);
void setFirmwareCustomVersion(int majorVersion, int minorVersion, int patchVersion);
QString gitHash(void) const { return _gitHash; }
quint64 vehicleUID(void) const { return _uid; }
QString vehicleUIDStr();
bool soloFirmware(void) const { return _soloFirmware; }
void setSoloFirmware(bool soloFirmware);
int defaultComponentId(void) { return _defaultComponentId; }
/// Sets the default component id for an offline editing vehicle