Vehicle.h 74.6 KB
Newer Older
1 2
/****************************************************************************
 *
Gus Grubba's avatar
Gus Grubba committed
3
 * (c) 2009-2020 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org>
4 5 6 7 8
 *
 * QGroundControl is licensed according to the terms in the file
 * COPYING.md in the root of the source code directory.
 *
 ****************************************************************************/
dogmaphobic's avatar
dogmaphobic committed
9

10
#pragma once
11

12
#include <QElapsedTimer>
13
#include <QObject>
14
#include <QVariantList>
15
#include <QGeoCoordinate>
16
#include <QTime>
17
#include <QQueue>
18

Don Gagne's avatar
Don Gagne committed
19
#include "FactGroup.h"
20
#include "QGCMAVLink.h"
21
#include "QmlObjectListModel.h"
Don Gagne's avatar
Don Gagne committed
22
#include "MAVLinkProtocol.h"
dogmaphobic's avatar
dogmaphobic committed
23
#include "UASMessageHandler.h"
24
#include "SettingsFact.h"
25
#include "QGCMapCircle.h"
26
#include "TerrainFactGroup.h"
27
#include "SysStatusSensorInfo.h"
28 29 30 31 32 33 34
#include "VehicleClockFactGroup.h"
#include "VehicleDistanceSensorFactGroup.h"
#include "VehicleWindFactGroup.h"
#include "VehicleGPSFactGroup.h"
#include "VehicleSetpointFactGroup.h"
#include "VehicleTemperatureFactGroup.h"
#include "VehicleVibrationFactGroup.h"
35
#include "VehicleEscStatusFactGroup.h"
36
#include "VehicleEstimatorStatusFactGroup.h"
37 38 39 40 41
#include "VehicleLinkManager.h"
#include "MissionManager.h"
#include "GeoFenceManager.h"
#include "RallyPointManager.h"
#include "FTPManager.h"
42

43 44
class UAS;
class UASInterface;
45
class FirmwarePlugin;
46
class FirmwarePluginManager;
47
class AutoPilotPlugin;
48
class ParameterManager;
49
class JoystickManager;
dogmaphobic's avatar
dogmaphobic committed
50
class UASMessage;
51
class SettingsManager;
52
class QGCCameraManager;
Gus Grubba's avatar
Gus Grubba committed
53
class Joystick;
Gus Grubba's avatar
Gus Grubba committed
54
class VehicleObjectAvoidance;
55
class TrajectoryPoints;
56
class TerrainProtocolHandler;
57
class ComponentInformationManager;
58
class VehicleBatteryFactGroup;
59 60 61
class SendMavCommandWithSignallingTest;
class SendMavCommandWithHandlerTest;
class RequestMessageTest;
62 63
class LinkInterface;
class LinkManager;
64
class InitialConnectStateMachine;
Gus Grubba's avatar
Gus Grubba committed
65

66 67 68
#if defined(QGC_AIRMAP_ENABLED)
class AirspaceVehicleManager;
#endif
69 70 71

Q_DECLARE_LOGGING_CATEGORY(VehicleLog)

Don Gagne's avatar
Don Gagne committed
72
class Vehicle : public FactGroup
73 74
{
    Q_OBJECT
dogmaphobic's avatar
dogmaphobic committed
75

76 77 78 79 80 81 82 83
    friend class InitialConnectStateMachine;
    friend class VehicleLinkManager;
    friend class VehicleBatteryFactGroup;           // Allow VehicleBatteryFactGroup to call _addFactGroup
    friend class SendMavCommandWithSignallingTest;  // Unit test
    friend class SendMavCommandWithHandlerTest;     // Unit test
    friend class RequestMessageTest;                // Unit test


84
public:
85 86
    Vehicle(LinkInterface*          link,
            int                     vehicleId,
87
            int                     defaultComponentId,
88 89 90 91
            MAV_AUTOPILOT           firmwareType,
            MAV_TYPE                vehicleType,
            FirmwarePluginManager*  firmwarePluginManager,
            JoystickManager*        joystickManager);
92

93 94 95 96
    // Pass these into the offline constructor to create an offline vehicle which tracks the offline vehicle settings
    static const MAV_AUTOPILOT    MAV_AUTOPILOT_TRACK = static_cast<MAV_AUTOPILOT>(-1);
    static const MAV_TYPE         MAV_TYPE_TRACK = static_cast<MAV_TYPE>(-1);

97 98 99 100
    // The following is used to create a disconnected Vehicle for use while offline editing.
    Vehicle(MAV_AUTOPILOT           firmwareType,
            MAV_TYPE                vehicleType,
            FirmwarePluginManager*  firmwarePluginManager,
101
            QObject*                parent = nullptr);
102

103
    ~Vehicle();
dogmaphobic's avatar
dogmaphobic committed
104

105 106 107 108 109
    /// 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,
110
        SysStatusSensorAbsolutePressure =       MAV_SYS_STATUS_SENSOR_ABSOLUTE_PRESSURE,
111 112 113 114 115 116 117 118 119 120 121 122 123 124 125 126 127 128 129 130 131 132 133 134 135
        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)

136 137 138 139 140 141 142
    enum CheckList {
        CheckListNotSetup = 0,
        CheckListPassed,
        CheckListFailed,
    };
    Q_ENUM(CheckList)

143 144 145 146 147 148 149 150 151 152 153 154 155 156 157 158 159 160 161 162 163 164 165 166 167 168 169 170 171 172 173 174 175 176 177 178 179 180 181 182 183 184 185 186 187 188 189 190 191 192 193 194 195 196 197 198 199 200 201 202 203 204 205 206 207 208 209 210 211 212 213 214 215 216 217 218 219 220 221 222 223 224 225 226 227 228 229 230 231 232 233 234 235 236 237 238
    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(QGeoCoordinate       armedPosition               READ armedPosition                                                  NOTIFY armedPositionChanged)
    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(QStringList          extraJoystickFlightModes    READ extraJoystickFlightModes                                       NOTIFY flightModesChanged)
    Q_PROPERTY(QString              flightMode                  READ flightMode                 WRITE setFlightMode                 NOTIFY flightModeChanged)
    Q_PROPERTY(TrajectoryPoints*    trajectoryPoints            MEMBER _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              formattedMessages           READ formattedMessages                                              NOTIFY formattedMessagesChanged)
    Q_PROPERTY(QString              latestError                 READ latestError                                                    NOTIFY latestErrorChanged)
    Q_PROPERTY(bool                 joystickEnabled             READ joystickEnabled            WRITE setJoystickEnabled            NOTIFY joystickEnabledChanged)
    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(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(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(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              smartRTLFlightMode          READ smartRTLFlightMode                                             CONSTANT)
    Q_PROPERTY(bool                 supportsSmartRTL            READ supportsSmartRTL                                               CONSTANT)
    Q_PROPERTY(QString              landFlightMode              READ landFlightMode                                                 CONSTANT)
    Q_PROPERTY(QString              takeControlFlightMode       READ takeControlFlightMode                                          CONSTANT)
    Q_PROPERTY(QString              followFlightMode            READ followFlightMode                                               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         toolIndicators              READ toolIndicators                                                 NOTIFY toolIndicatorsChanged)
    Q_PROPERTY(QVariantList         modeIndicators              READ modeIndicators                                                 NOTIFY modeIndicatorsChanged)
    Q_PROPERTY(bool              initialPlanRequestComplete     READ initialPlanRequestComplete                                     NOTIFY initialPlanRequestCompleteChanged)
    Q_PROPERTY(QVariantList         staticCameraList            READ staticCameraList                                               CONSTANT)
    Q_PROPERTY(QGCCameraManager*    cameraManager               READ cameraManager                                                  NOTIFY cameraManagerChanged)
    Q_PROPERTY(QString              hobbsMeter                  READ hobbsMeter                                                     NOTIFY hobbsMeterChanged)
    Q_PROPERTY(bool                 vtolInFwdFlight             READ vtolInFwdFlight            WRITE setVtolInFwdFlight            NOTIFY vtolInFwdFlightChanged)
    Q_PROPERTY(bool                 supportsTerrainFrame        READ supportsTerrainFrame                                           NOTIFY firmwareTypeChanged)
    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)
    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)
    Q_PROPERTY(bool                 isROIEnabled                READ isROIEnabled                                                   NOTIFY isROIEnabledChanged)
    Q_PROPERTY(CheckList            checkListState              READ checkListState             WRITE setCheckListState             NOTIFY checkListStateChanged)
    Q_PROPERTY(bool                 readyToFlyAvailable         READ readyToFlyAvailable                                            NOTIFY readyToFlyAvailableChanged)  ///< true: readyToFly signalling is available on this vehicle
    Q_PROPERTY(bool                 readyToFly                  READ readyToFly                                                     NOTIFY readyToFlyChanged)
    Q_PROPERTY(QObject*             sysStatusSensorInfo         READ sysStatusSensorInfo                                            CONSTANT)
    Q_PROPERTY(bool                 allSensorsHealthy           READ allSensorsHealthy                                              NOTIFY allSensorsHealthyChanged)    //< true: all sensors in SYS_STATUS reported as healthy
239

240 241 242 243
    // The following properties relate to Orbit status
    Q_PROPERTY(bool             orbitActive     READ orbitActive        NOTIFY orbitActiveChanged)
    Q_PROPERTY(QGCMapCircle*    orbitMapCircle  READ orbitMapCircle     CONSTANT)

244
    // Vehicle state used for guided control
Don Gagne's avatar
Don Gagne committed
245 246 247 248 249 250
    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
251
    Q_PROPERTY(bool     roiModeSupported        READ roiModeSupported                               CONSTANT)                   ///< Orbit mode is supported by this vehicle
Don Gagne's avatar
Don Gagne committed
252 253
    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
254

Gus Grubba's avatar
Gus Grubba committed
255
    Q_PROPERTY(ParameterManager*        parameterManager    READ parameterManager   CONSTANT)
256
    Q_PROPERTY(VehicleLinkManager*      vehicleLinkManager  READ vehicleLinkManager CONSTANT)
Gus Grubba's avatar
Gus Grubba committed
257
    Q_PROPERTY(VehicleObjectAvoidance*  objectAvoidance     READ objectAvoidance    CONSTANT)
258

Don Gagne's avatar
Don Gagne committed
259 260 261 262 263
    // 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
264 265 266
    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
267 268 269 270 271
    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)
272
    Q_PROPERTY(Fact* flightDistance     READ flightDistance     CONSTANT)
273
    Q_PROPERTY(Fact* distanceToHome     READ distanceToHome     CONSTANT)
274
    Q_PROPERTY(Fact* missionItemIndex   READ missionItemIndex   CONSTANT)
275
    Q_PROPERTY(Fact* headingToNextWP    READ headingToNextWP    CONSTANT)
276
    Q_PROPERTY(Fact* headingToHome      READ headingToHome      CONSTANT)
277
    Q_PROPERTY(Fact* distanceToGCS      READ distanceToGCS      CONSTANT)
278
    Q_PROPERTY(Fact* hobbs              READ hobbs              CONSTANT)
279
    Q_PROPERTY(Fact* throttlePct        READ throttlePct        CONSTANT)
Don Gagne's avatar
Don Gagne committed
280

281 282 283 284 285 286
    Q_PROPERTY(FactGroup*           gps             READ gpsFactGroup               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)
287
    Q_PROPERTY(FactGroup*           escStatus       READ escStatusFactGroup         CONSTANT)
288 289 290 291
    Q_PROPERTY(FactGroup*           estimatorStatus READ estimatorStatusFactGroup   CONSTANT)
    Q_PROPERTY(FactGroup*           terrain         READ terrainFactGroup           CONSTANT)
    Q_PROPERTY(FactGroup*           distanceSensors READ distanceSensorFactGroup    CONSTANT)
    Q_PROPERTY(QmlObjectListModel*  batteries       READ batteries                  CONSTANT)
Don Gagne's avatar
Don Gagne committed
292

293 294 295 296 297 298 299 300 301
    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
302 303
    Q_PROPERTY(quint64  vehicleUID                  READ vehicleUID                 NOTIFY vehicleUIDChanged)
    Q_PROPERTY(QString  vehicleUIDStr               READ vehicleUIDStr              NOTIFY vehicleUIDChanged)
304

305 306
    /// Resets link status counters
    Q_INVOKABLE void resetCounters  ();
307

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

Gus Grubba's avatar
Gus Grubba committed
311
    Q_INVOKABLE void virtualTabletJoystickValue(double roll, double pitch, double yaw, double thrust);
Don Gagne's avatar
Don Gagne committed
312

Don Gagne's avatar
Don Gagne committed
313
    /// Command vehicle to return to launch
DonLakeFlyer's avatar
DonLakeFlyer committed
314
    Q_INVOKABLE void guidedModeRTL(bool smartRTL);
Don Gagne's avatar
Don Gagne committed
315 316

    /// Command vehicle to land at current location
317
    Q_INVOKABLE void guidedModeLand();
Don Gagne's avatar
Don Gagne committed
318 319

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

322
    /// @return The minimum takeoff altitude (relative) for guided takeoff.
323
    Q_INVOKABLE double minimumTakeoffAltitude();
324

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

328 329 330
    /// 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
331

332
    /// Command vehicle to orbit given center point
DonLakeFlyer's avatar
DonLakeFlyer committed
333
    ///     @param centerCoord Orit around this point
334
    ///     @param radius Distance from vehicle to centerCoord
DonLakeFlyer's avatar
DonLakeFlyer committed
335 336
    ///     @param amslAltitude Desired vehicle altitude
    Q_INVOKABLE void guidedModeOrbit(const QGeoCoordinate& centerCoord, double radius, double amslAltitude);
337

Gus Grubba's avatar
Gus Grubba committed
338 339 340
    /// Command vehicle to keep given point as ROI
    ///     @param centerCoord ROI coordinates
    Q_INVOKABLE void guidedModeROI(const QGeoCoordinate& centerCoord);
341
    Q_INVOKABLE void stopGuidedModeROI();
Gus Grubba's avatar
Gus Grubba committed
342

Don Gagne's avatar
Don Gagne committed
343 344
    /// Command vehicle to pause at current location. If vehicle supports guide mode, vehicle will be left
    /// in guided mode after pause.
345
    Q_INVOKABLE void pauseVehicle();
Don Gagne's avatar
Don Gagne committed
346 347

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

350
    /// Command vehicle to abort landing
351
    Q_INVOKABLE void abortLanding(double climbOutAltitude);
352

353
    Q_INVOKABLE void startMission();
354

355 356 357
    /// Alter the current mission item on the vehicle
    Q_INVOKABLE void setCurrentMissionSequence(int seq);

358 359 360
    /// Reboot vehicle
    Q_INVOKABLE void rebootVehicle();

dogmaphobic's avatar
dogmaphobic committed
361 362 363
    /// Clear Messages
    Q_INVOKABLE void clearMessages();

Don Gagne's avatar
Don Gagne committed
364
    Q_INVOKABLE void sendPlan(QString planFile);
Don Gagne's avatar
Don Gagne committed
365

366 367 368 369 370
    /// 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
371 372 373
    /// Test motor
    ///     @param motor Motor number, 1-based
    ///     @param percent 0-no power, 100-full power
374 375
    ///     @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
376

Don Gagne's avatar
Don Gagne committed
377 378
    Q_INVOKABLE void setPIDTuningTelemetryMode(bool pidTuning);

Gus Grubba's avatar
Gus Grubba committed
379 380 381 382
    Q_INVOKABLE void gimbalControlValue (double pitch, double yaw);
    Q_INVOKABLE void gimbalPitchStep    (int direction);
    Q_INVOKABLE void gimbalYawStep      (int direction);
    Q_INVOKABLE void centerGimbal       ();
383
    Q_INVOKABLE void forceArm           ();
384

DoinLakeFlyer's avatar
DoinLakeFlyer committed
385 386 387 388 389 390
    /// 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);

391 392
    /// Removes the vehicle from the system
    Q_INVOKABLE void closeVehicle(void) { _vehicleLinkManager->closeVehicle(); }
DoinLakeFlyer's avatar
DoinLakeFlyer committed
393

394
#if !defined(NO_ARDUPILOT_DIALECT)
395
    Q_INVOKABLE void flashBootloader();
396 397
#endif

398 399 400 401 402 403
    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
404

405
    // Property accessors
Don Gagne's avatar
Don Gagne committed
406

407 408
    QGeoCoordinate coordinate() { return _coordinate; }
    QGeoCoordinate armedPosition    () { return _armedPosition; }
dogmaphobic's avatar
dogmaphobic committed
409

Gus Grubba's avatar
Gus Grubba committed
410
    void updateFlightDistance(double distance);
411

412 413 414
    bool joystickEnabled            ();
    void setJoystickEnabled         (bool enabled);
    void sendJoystickDataThreadSafe (float roll, float pitch, float yaw, float thrust, quint16 buttons);
dogmaphobic's avatar
dogmaphobic committed
415

416
    // Property accesors
417 418 419 420
    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
421

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

426 427 428
    /// 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
429

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

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

Don Gagne's avatar
Don Gagne committed
436
    /// Provides access to the Firmware Plugin for this Vehicle
437
    FirmwarePlugin* firmwarePlugin() { return _firmwarePlugin; }
dogmaphobic's avatar
dogmaphobic committed
438 439


440
    QGeoCoordinate homePosition();
dogmaphobic's avatar
dogmaphobic committed
441

Gus Grubba's avatar
Gus Grubba committed
442 443
    bool armed      () { return _armed; }
    void setArmed   (bool armed);
Don Gagne's avatar
Don Gagne committed
444

445 446 447 448
    bool flightModeSetAvailable             ();
    QStringList flightModes                 ();
    QStringList extraJoystickFlightModes    ();
    QString flightMode                      () const;
449
    void setFlightMode                      (const QString& flightMode);
Don Gagne's avatar
Don Gagne committed
450

451 452 453 454 455
    bool fixedWing() const;
    bool multiRotor() const;
    bool vtol() const;
    bool rover() const;
    bool sub() const;
456

457 458 459 460 461 462
    bool supportsThrottleModeCenterZero () const;
    bool supportsNegativeThrust         ();
    bool supportsRadio                  () const;
    bool supportsJSButton               () const;
    bool supportsMotorInterference      () const;
    bool supportsTerrainFrame           () const;
463

Don Gagne's avatar
Don Gagne committed
464 465
    void setGuidedMode(bool guidedMode);

466
    QString prearmError() const { return _prearmError; }
Don Gagne's avatar
Don Gagne committed
467 468
    void setPrearmError(const QString& prearmError);

469
    QmlObjectListModel* cameraTriggerPoints () { return &_cameraTriggerPoints; }
dogmaphobic's avatar
dogmaphobic committed
470 471 472

    int  flowImageIndex() { return _flowImageIndex; }

473 474 475 476
    //-- Mavlink Logging
    void startMavlinkLog();
    void stopMavlinkLog();

477 478 479
    /// 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
480 481
    ///     @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
482

483 484 485 486
    // The follow method are used to turn on/off the tracking of settings updates for firmware/vehicle type on offline vehicles.
    void trackFirmwareVehicleTypeChanges(void);
    void stopTrackingFirmwareVehicleTypeChanges(void);

487 488 489 490 491 492
    typedef enum {
        MessageNone,
        MessageNormal,
        MessageWarning,
        MessageError
    } MessageType_t;
dogmaphobic's avatar
dogmaphobic committed
493

494 495 496 497 498 499 500 501 502 503 504 505 506 507 508 509 510 511 512 513 514 515 516 517 518 519 520 521 522 523 524 525 526 527 528 529 530 531 532 533 534 535 536 537 538 539 540 541 542 543 544 545 546 547 548 549 550
    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         formattedMessages           ();
    QString         latestError                 () { return _latestError; }
    float           latitude                    () { return static_cast<float>(_coordinate.latitude()); }
    float           longitude                   () { return static_cast<float>(_coordinate.longitude()); }
    bool            mavPresent                  () { return _mav != nullptr; }
    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(); }
    uint            messagesReceived            () { return _messagesReceived; }
    uint            messagesSent                () { return _messagesSent; }
    uint            messagesLost                () { return _messagesLost; }
    bool            flying                      () const { return _flying; }
    bool            landing                     () const { return _landing; }
    bool            guidedMode                  () const;
    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;
    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); }
    QString         missionFlightMode           () const;
    QString         pauseFlightMode             () const;
    QString         rtlFlightMode               () const;
    QString         smartRTLFlightMode          () const;
    bool            supportsSmartRTL            () const;
    QString         landFlightMode              () const;
    QString         takeControlFlightMode       () const;
    QString         followFlightMode            () 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            autoDisarm                  ();
    bool            orbitActive                 () const { return _orbitActive; }
    QGCMapCircle*   orbitMapCircle              () { return &_orbitMapCircle; }
    bool            readyToFlyAvailable         () { return _readyToFlyAvailable; }
    bool            readyToFly                  () { return _readyToFly; }
    bool            allSensorsHealthy           () { return _allSensorsHealthy; }
    QObject*        sysStatusSensorInfo         () { return &_sysStatusSensorInfo; }
551

552 553 554
    /// Get the maximum MAVLink protocol version supported
    /// @return the maximum version
    unsigned        maxProtoVersion         () const { return _maxProtoVersion; }
555

556 557 558 559 560 561 562 563 564 565 566 567 568 569 570 571 572 573
    enum CalibrationType {
        CalibrationRadio,
        CalibrationGyro,
        CalibrationMag,
        CalibrationAccel,
        CalibrationLevel,
        CalibrationEsc,
        CalibrationCopyTrims,
        CalibrationAPMCompassMot,
        CalibrationAPMPressureAirspeed,
        CalibrationAPMPreFlight,
        CalibrationPX4Airspeed,
        CalibrationPX4Pressure,
    };

    void startCalibration   (CalibrationType calType);
    void stopCalibration    (void);

574 575 576
    void startUAVCANBusConfig(void);
    void stopUAVCANBusConfig(void);

577 578 579 580 581 582 583 584 585 586 587 588 589
    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; }
590
    Fact* missionItemIndex                  () { return &_missionItemIndexFact; }
591 592 593 594 595 596 597 598 599 600 601 602 603
    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* windFactGroup                () { return &_windFactGroup; }
    FactGroup* vibrationFactGroup           () { return &_vibrationFactGroup; }
    FactGroup* temperatureFactGroup         () { return &_temperatureFactGroup; }
    FactGroup* clockFactGroup               () { return &_clockFactGroup; }
    FactGroup* setpointFactGroup            () { return &_setpointFactGroup; }
    FactGroup* distanceSensorFactGroup      () { return &_distanceSensorFactGroup; }
604
    FactGroup* escStatusFactGroup           () { return &_escStatusFactGroup; }
605
    FactGroup* estimatorStatusFactGroup     () { return &_estimatorStatusFactGroup; }
606
    FactGroup* terrainFactGroup             () { return &_terrainFactGroup; }
607
    QmlObjectListModel* batteries           () { return &_batteryFactGroupListModel; }
Don Gagne's avatar
Don Gagne committed
608

609 610 611
    MissionManager*                 missionManager      () { return _missionManager; }
    GeoFenceManager*                geoFenceManager     () { return _geoFenceManager; }
    RallyPointManager*              rallyPointManager   () { return _rallyPointManager; }
612 613
    ParameterManager*               parameterManager    () { return _parameterManager; }
    ParameterManager*               parameterManager    () const { return _parameterManager; }
614
    VehicleLinkManager*             vehicleLinkManager  () { return _vehicleLinkManager; }
615 616
    FTPManager*                     ftpManager          () { return _ftpManager; }
    ComponentInformationManager*    compInfoManager     () { return _componentInformationManager; }
617
    VehicleObjectAvoidance*         objectAvoidance     () { return _objectAvoidance; }
dogmaphobic's avatar
dogmaphobic committed
618

Don Gagne's avatar
Don Gagne committed
619 620
    static const int cMaxRcChannels = 18;

621 622
    /// 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.
623
    ///     @param compId Component to send to.
624 625
    ///     @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
626
    /// Signals: mavCommandResult on success or failure
627 628
    void sendMavCommand(int compId, 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 compId, 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
629

630
    /// Same as sendMavCommand but available from Qml.
631 632 633 634 635
    Q_INVOKABLE void sendCommand(int compId, 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);

    typedef enum {
        MavCmdResultCommandResultOnly,          ///< commandResult specifies full success/fail info
        MavCmdResultFailureNoResponseToCommand, ///< No response from vehicle to command
636
        MavCmdResultFailureDuplicateCommand,    ///< Unable to send command since duplicate is already being waited on for response
637 638 639
    } MavCmdResultFailureCode_t;

    /// Callback for sendMavCommandWithHandler
640 641
    ///     @param resultHandleData     Opaque data passed in to sendMavCommand call
    ///     @param commandResult        Ack result for command send
642 643
    ///     @param failureCode          Failure reason
    typedef void (*MavCmdResultHandler)(void* resultHandlerData, int compId, MAV_RESULT commandResult, MavCmdResultFailureCode_t failureCode);
644 645 646 647 648 649 650 651 652 653 654

    /// Sends the command and calls the callback with the result
    ///     @param resultHandler    Callback for result, nullptr for no callback
    ///     @param resultHandleData Opaque data passed through callback
    void sendMavCommandWithHandler(MavCmdResultHandler resultHandler, void* resultHandlerData, int compId, MAV_CMD command, 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);

    typedef enum {
        RequestMessageNoFailure,
        RequestMessageFailureCommandError,
        RequestMessageFailureCommandNotAcked,
        RequestMessageFailureMessageNotReceived,
655
        RequestMessageFailureDuplicateCommand,    ///< Unabled to send command since duplicate is already being waited on for response
656 657 658 659 660
    } RequestMessageResultHandlerFailureCode_t;

    /// Callback for requestMessage
    ///     @param resultHandlerData    Opaque data which was passed in to requestMessage call
    ///     @param commandResult        Result from ack to REQUEST_MESSAGE command
661 662
    ///     @param failureCode          Failure code
    ///     @param message              Received message which was requested
663 664 665 666 667 668 669
    typedef void (*RequestMessageResultHandler)(void* resultHandlerData, MAV_RESULT commandResult, RequestMessageResultHandlerFailureCode_t failureCode, const mavlink_message_t& message);

    /// Requests the vehicle to send the specified message. Will retry a number of times.
    ///     @param resultHandler Callback for result
    ///     @param resultHandlerData Opaque data passed back to resultHandler
    void requestMessage(RequestMessageResultHandler resultHandler, void* resultHandlerData, int compId, int messageId, float param1 = 0.0f, float param2 = 0.0f, float param3 = 0.0f, float param4 = 0.0f, float param5 = 0.0f);

670 671 672 673 674 675 676 677
    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;
678
    void setFirmwareVersion(int majorVersion, int minorVersion, int patchVersion, FIRMWARE_VERSION_TYPE versionType = FIRMWARE_VERSION_TYPE_OFFICIAL);
679
    void setFirmwareCustomVersion(int majorVersion, int minorVersion, int patchVersion);
680
    static const int versionNotSetValue = -1;
Don Gagne's avatar
Don Gagne committed
681

682 683
    QString gitHash() const { return _gitHash; }
    quint64 vehicleUID() const { return _uid; }
Gus Grubba's avatar
Gus Grubba committed
684
    QString vehicleUIDStr();
685

686
    bool soloFirmware() const { return _soloFirmware; }
687 688
    void setSoloFirmware(bool soloFirmware);

689
    int defaultComponentId() { return _defaultComponentId; }
690 691 692

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

Don Gagne's avatar
Don Gagne committed
694
    /// @return -1 = Unknown, Number of motors on vehicle
695
    int motorCount();
Don Gagne's avatar
Don Gagne committed
696 697

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

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

703
    /// @return Firmware plugin instance data associated with this Vehicle
704
    QObject* firmwarePluginInstanceData() { return _firmwarePluginInstanceData; }
705 706 707 708 709

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

710 711 712 713
    QString vehicleImageOpaque  () const;
    QString vehicleImageOutline () const;
    QString vehicleImageCompass () const;

714 715
    const QVariantList&         toolIndicators      ();
    const QVariantList&         modeIndicators      ();
716
    const QVariantList&         staticCameraList    () const;
717

718
    bool capabilitiesKnown      () const { return _capabilityBitsKnown; }
719
    uint64_t capabilityBits     () const { return _capabilityBits; }    // Change signalled by capabilityBitsChanged
720

721
    QGCCameraManager*           cameraManager       () { return _cameraManager; }
722
    QString                     hobbsMeter          ();
723

DonLakeFlyer's avatar
DonLakeFlyer committed
724 725
    /// 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;
726
    bool initialPlanRequestComplete() const { return _initialPlanRequestComplete; }
DonLakeFlyer's avatar
DonLakeFlyer committed
727

728
    void forceInitialPlanRequestComplete();
729

730 731
    void _setFlying(bool flying);
    void _setLanding(bool landing);
DonLakeFlyer's avatar
DonLakeFlyer committed
732
    void _setHomePosition(QGeoCoordinate& homeCoord);
733 734
    void _setMaxProtoVersion(unsigned version);
    void _setMaxProtoVersionFromBothSources();
DonLakeFlyer's avatar
DonLakeFlyer committed
735

736 737 738
    /// Vehicle is about to be deleted
    void prepareDelete();

739 740 741 742 743
    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
744 745 746 747
    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; }
748
    bool        isROIEnabled            () { return _isROIEnabled; }
Gus Grubba's avatar
Gus Grubba committed
749

750 751 752
    CheckList   checkListState          () { return _checkListState; }
    void        setCheckListState       (CheckList cl)  { _checkListState = cl; emit checkListStateChanged(); }

Gus Grubba's avatar
Gus Grubba committed
753
public slots:
754
    void setVtolInFwdFlight                 (bool vtolInFwdFlight);
755 756
    void _offlineFirmwareTypeSettingChanged (QVariant varFirmwareType); // Should only be used by MissionControler to set firmware from Plan file
    void _offlineVehicleTypeSettingChanged  (QVariant varVehicleType);  // Should only be used by MissionController to set vehicle type from Plan file
Gus Grubba's avatar
Gus Grubba committed
757

758
signals:
759 760 761 762
    void coordinateChanged              (QGeoCoordinate coordinate);
    void joystickEnabledChanged         (bool enabled);
    void mavlinkMessageReceived         (const mavlink_message_t& message);
    void homePositionChanged            (const QGeoCoordinate& homePosition);
763
    void armedPositionChanged();
764 765 766 767 768 769 770 771 772 773 774 775
    void armedChanged                   (bool armed);
    void flightModeChanged              (const QString& flightMode);
    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 defaultCruiseSpeedChanged      (double cruiseSpeed);
    void defaultHoverSpeedChanged       (double hoverSpeed);
    void firmwareTypeChanged            ();
    void vehicleTypeChanged             ();
776
    void cameraManagerChanged           ();
777 778
    void hobbsMeterChanged              ();
    void capabilitiesKnownChanged       (bool capabilitiesKnown);
Don Gagne's avatar
Don Gagne committed
779
    void initialPlanRequestCompleteChanged(bool initialPlanRequestComplete);
780
    void capabilityBitsChanged          (uint64_t capabilityBits);
781 782
    void toolIndicatorsChanged          ();
    void modeIndicatorsChanged          ();
783 784 785 786 787 788 789 790
    void textMessageReceived            (int uasid, int componentid, int severity, QString text);
    void checkListStateChanged          ();
    void messagesReceivedChanged        ();
    void messagesSentChanged            ();
    void messagesLostChanged            ();
    void messageTypeChanged             ();
    void newMessageCountChanged         ();
    void messageCountChanged            ();
791 792
    void formattedMessagesChanged       ();
    void newFormattedMessage            (QString formattedMessage);
793 794 795 796 797 798 799 800 801 802 803 804 805 806 807 808 809 810 811
    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);
812 813 814
    void readyToFlyAvailableChanged     (bool readyToFlyAvailable);
    void readyToFlyChanged              (bool readyToFy);
    void allSensorsHealthyChanged       (bool allSensorsHealthy);
815 816 817 818 819

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

821
    /// New RC channel values coming from RC_CHANNELS message
Don Gagne's avatar
Don Gagne committed
822 823
    ///     @param channelCount Number of available channels, cMaxRcChannels max
    ///     @param pwmValues -1 signals channel not available
824
    void rcChannelsChanged              (int channelCount, int pwmValues[cMaxRcChannels]);
Don Gagne's avatar
Don Gagne committed
825 826

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

829 830 831 832
    void mavlinkRawImu                  (mavlink_message_t message);
    void mavlinkScaledImu1              (mavlink_message_t message);
    void mavlinkScaledImu2              (mavlink_message_t message);
    void mavlinkScaledImu3              (mavlink_message_t message);
833

834
    // Mavlink Log Download
835
    void mavlinkLogData                 (Vehicle* vehicle, uint8_t target_system, uint8_t target_component, uint16_t sequence, uint8_t first_message, QByteArray data, bool acked);
836

837
    /// Signalled in response to usage of sendMavCommand
838 839 840 841 842 843
    ///     @param vehicleId        Vehicle which command was sent to
    ///     @param targetComponent  Component which command was sent to
    ///     @param command          Command which was sent
    ///     @param ackResult        MAV_RESULT returned in ack
    ///     @param failureCode      More detailed failure code Vehicle::MavCmdResultFailureCode_t
    void mavCommandResult               (int vehicleId, int targetComponent, int command, int ackResult, int failureCode);
844

845
    // MAVlink Serial Data
846
    void mavlinkSerialControl           (uint8_t device, uint8_t flags, uint16_t timeout, uint32_t baudrate, QByteArray data);
847

848
    // MAVLink protocol version
849 850
    void requestProtocolVersion         (unsigned version);
    void mavlinkStatusChanged           ();
Gus Grubba's avatar
Gus Grubba committed
851

852 853 854 855 856
    void gimbalRollChanged              ();
    void gimbalPitchChanged             ();
    void gimbalYawChanged               ();
    void gimbalDataChanged              ();
    void isROIEnabledChanged            ();
857
    void initialConnectComplete         ();
858

859
private slots:
860 861 862 863 864 865 866 867 868 869 870 871 872 873 874
    void _mavlinkMessageReceived            (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);
    void _offlineCruiseSpeedSettingChanged  (QVariant value);
    void _offlineHoverSpeedSettingChanged   (QVariant value);
    void _handleTextMessage                 (int newCount);
    void _handletextMessageReceived         (UASMessage* message);
    void _imageReady                        (UASInterface* uas);    ///< A new camera image has arrived
    void _prearmErrorTimeout                ();
    void _firstMissionLoadComplete          ();
    void _firstGeoFenceLoadComplete         ();
    void _firstRallyPointLoadComplete       ();
875
    void _sendMavCommandResponseTimeoutCheck();
876 877 878 879 880 881 882 883 884 885 886 887
    void _clearCameraTriggerPoints          ();
    void _updateDistanceHeadingToHome       ();
    void _updateMissionItemIndex            ();
    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 _updateFlightTime                  ();
888

889
private:
890 891 892 893 894 895 896 897 898 899 900 901 902 903 904 905 906
    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 _handleBatteryStatus           (mavlink_message_t& message);
    void _handleSysStatus               (mavlink_message_t& message);
    void _handleExtendedSysState        (mavlink_message_t& message);
    void _handleCommandAck              (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);
907
    void _handleHighLatency             (mavlink_message_t& message);
908 909 910 911
    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);
912
    void _handleStatusText              (mavlink_message_t& message);
913 914 915 916
    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);
917 918
    // ArduPilot dialect messages
#if !defined(NO_ARDUPILOT_DIALECT)
919
    void _handleCameraFeedback          (const mavlink_message_t& message);
920
#endif
921 922 923 924 925 926 927 928 929 930 931 932 933 934 935 936 937 938 939 940
    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 _say                           (const QString& text);
    QString _vehicleIdSpeech            ();
    void _handleMavlinkLoggingData      (mavlink_message_t& message);
    void _handleMavlinkLoggingDataAcked (mavlink_message_t& message);
    void _ackMavlinkLogData             (uint16_t sequence);
    void _commonInit                    ();
    void _setupAutoDisarmSignalling     ();
    void _setCapabilities               (uint64_t capabilityBits);
    void _updateArmed                   (bool armed);
    bool _apmArmingNotRequired          ();
    void _pidTuningAdjustRates          (bool setRatesForTuning);
    void _initializeCsv                 ();
    void _writeCsvLine                  ();
    void _flightTimerStart              ();
    void _flightTimerStop               ();
941 942
    void _chunkedStatusTextTimeout      (void);
    void _chunkedStatusTextCompleted    (uint8_t compId);
Don Gagne's avatar
Don Gagne committed
943

944
    static void _rebootCommandResultHandler(void* resultHandlerData, int compId, MAV_RESULT commandResult, MavCmdResultFailureCode_t failureCode);
945

946
    int     _id;                    ///< Mavlink system id
947
    int     _defaultComponentId;
948
    bool    _offlineEditingVehicle = false; ///< true: This Vehicle is a "disconnected" vehicle for ui use while offline editing
dogmaphobic's avatar
dogmaphobic committed
949

950
    MAV_AUTOPILOT       _firmwareType;
951
    MAV_TYPE            _vehicleType;
952 953 954 955 956 957 958
    FirmwarePlugin*     _firmwarePlugin = nullptr;
    QObject*            _firmwarePluginInstanceData = nullptr;
    AutoPilotPlugin*    _autopilotPlugin = nullptr;
    MAVLinkProtocol*    _mavlink = nullptr;
    bool                _soloFirmware = false;
    QGCToolbox*         _toolbox = nullptr;
    SettingsManager*    _settingsManager = nullptr;
dogmaphobic's avatar
dogmaphobic committed
959

960 961
    QTimer              _csvLogTimer;
    QFile               _csvLogFile;
962

963
    bool            _joystickEnabled = false;
dogmaphobic's avatar
dogmaphobic committed
964

965
    UAS* _uas = nullptr;
dogmaphobic's avatar
dogmaphobic committed
966

967
    QGeoCoordinate  _coordinate;
968
    QGeoCoordinate  _homePosition;
969
    QGeoCoordinate  _armedPosition;
dogmaphobic's avatar
dogmaphobic committed
970

971 972 973 974 975 976 977
    UASInterface*   _mav = nullptr;
    int             _currentMessageCount = 0;
    int             _messageCount = 0;
    int             _currentErrorCount = 0;
    int             _currentWarningCount = 0;
    int             _currentNormalCount = 0;
    MessageType_t   _currentMessageType = MessageNone;
978
    QString         _latestError;
979 980 981 982 983 984 985 986 987 988
    int             _updateCount = 0;
    int             _rcRSSI = 255;
    double          _rcRSSIstore = 255;
    bool            _flying = false;
    bool            _landing = false;
    bool            _vtolInFwdFlight = false;
    uint32_t        _onboardControlSensorsPresent = 0;
    uint32_t        _onboardControlSensorsEnabled = 0;
    uint32_t        _onboardControlSensorsHealth = 0;
    uint32_t        _onboardControlSensorsUnhealthy = 0;
989 990 991
    bool            _gpsRawIntMessageAvailable              = false;
    bool            _globalPositionIntMessageAvailable      = false;
    bool            _altitudeMessageAvailable               = false;
992 993 994 995 996 997 998 999 1000
    double          _defaultCruiseSpeed = qQNaN();
    double          _defaultHoverSpeed = qQNaN();
    int             _telemetryRRSSI = 0;
    int             _telemetryLRSSI = 0;
    uint32_t        _telemetryRXErrors = 0;
    uint32_t        _telemetryFixed = 0;
    uint32_t        _telemetryTXBuffer = 0;
    int             _telemetryLNoise = 0;
    int             _telemetryRNoise = 0;
1001 1002 1003 1004
    bool            _mavlinkProtocolRequestComplete         = false;
    unsigned        _mavlinkProtocolRequestMaxProtoVersion  = 0;
    unsigned        _maxProtoVersion                        = 0;
    bool            _capabilityBitsKnown                    = false;
1005
    uint64_t        _capabilityBits;
1006
    bool            _receivingAttitudeQuaternion = false;
1007 1008 1009 1010 1011 1012
    CheckList       _checkListState                         = CheckListNotSetup;
    bool            _readyToFlyAvailable                    = false;
    bool            _readyToFly                             = false;
    bool            _allSensorsHealthy                      = true;

    SysStatusSensorInfo _sysStatusSensorInfo;
dogmaphobic's avatar
dogmaphobic committed
1013

1014
    QGCCameraManager* _cameraManager = nullptr;
1015

Don Gagne's avatar
Don Gagne committed
1016 1017 1018 1019
    QString             _prearmError;
    QTimer              _prearmErrorTimer;
    static const int    _prearmErrorTimeoutMSecs = 35 * 1000;   ///< Take away prearm error after 35 seconds

1020
    bool                _initialPlanRequestComplete = false;
1021

1022
    LinkManager*                    _linkManager                    = nullptr;
1023
    ParameterManager*               _parameterManager               = nullptr;
1024 1025
    FirmwarePluginManager*          _firmwarePluginManager          = nullptr;
    JoystickManager*                _joystickManager                = nullptr;
1026 1027
    ComponentInformationManager*    _componentInformationManager    = nullptr;
    VehicleObjectAvoidance*         _objectAvoidance                = nullptr;
1028
#if defined(QGC_AIRMAP_ENABLED)
1029
    AirspaceVehicleManager*         _airspaceVehicleManager         = nullptr;
1030
#endif
dogmaphobic's avatar
dogmaphobic committed
1031

1032 1033 1034
    bool    _armed = false;         ///< true: vehicle is armed
    uint8_t _base_mode = 0;     ///< base_mode from HEARTBEAT
    uint32_t _custom_mode = 0;  ///< custom_mode from HEARTBEAT
1035 1036 1037 1038 1039 1040

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

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

1044 1045
    static const int _sendMessageMultipleRetries = 5;
    static const int _sendMessageMultipleIntraMessageDelay = 500;
dogmaphobic's avatar
dogmaphobic committed
1046

1047
    QTimer  _sendMultipleTimer;
1048
    int     _nextSendMessageMultipleIndex = 0;
dogmaphobic's avatar
dogmaphobic committed
1049

1050
    QElapsedTimer                   _flightTimer;
DonLakeFlyer's avatar
DonLakeFlyer committed
1051
    QTimer                          _flightTimeUpdater;
1052
    TrajectoryPoints*               _trajectoryPoints = nullptr;
1053
    QmlObjectListModel              _cameraTriggerPoints;
1054
    //QMap<QString, ADSBVehicle*>     _trafficVehicleMap;
1055

1056
    // Toolbox references
dogmaphobic's avatar
dogmaphobic committed
1057

1058
    int                         _flowImageIndex = 0;
dogmaphobic's avatar
dogmaphobic committed
1059

1060
    bool _allLinksRemovedSent = false; ///< true: allLinkRemoved signal already sent one time
Don Gagne's avatar
Don Gagne committed
1061

1062 1063 1064 1065 1066 1067
    uint                _messagesReceived = 0;
    uint                _messagesSent = 0;
    uint                _messagesLost = 0;
    uint8_t             _messageSeq = 0;
    uint8_t             _compID = 0;
    bool                _heardFrom = false;
1068

Gus Grubba's avatar
Gus Grubba committed
1069 1070 1071 1072
    float               _curGimbalRoll  = 0.0f;
    float               _curGimbalPitch = 0.0f;
    float               _curGinmbalYaw  = 0.0f;
    bool                _haveGimbalData = false;
1073
    bool                _isROIEnabled   = false;
Gus Grubba's avatar
Gus Grubba committed
1074 1075
    Joystick*           _activeJoystick = nullptr;

1076
    bool _checkLatestStableFWDone = false;
1077 1078 1079 1080 1081 1082 1083
    int _firmwareMajorVersion = versionNotSetValue;
    int _firmwareMinorVersion = versionNotSetValue;
    int _firmwarePatchVersion = versionNotSetValue;
    int _firmwareCustomMajorVersion = versionNotSetValue;
    int _firmwareCustomMinorVersion = versionNotSetValue;
    int _firmwareCustomPatchVersion = versionNotSetValue;
    FIRMWARE_VERSION_TYPE _firmwareVersionType = FIRMWARE_VERSION_TYPE_OFFICIAL;
Don Gagne's avatar
Don Gagne committed
1084

1085
    QString _gitHash;
1086
    quint64 _uid = 0;
1087

1088 1089 1090 1091 1092
    uint64_t    _mavlinkSentCount       = 0;
    uint64_t    _mavlinkReceivedCount   = 0;
    uint64_t    _mavlinkLossCount       = 0;
    float       _mavlinkLossPercent     = 0.0f;

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

1095
    // Orbit status values
1096
    bool            _orbitActive = false;
1097 1098 1099 1100
    QGCMapCircle    _orbitMapCircle;
    QTimer          _orbitTelemetryTimer;
    static const int _orbitTelemetryTimeoutMsecs = 3000; // No telemetry for this amount and orbit will go inactive

1101
    // PID Tuning telemetry mode
1102 1103
    bool            _pidTuningTelemetryMode = false;
    bool            _pidTuningWaitingForRates = false;
1104 1105 1106
    QList<int>      _pidTuningMessages;
    QMap<int, int>  _pidTuningMessageRatesUsecs;

1107 1108 1109 1110 1111 1112 1113 1114 1115
    // 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;

1116 1117 1118 1119 1120
    /// Callback for waitForMavlinkMessage
    ///     @param resultHandleData     Opaque data passed in to waitForMavlinkMessage call
    ///     @param commandResult        Ack result for command send
    ///     @param noReponseFromVehicle true: The vehicle did not responsed to the COMMAND_LONG message
    typedef void (*WaitForMavlinkMessageResultHandler)(void* resultHandlerData, bool noResponsefromVehicle, const mavlink_message_t& message);
1121 1122

    /// Waits for the specified msecs for the message to be received. Calls timeoutHandler if not received.
1123
    void _waitForMavlinkMessage     (WaitForMavlinkMessageResultHandler resultHandler, void* resultHandlerData, int messageId, int timeoutMsecs);
1124 1125
    void _waitForMavlinkMessageClear(void);

1126 1127 1128
    int                                 _waitForMavlinkMessageId                = 0;
    bool                                _waitForMavlinkMessageTimeoutActive     = false;
    int                                 _waitForMavlinkMessageTimeoutMsecs      = 0;
1129
    QElapsedTimer                       _waitForMavlinkMessageElapsed;
1130 1131 1132 1133 1134 1135
    WaitForMavlinkMessageResultHandler  _waitForMavlinkMessageResultHandler     = nullptr;
    void*                               _waitForMavlinkMessageResultHandlerData = nullptr;

    void _waitForMavlinkMessageMessageReceived(const mavlink_message_t& message);

    // requestMessage handling
1136
    typedef struct RequestMessageInfo {
1137 1138 1139 1140 1141 1142
        bool                        commandAckReceived; // We keep track of the ack/message being received since the order in which this will come in is random
        bool                        messageReceived;    // We only delete the allocated RequestMessageInfo_t when both happen (or the message wait times out)
        int                         msgId;
        int                         compId;
        RequestMessageResultHandler resultHandler;
        void*                       resultHandlerData;
1143 1144
    } RequestMessageInfo_t;

1145
    static void _requestMessageCmdResultHandler             (void* resultHandlerData, int compId, MAV_RESULT result, MavCmdResultFailureCode_t failureCode);
1146 1147
    static void _requestMessageWaitForMessageResultHandler  (void* resultHandlerData, bool noResponsefromVehicle, const mavlink_message_t& message);

1148
    typedef struct MavCommandListEntry {
1149 1150
        int                 targetCompId        = MAV_COMP_ID_AUTOPILOT1;
        bool                useCommandInt       = false;
1151 1152
        MAV_CMD             command;
        MAV_FRAME           frame;
1153 1154 1155
        float               rgParam[7]          = { 0 };
        bool                showError           = true;
        bool                requestMessage      = false;                        // true: this is from a requestMessage call
1156
        MavCmdResultHandler resultHandler;
1157 1158 1159 1160 1161 1162 1163 1164 1165 1166 1167 1168 1169 1170 1171 1172 1173 1174
        void*               resultHandlerData   = nullptr;
        int                 maxTries            = _mavCommandMaxRetryCount;
        int                 tryCount            = 0;
        QElapsedTimer       elapsedTimer;
        int                 ackTimeoutMSecs     = _mavCommandAckTimeoutMSecs;
    } MavCommandListEntry_t;

    QList<MavCommandListEntry_t>    _mavCommandList;
    QTimer                          _mavCommandResponseCheckTimer;
    static const int                _mavCommandMaxRetryCount                = 3;
    static const int                _mavCommandResponseCheckTimeoutMSecs    = 500;
    static const int                _mavCommandAckTimeoutMSecs              = 3000;
    static const int                _mavCommandAckTimeoutMSecsHighLatency   = 120000;

    void _sendMavCommandWorker  (bool commandInt, bool requestMessage, bool showError, MavCmdResultHandler resultHandler, void* resultHandlerData, int compId, MAV_CMD command, MAV_FRAME frame, float param1, float param2, float param3, float param4, float param5, float param6, float param7);
    void _sendMavCommandFromList(MavCommandListEntry_t& commandEntry);
    int  _findMavCommandListEntryIndex(int targetCompId, MAV_CMD command);
    bool _sendMavCommandShouldRetry(MAV_CMD command);
1175

1176 1177
    QMap<uint8_t /* batteryId */, uint8_t /* MAV_BATTERY_CHARGE_STATE_OK */> _lowestBatteryChargeStateAnnouncedMap;

Don Gagne's avatar
Don Gagne committed
1178 1179 1180 1181 1182
    // FactGroup facts

    Fact _rollFact;
    Fact _pitchFact;
    Fact _headingFact;
DonLakeFlyer's avatar
DonLakeFlyer committed
1183 1184 1185
    Fact _rollRateFact;
    Fact _pitchRateFact;
    Fact _yawRateFact;
Don Gagne's avatar
Don Gagne committed
1186 1187 1188 1189 1190
    Fact _groundSpeedFact;
    Fact _airSpeedFact;
    Fact _climbRateFact;
    Fact _altitudeRelativeFact;
    Fact _altitudeAMSLFact;
1191
    Fact _flightDistanceFact;
1192
    Fact _flightTimeFact;
1193
    Fact _distanceToHomeFact;
1194
    Fact _missionItemIndexFact;
1195
    Fact _headingToNextWPFact;
1196
    Fact _headingToHomeFact;
1197
    Fact _distanceToGCSFact;
1198
    Fact _hobbsFact;
1199
    Fact _throttlePctFact;
Don Gagne's avatar
Don Gagne committed
1200

1201 1202 1203 1204 1205 1206 1207
    VehicleGPSFactGroup             _gpsFactGroup;
    VehicleWindFactGroup            _windFactGroup;
    VehicleVibrationFactGroup       _vibrationFactGroup;
    VehicleTemperatureFactGroup     _temperatureFactGroup;
    VehicleClockFactGroup           _clockFactGroup;
    VehicleSetpointFactGroup        _setpointFactGroup;
    VehicleDistanceSensorFactGroup  _distanceSensorFactGroup;
1208
    VehicleEscStatusFactGroup       _escStatusFactGroup;
1209
    VehicleEstimatorStatusFactGroup _estimatorStatusFactGroup;
1210
    TerrainFactGroup                _terrainFactGroup;
1211
    QmlObjectListModel              _batteryFactGroupListModel;
1212 1213

    TerrainProtocolHandler* _terrainProtocolHandler = nullptr;
Don Gagne's avatar
Don Gagne committed
1214

1215 1216 1217 1218 1219 1220 1221
    MissionManager*                 _missionManager             = nullptr;
    GeoFenceManager*                _geoFenceManager            = nullptr;
    RallyPointManager*              _rallyPointManager          = nullptr;
    VehicleLinkManager*             _vehicleLinkManager         = nullptr;
    FTPManager*                     _ftpManager                 = nullptr;
    InitialConnectStateMachine*     _initialConnectStateMachine = nullptr;

Don Gagne's avatar
Don Gagne committed
1222 1223 1224
    static const char* _rollFactName;
    static const char* _pitchFactName;
    static const char* _headingFactName;
DonLakeFlyer's avatar
DonLakeFlyer committed
1225 1226 1227
    static const char* _rollRateFactName;
    static const char* _pitchRateFactName;
    static const char* _yawRateFactName;
Don Gagne's avatar
Don Gagne committed
1228 1229 1230 1231 1232
    static const char* _groundSpeedFactName;
    static const char* _airSpeedFactName;
    static const char* _climbRateFactName;
    static const char* _altitudeRelativeFactName;
    static const char* _altitudeAMSLFactName;
1233
    static const char* _flightDistanceFactName;
1234
    static const char* _flightTimeFactName;
1235
    static const char* _distanceToHomeFactName;
1236
    static const char* _missionItemIndexFactName;
1237
    static const char* _headingToNextWPFactName;
1238
    static const char* _headingToHomeFactName;
1239
    static const char* _distanceToGCSFactName;
1240
    static const char* _hobbsFactName;
1241
    static const char* _throttlePctFactName;
Don Gagne's avatar
Don Gagne committed
1242

Don Gagne's avatar
Don Gagne committed
1243
    static const char* _gpsFactGroupName;
Don Gagne's avatar
Don Gagne committed
1244
    static const char* _windFactGroupName;
1245
    static const char* _vibrationFactGroupName;
1246
    static const char* _temperatureFactGroupName;
dheideman's avatar
dheideman committed
1247
    static const char* _clockFactGroupName;
1248
    static const char* _distanceSensorFactGroupName;
1249
    static const char* _escStatusFactGroupName;
1250
    static const char* _estimatorStatusFactGroupName;
1251
    static const char* _terrainFactGroupName;
Don Gagne's avatar
Don Gagne committed
1252

1253
    static const int _vehicleUIUpdateRateMSecs      = 100;
Don Gagne's avatar
Don Gagne committed
1254

1255
    // Settings keys
1256
    static const char* _settingsGroup;
1257
    static const char* _joystickEnabledSettingsKey;
1258
};
1259 1260

Q_DECLARE_METATYPE(Vehicle::MavCmdResultFailureCode_t)