Skip to content
Vehicle.h 93.1 KiB
Newer Older
DonLakeFlyer's avatar
 
DonLakeFlyer committed
    };

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

DonLakeFlyer's avatar
 
DonLakeFlyer committed
    void startUAVCANBusConfig(void);
    void stopUAVCANBusConfig(void);

    Fact* roll                              () { return &_rollFact; }
    Fact* pitch                             () { return &_pitchFact; }
    Fact* heading                           () { return &_headingFact; }
    Fact* rollRate                          () { return &_rollRateFact; }
    Fact* pitchRate                         () { return &_pitchRateFact; }
    Fact* yawRate                           () { return &_yawRateFact; }
    Fact* airSpeed                          () { return &_airSpeedFact; }
    Fact* groundSpeed                       () { return &_groundSpeedFact; }
    Fact* climbRate                         () { return &_climbRateFact; }
    Fact* altitudeRelative                  () { return &_altitudeRelativeFact; }
    Fact* altitudeAMSL                      () { return &_altitudeAMSLFact; }
    Fact* flightDistance                    () { return &_flightDistanceFact; }
    Fact* distanceToHome                    () { return &_distanceToHomeFact; }
    Fact* missionItemIndex                  () { return &_missionItemIndexFact; }
    Fact* headingToNextWP                   () { return &_headingToNextWPFact; }
    Fact* headingToHome                     () { return &_headingToHomeFact; }
    Fact* distanceToGCS                     () { return &_distanceToGCSFact; }
    Fact* hobbs                             () { return &_hobbsFact; }
    Fact* throttlePct                       () { return &_throttlePctFact; }

    FactGroup* gpsFactGroup                 () { return &_gpsFactGroup; }
    FactGroup* battery1FactGroup            () { return &_battery1FactGroup; }
    FactGroup* battery2FactGroup            () { return &_battery2FactGroup; }
    FactGroup* windFactGroup                () { return &_windFactGroup; }
    FactGroup* vibrationFactGroup           () { return &_vibrationFactGroup; }
    FactGroup* temperatureFactGroup         () { return &_temperatureFactGroup; }
    FactGroup* clockFactGroup               () { return &_clockFactGroup; }
    FactGroup* setpointFactGroup            () { return &_setpointFactGroup; }
    FactGroup* distanceSensorFactGroup      () { return &_distanceSensorFactGroup; }
    FactGroup* estimatorStatusFactGroup     () { return &_estimatorStatusFactGroup; }
DonLakeFlyer's avatar
 
DonLakeFlyer committed
    FactGroup* terrainFactGroup             () { return &_terrainFactGroup; }
    void setConnectionLostEnabled(bool connectionLostEnabled);
DonLakeFlyer's avatar
 
DonLakeFlyer committed
    ParameterManager*               parameterManager    () { return _parameterManager; }
    ParameterManager*               parameterManager    () const { return _parameterManager; }
    FTPManager*                     ftpManager          () { return _ftpManager; }
    ComponentInformationManager*    compInfoManager     () { return _componentInformationManager; }
DonLakeFlyer's avatar
 
DonLakeFlyer committed
    VehicleObjectAvoidance* objectAvoidance     () { return _objectAvoidance; }
Don Gagne's avatar
Don Gagne committed
    static const int cMaxRcChannels = 18;

Don Gagne's avatar
Don Gagne committed
    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.
DonLakeFlyer's avatar
 
DonLakeFlyer committed
    ///     @param compId Component to send to.
    ///     @param command MAV_CMD to send
    ///     @param showError true: Display error to user if command failed, false:  no error shown
DonLakeFlyer's avatar
DonLakeFlyer committed
    /// Signals: mavCommandResult on success or failure
DonLakeFlyer's avatar
 
DonLakeFlyer committed
    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);
DonLakeFlyer's avatar
DonLakeFlyer committed
    /// Same as sendMavCommand but available from Qml.
DonLakeFlyer's avatar
 
DonLakeFlyer committed
    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)
    {
        sendMavCommand(
DonLakeFlyer's avatar
 
DonLakeFlyer committed
            compId, static_cast<MAV_CMD>(command),
            showError,
            static_cast<float>(param1),
            static_cast<float>(param2),
            static_cast<float>(param3),
            static_cast<float>(param4),
            static_cast<float>(param5),
            static_cast<float>(param6),
            static_cast<float>(param7));
    }
DonLakeFlyer's avatar
 
DonLakeFlyer committed
    /// Callback for sendMavCommandWithHandle
    ///     @param resultHandleData     Opaque data passed in to sendMavCommand call
    ///     @param commandResult        Ack result for command send
    ///     @param noReponseFromVehicle true: The vehicle did not responsed to the COMMAND_LONG message
    typedef void (*MavCmdResultHandler)(void* resultHandlerData, int compId, MAV_RESULT commandResult, bool noResponsefromVehicle);

    /// 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,
    } 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
    ///     @param noResponseToCommand  true: Vehicle never acked the REQUEST_MESSAGE command
    ///     @param messageNotReceived   true: Vehicle never sent requested message
    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);

    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;
    void setFirmwareVersion(int majorVersion, int minorVersion, int patchVersion, FIRMWARE_VERSION_TYPE versionType = FIRMWARE_VERSION_TYPE_OFFICIAL);
    void setFirmwareCustomVersion(int majorVersion, int minorVersion, int patchVersion);
    static const int versionNotSetValue = -1;
    QString gitHash() const { return _gitHash; }
    quint64 vehicleUID() const { return _uid; }
Gus Grubba's avatar
Gus Grubba committed
    QString vehicleUIDStr();
    bool soloFirmware() const { return _soloFirmware; }
    void setSoloFirmware(bool soloFirmware);

    int defaultComponentId() { return _defaultComponentId; }

    /// Sets the default component id for an offline editing vehicle
    void setOfflineEditingDefaultComponentId(int defaultComponentId);
Don Gagne's avatar
Don Gagne committed
    /// @return -1 = Unknown, Number of motors on vehicle
    int motorCount();
Don Gagne's avatar
Don Gagne committed

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

    /// @return true: X confiuration, false: Plus configuration
    bool xConfigMotors();
    /// @return Firmware plugin instance data associated with this Vehicle
    QObject* firmwarePluginInstanceData() { return _firmwarePluginInstanceData; }

    /// Sets the firmware plugin instance data associated with this Vehicle. This object will be parented to the Vehicle
    /// and destroyed when the vehicle goes away.
    void setFirmwarePluginInstanceData(QObject* firmwarePluginInstanceData);

    QString vehicleImageOpaque  () const;
    QString vehicleImageOutline () const;
    QString vehicleImageCompass () const;

DoinLakeFlyer's avatar
 
DoinLakeFlyer committed
    const QVariantList&         toolIndicators      ();
    const QVariantList&         modeIndicators      ();
    const QVariantList&         staticCameraList    () const;
DonLakeFlyer's avatar
 
DonLakeFlyer committed
    bool capabilitiesKnown      () const { return _capabilityBitsKnown; }
    uint64_t capabilityBits     () const { return _capabilityBits; }    // Change signalled by capabilityBitsChanged
DonLakeFlyer's avatar
 
DonLakeFlyer committed
    QGCCameraManager*           cameraManager       () { return _cameraManager; }
    QString                     hobbsMeter          ();
DonLakeFlyer's avatar
DonLakeFlyer committed
    /// The vehicle is responsible for making the initial request for the Plan.
    /// @return: true: initial request is complete, false: initial request is still in progress;
    bool initialPlanRequestComplete() const { return _initialPlanRequestComplete; }
    void forceInitialPlanRequestComplete();
    void _setFlying(bool flying);
    void _setLanding(bool landing);
DonLakeFlyer's avatar
DonLakeFlyer committed
    void _setHomePosition(QGeoCoordinate& homeCoord);
DonLakeFlyer's avatar
 
DonLakeFlyer committed
    void _setMaxProtoVersion(unsigned version);
    void _setMaxProtoVersionFromBothSources();
    /// Vehicle is about to be deleted
    void prepareDelete();

    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
    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; }
    bool        isROIEnabled            () { return _isROIEnabled; }
Gus Grubba's avatar
Gus Grubba committed

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

Gus Grubba's avatar
Gus Grubba committed
public slots:
DonLakeFlyer's avatar
 
DonLakeFlyer committed
    void setVtolInFwdFlight                 (bool vtolInFwdFlight);
DonLakeFlyer's avatar
 
DonLakeFlyer committed
    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
    void allLinksInactive               (Vehicle* vehicle);
    void coordinateChanged              (QGeoCoordinate coordinate);
    void joystickEnabledChanged         (bool enabled);
    void activeChanged                  (bool active);
    void mavlinkMessageReceived         (const mavlink_message_t& message);
    void homePositionChanged            (const QGeoCoordinate& homePosition);
Gus Grubba's avatar
Gus Grubba committed
    void armedPositionChanged();
    void armedChanged                   (bool armed);
    void flightModeChanged              (const QString& flightMode);
    void connectionLostChanged          (bool connectionLost);
    void connectionLostEnabledChanged   (bool connectionLostEnabled);
    void autoDisconnectChanged          (bool autoDisconnectChanged);
    void flyingChanged                  (bool flying);
    void landingChanged                 (bool landing);
    void guidedModeChanged              (bool guidedMode);
    void vtolInFwdFlightChanged         (bool vtolInFwdFlight);
    void prearmErrorChanged             (const QString& prearmError);
    void soloFirmwareChanged            (bool soloFirmware);
    void defaultCruiseSpeedChanged      (double cruiseSpeed);
    void defaultHoverSpeedChanged       (double hoverSpeed);
    void firmwareTypeChanged            ();
    void vehicleTypeChanged             ();
DonLakeFlyer's avatar
 
DonLakeFlyer committed
    void cameraManagerChanged           ();
    void hobbsMeterChanged              ();
    void capabilitiesKnownChanged       (bool capabilitiesKnown);
Don Gagne's avatar
Don Gagne committed
    void initialPlanRequestCompleteChanged(bool initialPlanRequestComplete);
    void capabilityBitsChanged          (uint64_t capabilityBits);
DoinLakeFlyer's avatar
 
DoinLakeFlyer committed
    void toolIndicatorsChanged          ();
    void modeIndicatorsChanged          ();
    void highLatencyLinkChanged         (bool highLatencyLink);
    void priorityLinkNameChanged        (const QString& priorityLinkName);
    void linksChanged                   ();
    void linksPropertiesChanged         ();
    void textMessageReceived            (int uasid, int componentid, int severity, QString text);
    void checkListStateChanged          ();
    void messagesReceivedChanged        ();
    void messagesSentChanged            ();
    void messagesLostChanged            ();
    void messageTypeChanged             ();
    void newMessageCountChanged         ();
    void messageCountChanged            ();
    void formatedMessagesChanged        ();
    void formatedMessageChanged         ();
    void latestErrorChanged             ();
    void longitudeChanged               ();
    void currentConfigChanged           ();
    void flowImageIndexChanged          ();
    void rcRSSIChanged                  (int rcRSSI);
    void telemetryRRSSIChanged          (int value);
    void telemetryLRSSIChanged          (int value);
    void telemetryRXErrorsChanged       (unsigned int value);
    void telemetryFixedChanged          (unsigned int value);
    void telemetryTXBufferChanged       (unsigned int value);
    void telemetryLNoiseChanged         (int value);
    void telemetryRNoiseChanged         (int value);
    void autoDisarmChanged              ();
    void flightModesChanged             ();
    void sensorsPresentBitsChanged      (int sensorsPresentBits);
    void sensorsEnabledBitsChanged      (int sensorsEnabledBits);
    void sensorsHealthBitsChanged       (int sensorsHealthBits);
    void sensorsUnhealthyBitsChanged    (int sensorsUnhealthyBits);
    void orbitActiveChanged             (bool orbitActive);
DonLakeFlyer's avatar
 
DonLakeFlyer committed
    void readyToFlyAvailableChanged     (bool readyToFlyAvailable);
    void readyToFlyChanged              (bool readyToFy);
    void allSensorsHealthyChanged       (bool allSensorsHealthy);

    void firmwareVersionChanged         ();
    void firmwareCustomVersionChanged   ();
    void gitHashChanged                 (QString hash);
    void vehicleUIDChanged              ();
DonLakeFlyer's avatar
 
DonLakeFlyer committed
    /// New RC channel values coming from RC_CHANNELS message
Don Gagne's avatar
Don Gagne committed
    ///     @param channelCount Number of available channels, cMaxRcChannels max
    ///     @param pwmValues -1 signals channel not available
    void rcChannelsChanged              (int channelCount, int pwmValues[cMaxRcChannels]);
Don Gagne's avatar
Don Gagne committed

    /// Remote control RSSI changed  (0% - 100%)
    void remoteControlRSSIChanged       (uint8_t rssi);
    void mavlinkRawImu                  (mavlink_message_t message);
    void mavlinkScaledImu1              (mavlink_message_t message);
    void mavlinkScaledImu2              (mavlink_message_t message);
    void mavlinkScaledImu3              (mavlink_message_t message);
    void mavlinkLogData                 (Vehicle* vehicle, uint8_t target_system, uint8_t target_component, uint16_t sequence, uint8_t first_message, QByteArray data, bool acked);
    /// Signalled in response to usage of sendMavCommand
    ///     @param vehicleId Vehicle which command was sent to
    ///     @param component Component which command was sent to
    ///     @param command MAV_CMD Command which was sent
    ///     @param result MAV_RESULT returned in ack
    ///     @param noResponseFromVehicle true: vehicle did not respond to command, false: vehicle responsed, MAV_RESULT in result
    void mavCommandResult               (int vehicleId, int component, int command, int result, bool noReponseFromVehicle);
    // MAVlink Serial Data
    void mavlinkSerialControl           (uint8_t device, uint8_t flags, uint16_t timeout, uint32_t baudrate, QByteArray data);
    // MAVLink protocol version
    void requestProtocolVersion         (unsigned version);
    void mavlinkStatusChanged           ();
Gus Grubba's avatar
Gus Grubba committed

    void gimbalRollChanged              ();
    void gimbalPitchChanged             ();
    void gimbalYawChanged               ();
    void gimbalDataChanged              ();
    void isROIEnabledChanged            ();
DonLakeFlyer's avatar
 
DonLakeFlyer committed
    void initialConnectComplete         ();
private slots:
    void _mavlinkMessageReceived        (LinkInterface* link, mavlink_message_t message);
    void _linkInactiveOrDeleted         (LinkInterface* link);
    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 _updateHighLatencyLink         (bool sendCommand = true);
    void _handleTextMessage             (int newCount);
    void _handletextMessageReceived     (UASMessage* message);
dogmaphobic's avatar
dogmaphobic committed
    /** @brief A new camera image has arrived */
    void _imageReady                    (UASInterface* uas);
    void _prearmErrorTimeout            ();
DonLakeFlyer's avatar
 
DonLakeFlyer committed
    void _firstMissionLoadComplete           ();
    void _firstGeoFenceLoadComplete          ();
    void _firstRallyPointLoadComplete        ();
    void _sendMavCommandAgain           ();
    void _clearCameraTriggerPoints      ();
    void _updateDistanceHeadingToHome   ();
    void _updateHeadingToNextWP         ();
    void _updateDistanceToGCS           ();
    void _updateHobbsMeter              ();
    void _vehicleParamLoaded            (bool ready);
    void _sendQGCTimeToVehicle          ();
    void _mavlinkMessageStatus          (int uasId, uint64_t totalSent, uint64_t totalReceived, uint64_t totalLoss, float lossPercent);

    void _trafficUpdate                 (bool alert, QString traffic_id, QString vehicle_id, QGeoCoordinate location, float heading);
    void _orbitTelemetryTimeout         ();
    void _updateFlightTime              ();
    bool _containsLink                  (LinkInterface* link);
    void _addLink                       (LinkInterface* link);
    void _joystickChanged               (Joystick* joystick);
    void _loadSettings                  ();
    void _saveSettings                  ();
    void _startJoystick                 (bool start);
    void _handlePing                    (LinkInterface* link, mavlink_message_t& message);
    void _handleHomePosition            (mavlink_message_t& message);
    void _handleHeartbeat               (mavlink_message_t& message);
    void _handleRadioStatus             (mavlink_message_t& message);
    void _handleRCChannels              (mavlink_message_t& message);
    void _handleBatteryStatus           (mavlink_message_t& message);
    void _handleSysStatus               (mavlink_message_t& message);
    void _handleWindCov                 (mavlink_message_t& message);
    void _handleVibration               (mavlink_message_t& message);
    void _handleExtendedSysState        (mavlink_message_t& message);
    void _handleCommandAck              (mavlink_message_t& message);
    void _handleCommandLong             (mavlink_message_t& message);
    void _handleGpsRawInt               (mavlink_message_t& message);
    void _handleGlobalPositionInt       (mavlink_message_t& message);
    void _handleAltitude                (mavlink_message_t& message);
    void _handleVfrHud                  (mavlink_message_t& message);
    void _handleScaledPressure          (mavlink_message_t& message);
    void _handleScaledPressure2         (mavlink_message_t& message);
    void _handleScaledPressure3         (mavlink_message_t& message);
    void _handleHighLatency             (mavlink_message_t& message);
    void _handleHighLatency2            (mavlink_message_t& message);
    void _handleAttitudeWorker          (double rollRadians, double pitchRadians, double yawRadians);
    void _handleAttitude                (mavlink_message_t& message);
    void _handleAttitudeQuaternion      (mavlink_message_t& message);
    void _handleAttitudeTarget          (mavlink_message_t& message);
    void _handleDistanceSensor          (mavlink_message_t& message);
    void _handleEstimatorStatus         (mavlink_message_t& message);
DoinLakeFlyer's avatar
 
DoinLakeFlyer committed
    void _handleStatusText              (mavlink_message_t& message);
    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);
    // ArduPilot dialect messages
#if !defined(NO_ARDUPILOT_DIALECT)
    void _handleCameraFeedback          (const mavlink_message_t& message);
    void _handleWind                    (mavlink_message_t& message);
    void _handleCameraImageCaptured     (const mavlink_message_t& message);
    void _handleADSBVehicle             (const mavlink_message_t& message);
    void _missionManagerError           (int errorCode, const QString& errorMsg);
    void _geoFenceManagerError          (int errorCode, const QString& errorMsg);
    void _rallyPointManagerError        (int errorCode, const QString& errorMsg);
    void _linkActiveChanged             (LinkInterface* link, bool active, int vehicleID);
    void _say                           (const QString& text);
    QString _vehicleIdSpeech            ();
    void _handleMavlinkLoggingData      (mavlink_message_t& message);
    void _handleMavlinkLoggingDataAcked (mavlink_message_t& message);
    void _ackMavlinkLogData             (uint16_t sequence);
    void _sendNextQueuedMavCommand      ();
    void _updatePriorityLink            (bool updateActive, bool sendCommand);
    void _commonInit                    ();
    void _setupAutoDisarmSignalling     ();
    void _setCapabilities               (uint64_t capabilityBits);
    void _updateArmed                   (bool armed);
    bool _apmArmingNotRequired          ();
    void _pidTuningAdjustRates          (bool setRatesForTuning);
    void _initializeCsv                 ();
    void _writeCsvLine                  ();
    void _flightTimerStart              ();
    void _flightTimerStop               ();
DoinLakeFlyer's avatar
 
DoinLakeFlyer committed
    void _batteryStatusWorker           (int batteryId, double voltage, double current, double batteryRemainingPct);
DoinLakeFlyer's avatar
 
DoinLakeFlyer committed
    void _chunkedStatusTextTimeout      (void);
    void _chunkedStatusTextCompleted    (uint8_t compId);
    int     _id;                    ///< Mavlink system id
    int     _defaultComponentId;
    bool    _active;
    bool    _offlineEditingVehicle; ///< This Vehicle is a "disconnected" vehicle for ui use while offline editing
    MAV_AUTOPILOT       _firmwareType;
    MAV_TYPE            _vehicleType;
    FirmwarePlugin*     _firmwarePlugin;
    QObject*            _firmwarePluginInstanceData;
    AutoPilotPlugin*    _autopilotPlugin;
Don Gagne's avatar
Don Gagne committed
    MAVLinkProtocol*    _mavlink;
    bool                _soloFirmware;
    QGCToolbox*         _toolbox;
    SettingsManager*    _settingsManager;
    QTimer              _csvLogTimer;
    QFile               _csvLogFile;
Don Gagne's avatar
Don Gagne committed
    QList<LinkInterface*> _links;
    bool            _joystickEnabled;
    QGeoCoordinate  _coordinate;
    QGeoCoordinate  _homePosition;
Gus Grubba's avatar
Gus Grubba committed
    QGeoCoordinate  _armedPosition;
    UASInterface*   _mav;
    int             _currentMessageCount;
    int             _messageCount;
    int             _currentErrorCount;
    int             _currentWarningCount;
    int             _currentNormalCount;
    MessageType_t   _currentMessageType;
    QString         _latestError;
    int             _updateCount;
dogmaphobic's avatar
dogmaphobic committed
    QString         _formatedMessage;
Don Gagne's avatar
Don Gagne committed
    int             _rcRSSI;
    double          _rcRSSIstore;
Don Gagne's avatar
Don Gagne committed
    bool            _autoDisconnect;    ///< true: Automatically disconnect vehicle when last connection goes away or lost heartbeat
Don Gagne's avatar
Don Gagne committed
    bool            _flying;
    bool            _vtolInFwdFlight;
    uint32_t        _onboardControlSensorsPresent;
    uint32_t        _onboardControlSensorsEnabled;
    uint32_t        _onboardControlSensorsHealth;
    uint32_t        _onboardControlSensorsUnhealthy;
DonLakeFlyer's avatar
 
DonLakeFlyer committed
    bool            _gpsRawIntMessageAvailable              = false;
    bool            _globalPositionIntMessageAvailable      = false;
    bool            _altitudeMessageAvailable               = false;
DonLakeFlyer's avatar
DonLakeFlyer committed
    double          _defaultCruiseSpeed;
    double          _defaultHoverSpeed;
Gus Grubba's avatar
Gus Grubba committed
    int             _telemetryRRSSI;
    int             _telemetryLRSSI;
    uint32_t        _telemetryRXErrors;
    uint32_t        _telemetryFixed;
    uint32_t        _telemetryTXBuffer;
    int             _telemetryLNoise;
    int             _telemetryRNoise;
DonLakeFlyer's avatar
 
DonLakeFlyer committed
    bool            _mavlinkProtocolRequestComplete         = false;
    unsigned        _mavlinkProtocolRequestMaxProtoVersion  = 0;
    unsigned        _maxProtoVersion                        = 0;
    bool            _capabilityBitsKnown                    = false;
    uint64_t        _capabilityBits;
Don Gagne's avatar
Don Gagne committed
    bool            _highLatencyLink;
    bool            _receivingAttitudeQuaternion;
DonLakeFlyer's avatar
 
DonLakeFlyer committed
    CheckList       _checkListState                         = CheckListNotSetup;
    bool            _readyToFlyAvailable                    = false;
    bool            _readyToFly                             = false;
    bool            _allSensorsHealthy                      = true;

    SysStatusSensorInfo _sysStatusSensorInfo;
DonLakeFlyer's avatar
 
DonLakeFlyer committed
    QGCCameraManager* _cameraManager = nullptr;
Don Gagne's avatar
Don Gagne committed
    QString             _prearmError;
    QTimer              _prearmErrorTimer;
    static const int    _prearmErrorTimeoutMSecs = 35 * 1000;   ///< Take away prearm error after 35 seconds

    // Lost connection handling
    bool                _connectionLost;
    bool                _connectionLostEnabled;

DonLakeFlyer's avatar
DonLakeFlyer committed
    bool                _initialPlanRequestComplete;

Don Gagne's avatar
Don Gagne committed
    MissionManager*     _missionManager;
    GeoFenceManager*    _geoFenceManager;
    RallyPointManager*  _rallyPointManager;
DonLakeFlyer's avatar
 
DonLakeFlyer committed
    ParameterManager*               _parameterManager               = nullptr;
DonLakeFlyer's avatar
 
DonLakeFlyer committed
    FTPManager*                     _ftpManager                     = nullptr;
DonLakeFlyer's avatar
 
DonLakeFlyer committed
    ComponentInformationManager*    _componentInformationManager    = nullptr;
    InitialConnectStateMachine*     _initialConnectStateMachine     = nullptr;
    VehicleObjectAvoidance*         _objectAvoidance                = nullptr;
#if defined(QGC_AIRMAP_ENABLED)
    AirspaceVehicleManager* _airspaceVehicleManager;
Don Gagne's avatar
Don Gagne committed
    bool    _armed;         ///< true: vehicle is armed
    uint8_t _base_mode;     ///< base_mode from HEARTBEAT
    uint32_t _custom_mode;  ///< custom_mode from HEARTBEAT

    /// 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;
    QList<SendMessageMultipleInfo_t> _sendMessageMultipleList;    ///< List of messages being sent multiple times
    static const int _sendMessageMultipleRetries = 5;
    static const int _sendMessageMultipleIntraMessageDelay = 500;
    QTimer  _sendMultipleTimer;
    int     _nextSendMessageMultipleIndex;
DonLakeFlyer's avatar
 
DonLakeFlyer committed
    QTimer                          _flightTimeUpdater;
DonLakeFlyer's avatar
 
DonLakeFlyer committed
    TrajectoryPoints*               _trajectoryPoints;
    QmlObjectListModel              _cameraTriggerPoints;
DonLakeFlyer's avatar
 
DonLakeFlyer committed
    //QMap<QString, ADSBVehicle*>     _trafficVehicleMap;
    // Toolbox references
dogmaphobic's avatar
dogmaphobic committed
    FirmwarePluginManager*      _firmwarePluginManager;
    JoystickManager*            _joystickManager;

    int                         _flowImageIndex;

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

    uint                _messagesReceived;
    uint                _messagesSent;
    uint                _messagesLost;
    uint8_t             _messageSeq;
    uint8_t             _compID;
    bool                _heardFrom;

Gus Grubba's avatar
Gus Grubba committed
    float               _curGimbalRoll  = 0.0f;
    float               _curGimbalPitch = 0.0f;
    float               _curGinmbalYaw  = 0.0f;
    bool                _haveGimbalData = false;
    bool                _isROIEnabled   = false;
Gus Grubba's avatar
Gus Grubba committed
    Joystick*           _activeJoystick = nullptr;

DoinLakeFlyer's avatar
 
DoinLakeFlyer committed
    bool _checkLatestStableFWDone = false;
Don Gagne's avatar
Don Gagne committed
    int _firmwareMajorVersion;
    int _firmwareMinorVersion;
    int _firmwarePatchVersion;
    int _firmwareCustomMajorVersion;
    int _firmwareCustomMinorVersion;
    int _firmwareCustomPatchVersion;
    FIRMWARE_VERSION_TYPE _firmwareVersionType;
    QString _gitHash;
Gus Grubba's avatar
Gus Grubba committed
    quint64 _uid;
    QElapsedTimer   _lastBatteryAnnouncement;
    int     _lastAnnouncedLowBatteryPercent;
    SharedLinkInterfacePointer _priorityLink;  // We always keep a reference to the priority link to manage shutdown ordering
    uint64_t    _mavlinkSentCount       = 0;
    uint64_t    _mavlinkReceivedCount   = 0;
    uint64_t    _mavlinkLossCount       = 0;
    float       _mavlinkLossPercent     = 0.0f;

Don Gagne's avatar
 
Don Gagne committed
    QMap<QString, QTime> _noisySpokenPrearmMap; ///< Used to prevent PreArm messages from being spoken too often

Don Gagne's avatar
 
Don Gagne committed
    // Orbit status values
    bool            _orbitActive;
    QGCMapCircle    _orbitMapCircle;
    QTimer          _orbitTelemetryTimer;
    static const int _orbitTelemetryTimeoutMsecs = 3000; // No telemetry for this amount and orbit will go inactive

Don Gagne's avatar
 
Don Gagne committed
    // PID Tuning telemetry mode
    bool            _pidTuningTelemetryMode;
    bool            _pidTuningWaitingForRates;
    QList<int>      _pidTuningMessages;
    QMap<int, int>  _pidTuningMessageRatesUsecs;

DoinLakeFlyer's avatar
 
DoinLakeFlyer committed
    // 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;

DonLakeFlyer's avatar
 
DonLakeFlyer committed
    /// 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);
DonLakeFlyer's avatar
 
DonLakeFlyer committed

    /// Waits for the specified msecs for the message to be received. Calls timeoutHandler if not received.
DonLakeFlyer's avatar
 
DonLakeFlyer committed
    void _waitForMavlinkMessage     (WaitForMavlinkMessageResultHandler resultHandler, void* resultHandlerData, int messageId, int timeoutMsecs);
DonLakeFlyer's avatar
 
DonLakeFlyer committed
    void _waitForMavlinkMessageClear(void);

DonLakeFlyer's avatar
 
DonLakeFlyer committed
    int                                 _waitForMavlinkMessageId                = 0;
    bool                                _waitForMavlinkMessageTimeoutActive     = false;
    int                                 _waitForMavlinkMessageTimeoutMsecs      = 0;
DonLakeFlyer's avatar
 
DonLakeFlyer committed
    QElapsedTimer                       _waitForMavlinkMessageElapsed;
DonLakeFlyer's avatar
 
DonLakeFlyer committed
    WaitForMavlinkMessageResultHandler  _waitForMavlinkMessageResultHandler     = nullptr;
    void*                               _waitForMavlinkMessageResultHandlerData = nullptr;

    void _waitForMavlinkMessageMessageReceived(const mavlink_message_t& message);

    // requestMessage handling
    typedef struct {
DonLakeFlyer's avatar
 
DonLakeFlyer committed
        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;
DonLakeFlyer's avatar
 
DonLakeFlyer committed
    } RequestMessageInfo_t;

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

    typedef struct {
        int                 compId;
        bool                commandInt;     // true: use COMMAND_INT, false: use COMMAND_LONG
        MAV_CMD             command;
        MAV_FRAME           frame;
        float               rgParam[7];
        bool                showError;
        bool                requestMessage; // true: this is from a requestMessage call
        MavCmdResultHandler resultHandler;
        void*               resultHandlerData;
    } MavCommandQueueEntry_t;

    QQueue<MavCommandQueueEntry_t>  _mavCommandQueue;
    QTimer                          _mavCommandAckTimer;
    int                             _mavCommandRetryCount;
    static const int                _mavCommandMaxRetryCount =              3;
    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);
DonLakeFlyer's avatar
 
DonLakeFlyer committed

Don Gagne's avatar
Don Gagne committed
    // FactGroup facts

    Fact _rollFact;
    Fact _pitchFact;
    Fact _headingFact;
DonLakeFlyer's avatar
DonLakeFlyer committed
    Fact _rollRateFact;
    Fact _pitchRateFact;
    Fact _yawRateFact;
Don Gagne's avatar
Don Gagne committed
    Fact _groundSpeedFact;
    Fact _airSpeedFact;
    Fact _climbRateFact;
    Fact _altitudeRelativeFact;
    Fact _altitudeAMSLFact;
    Fact _flightDistanceFact;
    Fact _flightTimeFact;
    Fact _distanceToHomeFact;
    Fact _headingToNextWPFact;
Don Gagne's avatar
 
Don Gagne committed
    Fact _headingToHomeFact;
Don Gagne's avatar
 
Don Gagne committed
    Fact _distanceToGCSFact;
    Fact _hobbsFact;
Don Gagne's avatar
 
Don Gagne committed
    Fact _throttlePctFact;
    VehicleGPSFactGroup             _gpsFactGroup;
DonLakeFlyer's avatar
DonLakeFlyer committed
    VehicleBatteryFactGroup         _battery1FactGroup;
    VehicleBatteryFactGroup         _battery2FactGroup;
    VehicleWindFactGroup            _windFactGroup;
    VehicleVibrationFactGroup       _vibrationFactGroup;
    VehicleTemperatureFactGroup     _temperatureFactGroup;
    VehicleClockFactGroup           _clockFactGroup;
    VehicleSetpointFactGroup        _setpointFactGroup;
    VehicleDistanceSensorFactGroup  _distanceSensorFactGroup;
    VehicleEstimatorStatusFactGroup _estimatorStatusFactGroup;
DonLakeFlyer's avatar
 
DonLakeFlyer committed
    TerrainFactGroup                _terrainFactGroup;

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

    static const char* _rollFactName;
    static const char* _pitchFactName;
    static const char* _headingFactName;
DonLakeFlyer's avatar
DonLakeFlyer committed
    static const char* _rollRateFactName;
    static const char* _pitchRateFactName;
    static const char* _yawRateFactName;
Don Gagne's avatar
Don Gagne committed
    static const char* _groundSpeedFactName;
    static const char* _airSpeedFactName;
    static const char* _climbRateFactName;
    static const char* _altitudeRelativeFactName;
    static const char* _altitudeAMSLFactName;
    static const char* _flightDistanceFactName;
    static const char* _flightTimeFactName;
    static const char* _distanceToHomeFactName;
    static const char* _missionItemIndexFactName;
    static const char* _headingToNextWPFactName;
Don Gagne's avatar
 
Don Gagne committed
    static const char* _headingToHomeFactName;
Don Gagne's avatar
 
Don Gagne committed
    static const char* _distanceToGCSFactName;
    static const char* _hobbsFactName;
Don Gagne's avatar
 
Don Gagne committed
    static const char* _throttlePctFactName;
Don Gagne's avatar
Don Gagne committed
    static const char* _gpsFactGroupName;
DonLakeFlyer's avatar
DonLakeFlyer committed
    static const char* _battery1FactGroupName;
    static const char* _battery2FactGroupName;
Don Gagne's avatar
Don Gagne committed
    static const char* _windFactGroupName;
    static const char* _vibrationFactGroupName;
    static const char* _temperatureFactGroupName;
dheideman's avatar
dheideman committed
    static const char* _clockFactGroupName;
    static const char* _distanceSensorFactGroupName;
    static const char* _estimatorStatusFactGroupName;
DonLakeFlyer's avatar
 
DonLakeFlyer committed
    static const char* _terrainFactGroupName;
Don Gagne's avatar
Don Gagne committed

    static const int _vehicleUIUpdateRateMSecs = 100;

    // Settings keys
    static const char* _settingsGroup;
    static const char* _joystickEnabledSettingsKey;
DonLakeFlyer's avatar
 
DonLakeFlyer committed

    friend class InitialConnectStateMachine;