Skip to content
Snippets Groups Projects
Vehicle.h 42.1 KiB
Newer Older
  • Learn to ignore specific revisions
  • /****************************************************************************
     *
     *   (c) 2009-2016 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org>
     *
     * QGroundControl is licensed according to the terms in the file
     * COPYING.md in the root of the source code directory.
     *
     ****************************************************************************/
    
    
    /// @file
    ///     @author Don Gagne <don@thegagnes.com>
    
    #ifndef Vehicle_H
    #define Vehicle_H
    
    #include <QObject>
    
    #include <QGeoCoordinate>
    
    #include <QElapsedTimer>
    
    Don Gagne's avatar
    Don Gagne committed
    #include "FactGroup.h"
    
    #include "LinkInterface.h"
    #include "QGCMAVLink.h"
    
    #include "QmlObjectListModel.h"
    
    Don Gagne's avatar
    Don Gagne committed
    #include "MAVLinkProtocol.h"
    
    dogmaphobic's avatar
    dogmaphobic committed
    #include "UASMessageHandler.h"
    
    #include "SettingsFact.h"
    
    class UAS;
    class UASInterface;
    
    class FirmwarePlugin;
    
    class FirmwarePluginManager;
    
    class AutoPilotPlugin;
    
    Don Gagne's avatar
    Don Gagne committed
    class MissionManager;
    
    class GeoFenceManager;
    
    class RallyPointManager;
    
    class ParameterManager;
    
    class JoystickManager;
    
    dogmaphobic's avatar
    dogmaphobic committed
    class UASMessage;
    
    
    Q_DECLARE_LOGGING_CATEGORY(VehicleLog)
    
    
    Don Gagne's avatar
    Don Gagne committed
    class Vehicle;
    
    
    class VehicleVibrationFactGroup : public FactGroup
    {
        Q_OBJECT
    
    public:
        VehicleVibrationFactGroup(QObject* parent = NULL);
    
        Q_PROPERTY(Fact* xAxis      READ xAxis      CONSTANT)
        Q_PROPERTY(Fact* yAxis      READ yAxis      CONSTANT)
        Q_PROPERTY(Fact* zAxis      READ zAxis      CONSTANT)
        Q_PROPERTY(Fact* clipCount1 READ clipCount1 CONSTANT)
        Q_PROPERTY(Fact* clipCount2 READ clipCount2 CONSTANT)
        Q_PROPERTY(Fact* clipCount3 READ clipCount3 CONSTANT)
    
    
        Fact* xAxis         (void) { return &_xAxisFact; }
        Fact* yAxis         (void) { return &_yAxisFact; }
        Fact* zAxis         (void) { return &_zAxisFact; }
        Fact* clipCount1    (void) { return &_clipCount1Fact; }
        Fact* clipCount2    (void) { return &_clipCount2Fact; }
        Fact* clipCount3    (void) { return &_clipCount3Fact; }
    
    
        void setVehicle(Vehicle* vehicle);
    
        static const char* _xAxisFactName;
        static const char* _yAxisFactName;
        static const char* _zAxisFactName;
        static const char* _clipCount1FactName;
        static const char* _clipCount2FactName;
        static const char* _clipCount3FactName;
    
    private:
        Vehicle*    _vehicle;
        Fact        _xAxisFact;
        Fact        _yAxisFact;
        Fact        _zAxisFact;
        Fact        _clipCount1Fact;
        Fact        _clipCount2Fact;
        Fact        _clipCount3Fact;
    };
    
    
    Don Gagne's avatar
    Don Gagne committed
    class VehicleWindFactGroup : public FactGroup
    {
        Q_OBJECT
    
    public:
        VehicleWindFactGroup(QObject* parent = NULL);
    
        Q_PROPERTY(Fact* direction      READ direction      CONSTANT)
        Q_PROPERTY(Fact* speed          READ speed          CONSTANT)
        Q_PROPERTY(Fact* verticalSpeed  READ verticalSpeed  CONSTANT)
    
    
        Fact* direction     (void) { return &_directionFact; }
        Fact* speed         (void) { return &_speedFact; }
        Fact* verticalSpeed (void) { return &_verticalSpeedFact; }
    
    Don Gagne's avatar
    Don Gagne committed
    
        void setVehicle(Vehicle* vehicle);
    
        static const char* _directionFactName;
        static const char* _speedFactName;
        static const char* _verticalSpeedFactName;
    
    private:
        Vehicle*    _vehicle;
        Fact        _directionFact;
        Fact        _speedFact;
        Fact        _verticalSpeedFact;
    };
    
    
    Don Gagne's avatar
    Don Gagne committed
    class VehicleGPSFactGroup : public FactGroup
    {
        Q_OBJECT
    
    public:
        VehicleGPSFactGroup(QObject* parent = NULL);
    
        Q_PROPERTY(Fact* hdop               READ hdop               CONSTANT)
        Q_PROPERTY(Fact* vdop               READ vdop               CONSTANT)
        Q_PROPERTY(Fact* courseOverGround   READ courseOverGround   CONSTANT)
        Q_PROPERTY(Fact* count              READ count              CONSTANT)
        Q_PROPERTY(Fact* lock               READ lock               CONSTANT)
    
    
        Fact* hdop              (void) { return &_hdopFact; }
        Fact* vdop              (void) { return &_vdopFact; }
        Fact* courseOverGround  (void) { return &_courseOverGroundFact; }
        Fact* count             (void) { return &_countFact; }
        Fact* lock              (void) { return &_lockFact; }
    
    Don Gagne's avatar
    Don Gagne committed
    
        void setVehicle(Vehicle* vehicle);
    
    
    Don Gagne's avatar
    Don Gagne committed
        static const char* _hdopFactName;
        static const char* _vdopFactName;
        static const char* _courseOverGroundFactName;
        static const char* _countFactName;
        static const char* _lockFactName;
    
    
    Don Gagne's avatar
    Don Gagne committed
    private slots:
        void _setSatelliteCount(double val, QString);
        void _setSatRawHDOP(double val);
        void _setSatRawVDOP(double val);
        void _setSatRawCOG(double val);
        void _setSatLoc(UASInterface*, int fix);
    
    private:
        Vehicle*    _vehicle;
        Fact        _hdopFact;
        Fact        _vdopFact;
        Fact        _courseOverGroundFact;
        Fact        _countFact;
        Fact        _lockFact;
    
    Don Gagne's avatar
    Don Gagne committed
    };
    
    Don Gagne's avatar
    Don Gagne committed
    class VehicleBatteryFactGroup : public FactGroup
    {
        Q_OBJECT
    
    public:
        VehicleBatteryFactGroup(QObject* parent = NULL);
    
        Q_PROPERTY(Fact* voltage            READ voltage            CONSTANT)
        Q_PROPERTY(Fact* percentRemaining   READ percentRemaining   CONSTANT)
        Q_PROPERTY(Fact* mahConsumed        READ mahConsumed        CONSTANT)
        Q_PROPERTY(Fact* current            READ current            CONSTANT)
        Q_PROPERTY(Fact* temperature        READ temperature        CONSTANT)
    
        Q_PROPERTY(Fact* cellCount          READ cellCount          CONSTANT)
    
        Fact* voltage                   (void) { return &_voltageFact; }
        Fact* percentRemaining          (void) { return &_percentRemainingFact; }
        Fact* mahConsumed               (void) { return &_mahConsumedFact; }
        Fact* current                   (void) { return &_currentFact; }
        Fact* temperature               (void) { return &_temperatureFact; }
        Fact* cellCount                 (void) { return &_cellCountFact; }
    
    Don Gagne's avatar
    Don Gagne committed
    
    
        void setVehicle(Vehicle* vehicle);
    
        static const char* _voltageFactName;
        static const char* _percentRemainingFactName;
        static const char* _mahConsumedFactName;
        static const char* _currentFactName;
        static const char* _temperatureFactName;
        static const char* _cellCountFactName;
    
    
        static const char* _settingsGroup;
    
    
    Don Gagne's avatar
    Don Gagne committed
        static const double _voltageUnavailable;
        static const int    _percentRemainingUnavailable;
        static const int    _mahConsumedUnavailable;
        static const int    _currentUnavailable;
        static const double _temperatureUnavailable;
        static const int    _cellCountUnavailable;
    
    private:
    
        Vehicle*        _vehicle;
        Fact            _voltageFact;
        Fact            _percentRemainingFact;
        Fact            _mahConsumedFact;
        Fact            _currentFact;
        Fact            _temperatureFact;
        Fact            _cellCountFact;
    
    Don Gagne's avatar
    Don Gagne committed
    };
    
    class Vehicle : public FactGroup
    
        Vehicle(LinkInterface*          link,
                int                     vehicleId,
                MAV_AUTOPILOT           firmwareType,
                MAV_TYPE                vehicleType,
                FirmwarePluginManager*  firmwarePluginManager,
                JoystickManager*        joystickManager);
    
        // The following is used to create a disconnected Vehicle for use while offline editing.
        Vehicle(MAV_AUTOPILOT           firmwareType,
                MAV_TYPE                vehicleType,
                FirmwarePluginManager*  firmwarePluginManager,
                QObject*                parent = NULL);
    
        Q_PROPERTY(int                  id                      READ id                                                     CONSTANT)
        Q_PROPERTY(AutoPilotPlugin*     autopilot               MEMBER _autopilotPlugin                                     CONSTANT)
        Q_PROPERTY(QGeoCoordinate       coordinate              READ coordinate                                             NOTIFY coordinateChanged)
        Q_PROPERTY(bool                 coordinateValid         READ coordinateValid                                        NOTIFY coordinateValidChanged)
        Q_PROPERTY(bool                 homePositionAvailable   READ homePositionAvailable                                  NOTIFY homePositionAvailableChanged)
        Q_PROPERTY(QGeoCoordinate       homePosition            READ homePosition                                           NOTIFY homePositionChanged)
        Q_PROPERTY(bool                 armed                   READ armed                  WRITE setArmed                  NOTIFY armedChanged)
        Q_PROPERTY(bool                 flightModeSetAvailable  READ flightModeSetAvailable                                 CONSTANT)
        Q_PROPERTY(QStringList          flightModes             READ flightModes                                            CONSTANT)
        Q_PROPERTY(QString              flightMode              READ flightMode             WRITE setFlightMode             NOTIFY flightModeChanged)
        Q_PROPERTY(bool                 hilMode                 READ hilMode                WRITE setHilMode                NOTIFY hilModeChanged)
        Q_PROPERTY(QmlObjectListModel*  trajectoryPoints        READ trajectoryPoints                                       CONSTANT)
        Q_PROPERTY(float                latitude                READ latitude                                               NOTIFY coordinateChanged)
        Q_PROPERTY(float                longitude               READ longitude                                              NOTIFY coordinateChanged)
        Q_PROPERTY(QString              currentState            READ currentState                                           NOTIFY currentStateChanged)
        Q_PROPERTY(bool                 messageTypeNone         READ messageTypeNone                                        NOTIFY messageTypeChanged)
        Q_PROPERTY(bool                 messageTypeNormal       READ messageTypeNormal                                      NOTIFY messageTypeChanged)
        Q_PROPERTY(bool                 messageTypeWarning      READ messageTypeWarning                                     NOTIFY messageTypeChanged)
        Q_PROPERTY(bool                 messageTypeError        READ messageTypeError                                       NOTIFY messageTypeChanged)
        Q_PROPERTY(int                  newMessageCount         READ newMessageCount                                        NOTIFY newMessageCountChanged)
        Q_PROPERTY(int                  messageCount            READ messageCount                                           NOTIFY messageCountChanged)
        Q_PROPERTY(QString              formatedMessages        READ formatedMessages                                       NOTIFY formatedMessagesChanged)
        Q_PROPERTY(QString              formatedMessage         READ formatedMessage                                        NOTIFY formatedMessageChanged)
        Q_PROPERTY(QString              latestError             READ latestError                                            NOTIFY latestErrorChanged)
        Q_PROPERTY(int                  joystickMode            READ joystickMode           WRITE setJoystickMode           NOTIFY joystickModeChanged)
        Q_PROPERTY(QStringList          joystickModes           READ joystickModes                                          CONSTANT)
        Q_PROPERTY(bool                 joystickEnabled         READ joystickEnabled        WRITE setJoystickEnabled        NOTIFY joystickEnabledChanged)
        Q_PROPERTY(bool                 active                  READ active                 WRITE setActive                 NOTIFY activeChanged)
        Q_PROPERTY(int                  flowImageIndex          READ flowImageIndex                                         NOTIFY flowImageIndexChanged)
        Q_PROPERTY(int                  rcRSSI                  READ rcRSSI                                                 NOTIFY rcRSSIChanged)
        Q_PROPERTY(bool                 px4Firmware             READ px4Firmware                                            CONSTANT)
        Q_PROPERTY(bool                 apmFirmware             READ apmFirmware                                            CONSTANT)
        Q_PROPERTY(bool                 soloFirmware            READ soloFirmware           WRITE setSoloFirmware           NOTIFY soloFirmwareChanged)
        Q_PROPERTY(bool                 genericFirmware         READ genericFirmware                                        CONSTANT)
        Q_PROPERTY(bool                 connectionLost          READ connectionLost                                         NOTIFY connectionLostChanged)
        Q_PROPERTY(bool                 connectionLostEnabled   READ connectionLostEnabled  WRITE setConnectionLostEnabled  NOTIFY connectionLostEnabledChanged)
        Q_PROPERTY(uint                 messagesReceived        READ messagesReceived                                       NOTIFY messagesReceivedChanged)
        Q_PROPERTY(uint                 messagesSent            READ messagesSent                                           NOTIFY messagesSentChanged)
        Q_PROPERTY(uint                 messagesLost            READ messagesLost                                           NOTIFY messagesLostChanged)
        Q_PROPERTY(bool                 fixedWing               READ fixedWing                                              CONSTANT)
        Q_PROPERTY(bool                 multiRotor              READ multiRotor                                             CONSTANT)
        Q_PROPERTY(bool                 vtol                    READ vtol                                                   CONSTANT)
        Q_PROPERTY(bool                 rover                   READ rover                                                  CONSTANT)
    
        Q_PROPERTY(bool                 supportsManualControl   READ supportsManualControl                                  CONSTANT)
    
        Q_PROPERTY(bool        supportsThrottleModeCenterZero   READ supportsThrottleModeCenterZero                         CONSTANT)
    
        Q_PROPERTY(bool                 supportsJSButton        READ supportsJSButton                                       CONSTANT)
    
        Q_PROPERTY(bool                 supportsRadio           READ supportsRadio                                          CONSTANT)
    
        Q_PROPERTY(bool                 sub                     READ sub                                                    CONSTANT)
    
        Q_PROPERTY(bool                 autoDisconnect          MEMBER _autoDisconnect                                      NOTIFY autoDisconnectChanged)
        Q_PROPERTY(QString              prearmError             READ prearmError            WRITE setPrearmError            NOTIFY prearmErrorChanged)
    
    Don Gagne's avatar
    Don Gagne committed
        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              brandImage              READ brandImage                                             CONSTANT)
    
        Q_PROPERTY(QStringList          unhealthySensors        READ unhealthySensors                                       NOTIFY unhealthySensorsChanged)
    
    Don Gagne's avatar
    Don Gagne committed
        /// true: Vehicle is flying, false: Vehicle is on ground
        Q_PROPERTY(bool flying      READ flying     WRITE setFlying     NOTIFY flyingChanged)
    
        /// true: Vehicle is in Guided mode and can respond to guided commands, false: vehicle cannot respond to direct control commands
        Q_PROPERTY(bool guidedMode  READ guidedMode WRITE setGuidedMode NOTIFY guidedModeChanged)
    
        /// true: Guided mode commands are supported by this vehicle
        Q_PROPERTY(bool guidedModeSupported READ guidedModeSupported CONSTANT)
    
        /// true: pauseVehicle command is supported
        Q_PROPERTY(bool pauseVehicleSupported READ pauseVehicleSupported CONSTANT)
    
    
        /// true: Orbit mode is supported by this vehicle
        Q_PROPERTY(bool orbitModeSupported READ orbitModeSupported CONSTANT)
    
    
        Q_PROPERTY(ParameterManager* parameterManager READ parameterManager CONSTANT)
    
    
    Don Gagne's avatar
    Don Gagne committed
        // FactGroup object model properties
    
        Q_PROPERTY(Fact* roll               READ roll               CONSTANT)
        Q_PROPERTY(Fact* pitch              READ pitch              CONSTANT)
        Q_PROPERTY(Fact* heading            READ heading            CONSTANT)
        Q_PROPERTY(Fact* 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)
    
    
    Don Gagne's avatar
    Don Gagne committed
        Q_PROPERTY(FactGroup* gps       READ gpsFactGroup       CONSTANT)
        Q_PROPERTY(FactGroup* battery   READ batteryFactGroup   CONSTANT)
    
        Q_PROPERTY(FactGroup* wind      READ windFactGroup      CONSTANT)
        Q_PROPERTY(FactGroup* vibration READ vibrationFactGroup CONSTANT)
    
        Q_PROPERTY(int firmwareMajorVersion READ firmwareMajorVersion NOTIFY firmwareMajorVersionChanged)
        Q_PROPERTY(int firmwareMinorVersion READ firmwareMinorVersion NOTIFY firmwareMinorVersionChanged)
        Q_PROPERTY(int firmwarePatchVersion READ firmwarePatchVersion NOTIFY firmwarePatchVersionChanged)
        Q_PROPERTY(int firmwareVersionType READ firmwareVersionType NOTIFY firmwareVersionTypeChanged)
        Q_PROPERTY(QString firmwareVersionTypeString READ firmwareVersionTypeString NOTIFY firmwareVersionTypeChanged)
    
    
        /// Resets link status counters
        Q_INVOKABLE void resetCounters  ();
    
    
        /// Returns the number of buttons which are reserved for firmware use in the MANUAL_CONTROL mavlink
        /// message. For example PX4 Flight Stack reserves the first 8 buttons to simulate rc switches.
        /// The remainder can be assigned to Vehicle actions.
        /// @return -1: reserver all buttons, >0 number of buttons to reserve
        Q_PROPERTY(int manualControlReservedButtonCount READ manualControlReservedButtonCount CONSTANT)
    
        Q_INVOKABLE QString     getMavIconColor();
    
    dogmaphobic's avatar
    dogmaphobic committed
        // Called when the message drop-down is invoked to clear current count
        Q_INVOKABLE void        resetMessages();
    
    
    Don Gagne's avatar
    Don Gagne committed
        Q_INVOKABLE void virtualTabletJoystickValue(double roll, double pitch, double yaw, double thrust);
    
    Don Gagne's avatar
    Don Gagne committed
        Q_INVOKABLE void disconnectInactiveVehicle(void);
    
        Q_INVOKABLE void clearTrajectoryPoints(void);
    
    
    Don Gagne's avatar
    Don Gagne committed
        /// Command vehicle to return to launch
        Q_INVOKABLE void guidedModeRTL(void);
    
        /// Command vehicle to land at current location
        Q_INVOKABLE void guidedModeLand(void);
    
        /// Command vehicle to takeoff from current location
        Q_INVOKABLE void guidedModeTakeoff(double altitudeRel);
    
        /// Command vehicle to move to specified location (altitude is included and relative)
        Q_INVOKABLE void guidedModeGotoLocation(const QGeoCoordinate& gotoCoord);
    
        /// Command vehicle to change to the specified relatice altitude
        Q_INVOKABLE void guidedModeChangeAltitude(double altitudeRel);
    
    
        /// Command vehicle to orbit given center point
        ///     @param centerCoord Center Coordinates
        ///     @param radius Distance from vehicle to centerCoord
        ///     @param velocity Orbit velocity (positive CW, negative CCW)
        ///     @param altitude Desired Vehicle Altitude
        Q_INVOKABLE void guidedModeOrbit(const QGeoCoordinate& centerCoord = QGeoCoordinate(), double radius = NAN, double velocity = NAN, double altitude = NAN);
    
    
    Don Gagne's avatar
    Don Gagne committed
        /// Command vehicle to pause at current location. If vehicle supports guide mode, vehicle will be left
        /// in guided mode after pause.
        Q_INVOKABLE void pauseVehicle(void);
    
        /// Command vehicle to kill all motors no matter what state
        Q_INVOKABLE void emergencyStop(void);
    
    
        /// Alter the current mission item on the vehicle
        Q_INVOKABLE void setCurrentMissionSequence(int seq);
    
    
        /// Reboot vehicle
        Q_INVOKABLE void rebootVehicle();
    
    
    dogmaphobic's avatar
    dogmaphobic committed
        /// Clear Messages
        Q_INVOKABLE void clearMessages();
    
    
    Don Gagne's avatar
    Don Gagne committed
    #if 0
        // Temporarily removed, waiting for new command implementation
    
    Don Gagne's avatar
    Don Gagne committed
        /// Test motor
        ///     @param motor Motor number, 1-based
        ///     @param percent 0-no power, 100-full power
        ///     @param timeoutSecs Number of seconds for motor to run
        Q_INVOKABLE void motorTest(int motor, int percent, int timeoutSecs);
    
    Don Gagne's avatar
    Don Gagne committed
    #endif
    
    Don Gagne's avatar
    Don Gagne committed
        bool guidedModeSupported(void) const;
        bool pauseVehicleSupported(void) const;
    
        bool orbitModeSupported(void) const;
    
        // Property accessors
    
        QGeoCoordinate coordinate(void) { return _coordinate; }
        bool coordinateValid(void)      { return _coordinateValid; }
    
    Don Gagne's avatar
    Don Gagne committed
        void _setCoordinateValid(bool coordinateValid);
    
            JoystickModeRC,         ///< Joystick emulates an RC Transmitter
    
            JoystickModeAttitude,
            JoystickModePosition,
            JoystickModeForce,
            JoystickModeVelocity,
            JoystickModeMax
        } JoystickMode_t;
    
        int joystickMode(void);
        void setJoystickMode(int mode);
    
        /// List of joystick mode names
        QStringList joystickModes(void);
    
        bool joystickEnabled(void);
        void setJoystickEnabled(bool enabled);
    
        // Is vehicle active with respect to current active vehicle in QGC
        bool active(void);
        void setActive(bool active);
    
        // Property accesors
        int id(void) { return _id; }
    
        MAV_AUTOPILOT firmwareType(void) const { return _firmwareType; }
        MAV_TYPE vehicleType(void) const { return _vehicleType; }
    
        Q_INVOKABLE QString vehicleTypeName(void) const;
    
        /// Returns the highest quality link available to the Vehicle
        LinkInterface* priorityLink(void);
    
        /// Sends a message to the specified link
        /// @return true: message sent, false: Link no longer connected
        bool sendMessageOnLink(LinkInterface* link, mavlink_message_t message);
    
    
        /// Sends the specified messages multiple times to the vehicle in order to attempt to
        /// guarantee that it makes it to the vehicle.
        void sendMessageMultiple(mavlink_message_t message);
    
        /// Provides access to uas from vehicle. Temporary workaround until UAS is fully phased out.
        UAS* uas(void) { return _uas; }
    
        /// Provides access to uas from vehicle. Temporary workaround until AutoPilotPlugin is fully phased out.
        AutoPilotPlugin* autopilotPlugin(void) { return _autopilotPlugin; }
    
    Don Gagne's avatar
    Don Gagne committed
        /// Provides access to the Firmware Plugin for this Vehicle
        FirmwarePlugin* firmwarePlugin(void) { return _firmwarePlugin; }
    
        int manualControlReservedButtonCount(void);
    
        MissionManager*     missionManager(void)    { return _missionManager; }
        GeoFenceManager*    geoFenceManager(void)   { return _geoFenceManager; }
        RallyPointManager*  rallyPointManager(void) { return _rallyPointManager; }
    
        bool homePositionAvailable(void);
        QGeoCoordinate homePosition(void);
    
    Don Gagne's avatar
    Don Gagne committed
        bool armed(void) { return _armed; }
        void setArmed(bool armed);
    
        bool flightModeSetAvailable(void);
        QStringList flightModes(void);
    
    Don Gagne's avatar
    Don Gagne committed
        QString flightMode(void) const;
    
    Don Gagne's avatar
    Don Gagne committed
        void setFlightMode(const QString& flightMode);
    
        bool hilMode(void);
        void setHilMode(bool hilMode);
    
        bool fixedWing(void) const;
        bool multiRotor(void) const;
    
    Don Gagne's avatar
    Don Gagne committed
        bool vtol(void) const;
    
    Don Gagne's avatar
    Don Gagne committed
        bool rover(void) const;
    
        bool sub(void) const;
    
        bool supportsManualControl(void) const;
    
        bool supportsThrottleModeCenterZero(void) const;
    
        bool supportsRadio(void) const;
    
        bool supportsJSButton(void) const;
    
    Don Gagne's avatar
    Don Gagne committed
        void setFlying(bool flying);
        void setGuidedMode(bool guidedMode);
    
    
    Don Gagne's avatar
    Don Gagne committed
        QString prearmError(void) const { return _prearmError; }
        void setPrearmError(const QString& prearmError);
    
    
        QmlObjectListModel* trajectoryPoints(void) { return &_mapTrajectoryList; }
    
    dogmaphobic's avatar
    dogmaphobic committed
    
        int  flowImageIndex() { return _flowImageIndex; }
    
    
        //-- Mavlink Logging
        void startMavlinkLog();
        void stopMavlinkLog();
    
    
        /// Requests the specified data stream from the vehicle
        ///     @param stream Stream which is being requested
        ///     @param rate Rate at which to send stream in Hz
    
        ///     @param sendMultiple Send multiple time to guarantee Vehicle reception
        void requestDataStream(MAV_DATA_STREAM stream, uint16_t rate, bool sendMultiple = true);
    
        typedef enum {
            MessageNone,
            MessageNormal,
            MessageWarning,
            MessageError
        } MessageType_t;
    
        bool            messageTypeNone         () { return _currentMessageType == MessageNone; }
        bool            messageTypeNormal       () { return _currentMessageType == MessageNormal; }
        bool            messageTypeWarning      () { return _currentMessageType == MessageWarning; }
        bool            messageTypeError        () { return _currentMessageType == MessageError; }
        int             newMessageCount         () { return _currentMessageCount; }
        int             messageCount            () { return _messageCount; }
        QString         formatedMessages        ();
        QString         formatedMessage         () { return _formatedMessage; }
        QString         latestError             () { return _latestError; }
        float           latitude                () { return _coordinate.latitude(); }
        float           longitude               () { return _coordinate.longitude(); }
        bool            mavPresent              () { return _mav != NULL; }
        QString         currentState            () { return _currentState; }
        int             rcRSSI                  () { return _rcRSSI; }
        bool            px4Firmware             () const { return _firmwareType == MAV_AUTOPILOT_PX4; }
        bool            apmFirmware             () const { return _firmwareType == MAV_AUTOPILOT_ARDUPILOTMEGA; }
        bool            genericFirmware         () const { return !px4Firmware() && !apmFirmware(); }
        bool            connectionLost          () const { return _connectionLost; }
        bool            connectionLostEnabled   () const { return _connectionLostEnabled; }
        uint            messagesReceived        () { return _messagesReceived; }
        uint            messagesSent            () { return _messagesSent; }
        uint            messagesLost            () { return _messagesLost; }
        bool            flying                  () const { return _flying; }
        bool            guidedMode              () const;
        uint8_t         baseMode                () const { return _base_mode; }
        uint32_t        customMode              () const { return _custom_mode; }
        bool            isOfflineEditingVehicle () const { return _offlineEditingVehicle; }
    
        QString         brandImage              () const;
    
        QStringList     unhealthySensors        () const;
    
    Don Gagne's avatar
    Don Gagne committed
        Fact* roll              (void) { return &_rollFact; }
        Fact* heading           (void) { return &_headingFact; }
        Fact* pitch             (void) { return &_pitchFact; }
        Fact* airSpeed          (void) { return &_airSpeedFact; }
        Fact* groundSpeed       (void) { return &_groundSpeedFact; }
        Fact* climbRate         (void) { return &_climbRateFact; }
        Fact* altitudeRelative  (void) { return &_altitudeRelativeFact; }
        Fact* altitudeAMSL      (void) { return &_altitudeAMSLFact; }
    
    
        FactGroup* gpsFactGroup         (void) { return &_gpsFactGroup; }
        FactGroup* batteryFactGroup     (void) { return &_batteryFactGroup; }
        FactGroup* windFactGroup        (void) { return &_windFactGroup; }
        FactGroup* vibrationFactGroup   (void) { return &_vibrationFactGroup; }
    
        void setConnectionLostEnabled(bool connectionLostEnabled);
    
        ParameterManager* parameterManager(void) { return _parameterManager; }
        ParameterManager* parameterManager(void) const { return _parameterManager; }
    
    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.
        ///     @param component Component to send to
        ///     @param command MAV_CMD to send
        ///     @param showError true: Display error to user if command failed, false:  no error shown
        void sendMavCommand(int component, MAV_CMD command, bool showError, float param1 = 0.0f, float param2 = 0.0f, float param3 = 0.0f, float param4 = 0.0f, float param5 = 0.0f, float param6 = 0.0f, float param7 = 0.0f);
    
    Don Gagne's avatar
    Don Gagne committed
        int firmwareMajorVersion(void) const { return _firmwareMajorVersion; }
        int firmwareMinorVersion(void) const { return _firmwareMinorVersion; }
        int firmwarePatchVersion(void) const { return _firmwarePatchVersion; }
    
        int firmwareVersionType(void) const { return _firmwareVersionType; }
        QString firmwareVersionTypeString(void) const;
        void setFirmwareVersion(int majorVersion, int minorVersion, int patchVersion, FIRMWARE_VERSION_TYPE versionType = FIRMWARE_VERSION_TYPE_OFFICIAL);
    
        static const int versionNotSetValue = -1;
    
        bool soloFirmware(void) const { return _soloFirmware; }
        void setSoloFirmware(bool soloFirmware);
    
    
    Don Gagne's avatar
    Don Gagne committed
        int defaultComponentId(void);
    
    
    Don Gagne's avatar
    Don Gagne committed
        /// @return -1 = Unknown, Number of motors on vehicle
        int motorCount(void);
    
        /// @return true: Motors are coaxial like an X8 config, false: Quadcopter for example
        bool coaxialMotors(void);
    
        /// @return true: X confiuration, false: Plus configuration
        bool xConfigMotors(void);
    
    
        /// @return Firmware plugin instance data associated with this Vehicle
        QObject* firmwarePluginInstanceData(void) { 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);
    
    
    public slots:
        void setLatitude(double latitude);
        void setLongitude(double longitude);
    
    Don Gagne's avatar
    Don Gagne committed
        void allLinksInactive(Vehicle* vehicle);
    
        void coordinateChanged(QGeoCoordinate coordinate);
    
        void coordinateValidChanged(bool coordinateValid);
    
        void joystickModeChanged(int mode);
    
        void joystickEnabledChanged(bool enabled);
        void activeChanged(bool active);
    
    Don Gagne's avatar
    Don Gagne committed
        void mavlinkMessageReceived(const mavlink_message_t& message);
    
        void homePositionAvailableChanged(bool homePositionAvailable);
        void homePositionChanged(const QGeoCoordinate& homePosition);
    
    Don Gagne's avatar
    Don Gagne committed
        void armedChanged(bool armed);
        void flightModeChanged(const QString& flightMode);
        void hilModeChanged(bool hilMode);
    
        /** @brief HIL actuator controls (replaces HIL controls) */
        void hilActuatorControlsChanged(quint64 time, quint64 flags, float ctl_0, float ctl_1, float ctl_2, float ctl_3, float ctl_4, float ctl_5, float ctl_6, float ctl_7, float ctl_8, float ctl_9, float ctl_10, float ctl_11, float ctl_12, float ctl_13, float ctl_14, float ctl_15, quint8 mode);
    
        void connectionLostChanged(bool connectionLost);
        void connectionLostEnabledChanged(bool connectionLostEnabled);
    
    Don Gagne's avatar
    Don Gagne committed
        void autoDisconnectChanged(bool autoDisconnectChanged);
    
    Don Gagne's avatar
    Don Gagne committed
        void flyingChanged(bool flying);
        void guidedModeChanged(bool guidedMode);
    
    Don Gagne's avatar
    Don Gagne committed
        void prearmErrorChanged(const QString& prearmError);
    
        void soloFirmwareChanged(bool soloFirmware);
    
        void unhealthySensorsChanged(void);
    
        void messagesReceivedChanged    ();
        void messagesSentChanged        ();
        void messagesLostChanged        ();
    
    
        /// Used internally to move sendMessage call to main thread
    
        void _sendMessageOnLinkOnThread(LinkInterface* link, mavlink_message_t message);
    
        void messageTypeChanged     ();
        void newMessageCountChanged ();
        void messageCountChanged    ();
    
    dogmaphobic's avatar
    dogmaphobic committed
        void formatedMessagesChanged();
        void formatedMessageChanged ();
    
        void latestErrorChanged     ();
        void longitudeChanged       ();
        void currentConfigChanged   ();
        void currentStateChanged    ();
    
    dogmaphobic's avatar
    dogmaphobic committed
        void flowImageIndexChanged  ();
    
    Don Gagne's avatar
    Don Gagne committed
        void rcRSSIChanged          (int rcRSSI);
    
        void firmwareMajorVersionChanged(int major);
        void firmwareMinorVersionChanged(int minor);
        void firmwarePatchVersionChanged(int patch);
        void firmwareVersionTypeChanged(int type);
    
    
    Don Gagne's avatar
    Don Gagne committed
        /// New RC channel values
        ///     @param channelCount Number of available channels, cMaxRcChannels max
        ///     @param pwmValues -1 signals channel not available
        void rcChannelsChanged(int channelCount, int pwmValues[cMaxRcChannels]);
    
        /// 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);
    
    
    Gus Grubba's avatar
    Gus Grubba committed
        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);
    
    private slots:
        void _mavlinkMessageReceived(LinkInterface* link, mavlink_message_t message);
    
    Don Gagne's avatar
    Don Gagne committed
        void _linkInactiveOrDeleted(LinkInterface* link);
    
        void _sendMessageOnLink(LinkInterface* link, mavlink_message_t message);
    
        void _sendMessageMultipleNext(void);
    
        void _addNewMapTrajectoryPoint(void);
    
        void _parametersReady(bool parametersReady);
    
    Don Gagne's avatar
    Don Gagne committed
        void _remoteControlRSSIChanged(uint8_t rssi);
    
    Don Gagne's avatar
    Don Gagne committed
        void _handleFlightModeChanged(const QString& flightMode);
    
        void _announceArmedChanged(bool armed);
    
        void _handleTextMessage                 (int newCount);
    
    dogmaphobic's avatar
    dogmaphobic committed
        void _handletextMessageReceived         (UASMessage* message);
    
        /** @brief Attitude from main autopilot / system state */
        void _updateAttitude                    (UASInterface* uas, double roll, double pitch, double yaw, quint64 timestamp);
        /** @brief Attitude from one specific component / redundant autopilot */
        void _updateAttitude                    (UASInterface* uas, int component, double roll, double pitch, double yaw, quint64 timestamp);
        void _updateSpeed                       (UASInterface* uas, double _groundSpeed, double _airSpeed, quint64 timestamp);
    
    Don Gagne's avatar
    Don Gagne committed
        void _updateAltitude                    (UASInterface* uas, double _altitudeAMSL, double _altitudeRelative, double _climbRate, quint64 timestamp);
    
        void _updateNavigationControllerErrors  (UASInterface* uas, double altitudeError, double speedError, double xtrackError);
        void _updateNavigationControllerData    (UASInterface *uas, float navRoll, float navPitch, float navBearing, float targetBearing, float targetDistance);
        void _checkUpdate                       ();
        void _updateState                       (UASInterface* system, QString name, QString description);
    
    dogmaphobic's avatar
    dogmaphobic committed
        /** @brief A new camera image has arrived */
        void _imageReady                        (UASInterface* uas);
    
        void _connectionLostTimeout(void);
    
    Don Gagne's avatar
    Don Gagne committed
        void _prearmErrorTimeout(void);
    
        void _newMissionItemsAvailable(void);
    
        void _newGeoFenceAvailable(void);
    
        void _sendMavCommandAgain(void);
    
    private:
        bool _containsLink(LinkInterface* link);
        void _addLink(LinkInterface* link);
    
        void _loadSettings(void);
        void _saveSettings(void);
    
        void _startJoystick(bool start);
    
    Don Gagne's avatar
    Don Gagne committed
        void _handleHomePosition(mavlink_message_t& message);
        void _handleHeartbeat(mavlink_message_t& message);
    
    Don Gagne's avatar
    Don Gagne committed
        void _handleRCChannels(mavlink_message_t& message);
        void _handleRCChannelsRaw(mavlink_message_t& message);
    
    Don Gagne's avatar
    Don Gagne committed
        void _handleBatteryStatus(mavlink_message_t& message);
        void _handleSysStatus(mavlink_message_t& message);
    
        void _handleWindCov(mavlink_message_t& message);
    
    Don Gagne's avatar
    Don Gagne committed
        void _handleWind(mavlink_message_t& message);
    
        void _handleVibration(mavlink_message_t& message);
    
    Don Gagne's avatar
    Don Gagne committed
        void _handleExtendedSysState(mavlink_message_t& message);
    
        void _handleCommandAck(mavlink_message_t& message);
    
    Gus Grubba's avatar
    Gus Grubba committed
        void _handleAutopilotVersion(LinkInterface* link, mavlink_message_t& message);
    
        void _handleHilActuatorControls(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 _mapTrajectoryStart(void);
        void _mapTrajectoryStop(void);
    
        void _connectionActive(void);
    
        void _say(const QString& text);
        QString _vehicleIdSpeech(void);
    
        void _handleMavlinkLoggingData(mavlink_message_t& message);
        void _handleMavlinkLoggingDataAcked(mavlink_message_t& message);
        void _ackMavlinkLogData(uint16_t sequence);
    
        void _sendNextQueuedMavCommand(void);
    
        int     _id;                    ///< Mavlink system id
    
        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;
    
    Don Gagne's avatar
    Don Gagne committed
        QList<LinkInterface*> _links;
    
        JoystickMode_t  _joystickMode;
    
        bool            _joystickEnabled;
    
        QGeoCoordinate  _coordinate;
        bool            _coordinateValid;       ///< true: vehicle has 3d lock and therefore valid location
    
        bool            _homePositionAvailable;
        QGeoCoordinate  _homePosition;
    
        UASInterface*   _mav;
        int             _currentMessageCount;
        int             _messageCount;
        int             _currentErrorCount;
        int             _currentWarningCount;
        int             _currentNormalCount;
        MessageType_t   _currentMessageType;
        QString         _latestError;
        float           _navigationAltitudeError;
        float           _navigationSpeedError;
        float           _navigationCrosstrackError;
        float           _navigationTargetBearing;
        QTimer*         _refreshTimer;
        QString         _currentState;
        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;
    
        uint32_t        _onboardControlSensorsPresent;
        uint32_t        _onboardControlSensorsEnabled;
        uint32_t        _onboardControlSensorsHealth;
        uint32_t        _onboardControlSensorsUnhealthy;
    
        typedef struct {
            int     component;
            MAV_CMD command;
            float   rgParam[7];
            bool    showError;
        } MavCommandQueueEntry_t;
    
        QList<MavCommandQueueEntry_t>   _mavCommandQueue;
        QTimer                          _mavCommandAckTimer;
        int                             _mavCommandRetryCount;
        static const int                _mavCommandMaxRetryCount = 3;
    
        static const int                _mavCommandAckTimeoutMSecs = 3000;
    
    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;
        static const int    _connectionLostTimeoutMSecs = 3500;  // Signal connection lost after 3.5 seconds of missed heartbeat
        QTimer              _connectionLostTimer;
    
    
    Don Gagne's avatar
    Don Gagne committed
        MissionManager*     _missionManager;
    
        bool                _missionManagerInitialRequestSent;
    
        GeoFenceManager*    _geoFenceManager;
    
        bool                _geoFenceManagerInitialRequestSent;
    
        RallyPointManager*  _rallyPointManager;
        bool                _rallyPointManagerInitialRequestSent;
    
        ParameterManager*    _parameterManager;
    
    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;
    
        QTimer              _mapTrajectoryTimer;
        QmlObjectListModel  _mapTrajectoryList;
        QGeoCoordinate      _mapTrajectoryLastCoordinate;
        bool                _mapTrajectoryHaveFirstCoordinate;
        static const int    _mapTrajectoryMsecsBetweenPoints = 1000;
    
        // 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;
    
    
    Don Gagne's avatar
    Don Gagne committed
        int _firmwareMajorVersion;
        int _firmwareMinorVersion;
        int _firmwarePatchVersion;
    
        FIRMWARE_VERSION_TYPE _firmwareVersionType;
    
        static const int    _lowBatteryAnnounceRepeatMSecs; // Amount of time in between each low battery announcement
        QElapsedTimer       _lowBatteryAnnounceTimer;
    
    
    Don Gagne's avatar
    Don Gagne committed
        // FactGroup facts
    
        Fact _rollFact;
        Fact _pitchFact;
        Fact _headingFact;
        Fact _groundSpeedFact;
        Fact _airSpeedFact;
        Fact _climbRateFact;
        Fact _altitudeRelativeFact;
        Fact _altitudeAMSLFact;
    
    
        VehicleGPSFactGroup         _gpsFactGroup;
        VehicleBatteryFactGroup     _batteryFactGroup;
        VehicleWindFactGroup        _windFactGroup;
        VehicleVibrationFactGroup   _vibrationFactGroup;
    
    Don Gagne's avatar
    Don Gagne committed
    
        static const char* _rollFactName;
        static const char* _pitchFactName;
        static const char* _headingFactName;
        static const char* _groundSpeedFactName;
        static const char* _airSpeedFactName;
        static const char* _climbRateFactName;
        static const char* _altitudeRelativeFactName;
        static const char* _altitudeAMSLFactName;
    
    Don Gagne's avatar
    Don Gagne committed
        static const char* _gpsFactGroupName;
    
    Don Gagne's avatar
    Don Gagne committed
        static const char* _batteryFactGroupName;
    
    Don Gagne's avatar
    Don Gagne committed
        static const char* _windFactGroupName;
    
        static const char* _vibrationFactGroupName;
    
    Don Gagne's avatar
    Don Gagne committed
    
        static const int _vehicleUIUpdateRateMSecs = 100;
    
    
        // Settings keys
    
        static const char* _settingsGroup;
        static const char* _joystickModeSettingsKey;
    
        static const char* _joystickEnabledSettingsKey;