Vehicle.h 18 KB
Newer Older
1 2 3 4 5 6 7 8 9 10 11 12 13 14 15 16 17 18 19 20 21 22 23 24 25 26 27 28 29 30
/*=====================================================================
 
 QGroundControl Open Source Ground Control Station
 
 (c) 2009 - 2014 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org>
 
 This file is part of the QGROUNDCONTROL project
 
 QGROUNDCONTROL is free software: you can redistribute it and/or modify
 it under the terms of the GNU General Public License as published by
 the Free Software Foundation, either version 3 of the License, or
 (at your option) any later version.
 
 QGROUNDCONTROL is distributed in the hope that it will be useful,
 but WITHOUT ANY WARRANTY; without even the implied warranty of
 MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
 GNU General Public License for more details.
 
 You should have received a copy of the GNU General Public License
 along with QGROUNDCONTROL. If not, see <http://www.gnu.org/licenses/>.
 
 ======================================================================*/

/// @file
///     @author Don Gagne <don@thegagnes.com>

#ifndef Vehicle_H
#define Vehicle_H

#include <QObject>
31
#include <QGeoCoordinate>
32
#include <QQmlListProperty>
33 34 35

#include "LinkInterface.h"
#include "QGCMAVLink.h"
36
#include "MissionItem.h"
37
#include "QmlObjectListModel.h"
Don Gagne's avatar
Don Gagne committed
38
#include "MAVLinkProtocol.h"
39

40 41
class UAS;
class UASInterface;
42 43
class FirmwarePlugin;
class AutoPilotPlugin;
44
class UASWaypointManager;
Don Gagne's avatar
Don Gagne committed
45
class MissionManager;
46 47 48 49 50 51 52 53 54

Q_DECLARE_LOGGING_CATEGORY(VehicleLog)

class Vehicle : public QObject
{
    Q_OBJECT
    
public:
    Vehicle(LinkInterface* link, int vehicleId, MAV_AUTOPILOT firmwareType);
55
    ~Vehicle();
56 57 58
    
    Q_PROPERTY(int id READ id CONSTANT)
    Q_PROPERTY(AutoPilotPlugin* autopilot MEMBER _autopilotPlugin CONSTANT)
59
    
Don Gagne's avatar
Don Gagne committed
60 61
    Q_PROPERTY(QGeoCoordinate   coordinate      MEMBER _geoCoordinate   NOTIFY coordinateChanged)
    Q_PROPERTY(MissionManager*  missionManager  MEMBER _missionManager  CONSTANT)
62
    
63 64 65
    Q_PROPERTY(bool             homePositionAvailable   READ homePositionAvailable  NOTIFY homePositionAvailableChanged)
    Q_PROPERTY(QGeoCoordinate   homePosition            READ homePosition           NOTIFY homePositionChanged)
    
Don Gagne's avatar
Don Gagne committed
66 67 68 69 70 71 72 73
    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)
    
74 75
    Q_PROPERTY(bool missingParameters READ missingParameters NOTIFY missingParametersChanged)
    
76 77 78 79 80 81 82 83 84 85 86 87 88 89 90 91 92 93 94 95 96 97 98 99 100 101 102 103 104 105 106 107 108
    Q_INVOKABLE QString     getMavIconColor();
    
    //-- System Messages
    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      latestError         READ latestError        NOTIFY latestErrorChanged)
    //-- UAV Stats
    Q_PROPERTY(float        roll                READ roll               NOTIFY rollChanged)
    Q_PROPERTY(float        pitch               READ pitch              NOTIFY pitchChanged)
    Q_PROPERTY(float        heading             READ heading            NOTIFY headingChanged)
    Q_PROPERTY(float        groundSpeed         READ groundSpeed        NOTIFY groundSpeedChanged)
    Q_PROPERTY(float        airSpeed            READ airSpeed           NOTIFY airSpeedChanged)
    Q_PROPERTY(float        climbRate           READ climbRate          NOTIFY climbRateChanged)
    Q_PROPERTY(float        altitudeRelative    READ altitudeRelative   NOTIFY altitudeRelativeChanged)
    Q_PROPERTY(float        altitudeWGS84       READ altitudeWGS84      NOTIFY altitudeWGS84Changed)
    Q_PROPERTY(float        altitudeAMSL        READ altitudeAMSL       NOTIFY altitudeAMSLChanged)
    Q_PROPERTY(float        latitude            READ latitude           NOTIFY latitudeChanged)
    Q_PROPERTY(float        longitude           READ longitude          NOTIFY longitudeChanged)
    Q_PROPERTY(double       batteryVoltage      READ batteryVoltage     NOTIFY batteryVoltageChanged)
    Q_PROPERTY(double       batteryPercent      READ batteryPercent     NOTIFY batteryPercentChanged)
    Q_PROPERTY(double       batteryConsumed     READ batteryConsumed    NOTIFY batteryConsumedChanged)
    Q_PROPERTY(QString      systemPixmap        READ systemPixmap       NOTIFY systemPixmapChanged)
    Q_PROPERTY(int          satelliteCount      READ satelliteCount     NOTIFY satelliteCountChanged)
    Q_PROPERTY(QString      currentState        READ currentState       NOTIFY currentStateChanged)
    Q_PROPERTY(QString      systemName          READ systemName         NOTIFY systemNameChanged)
    Q_PROPERTY(int          satelliteLock       READ satelliteLock      NOTIFY satelliteLockChanged)
    Q_PROPERTY(double       waypointDistance    READ waypointDistance   NOTIFY waypointDistanceChanged)
    Q_PROPERTY(uint16_t     currentWaypoint     READ currentWaypoint    NOTIFY currentWaypointChanged)
    Q_PROPERTY(unsigned int heartbeatTimeout    READ heartbeatTimeout   NOTIFY heartbeatTimeoutChanged)
109
    
110 111
    Q_PROPERTY(QmlObjectListModel* missionItems READ missionItemsModel CONSTANT)
    QmlObjectListModel* missionItemsModel(void);
112
    
113 114 115 116 117 118 119
    /// 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)
    
    typedef enum {
120
        JoystickModeRC,         ///< Joystick emulates an RC Transmitter
121 122 123 124 125 126 127 128 129 130 131 132 133 134 135 136
        JoystickModeAttitude,
        JoystickModePosition,
        JoystickModeForce,
        JoystickModeVelocity,
        JoystickModeMax
    } JoystickMode_t;
    
    /// The joystick mode associated with this vehicle. Joystick modes are stored keyed by mavlink system id.
    Q_PROPERTY(int joystickMode READ joystickMode WRITE setJoystickMode NOTIFY joystickModeChanged)
    int joystickMode(void);
    void setJoystickMode(int mode);
    
    /// List of joystick mode names
    Q_PROPERTY(QStringList joystickModes READ joystickModes CONSTANT)
    QStringList joystickModes(void);
    
137 138 139 140 141 142 143 144 145 146
    // Enable/Disable joystick for this vehicle
    Q_PROPERTY(bool joystickEnabled READ joystickEnabled WRITE setJoystickEnabled NOTIFY joystickEnabledChanged)
    bool joystickEnabled(void);
    void setJoystickEnabled(bool enabled);
    
    // Is vehicle active with respect to current active vehicle in QGC
    Q_PROPERTY(bool active READ active WRITE setActive NOTIFY activeChanged)
    bool active(void);
    void setActive(bool active);
    
147 148 149 150 151 152 153 154 155 156 157 158 159
    // Property accesors
    int id(void) { return _id; }
    MAV_AUTOPILOT firmwareType(void) { return _firmwareType; }
    
    /// Sends this specified message to all links accociated with this vehicle
    void sendMessage(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
160 161 162
    /// Provides access to the Firmware Plugin for this Vehicle
    FirmwarePlugin* firmwarePlugin(void) { return _firmwarePlugin; }
    
163 164
    QList<LinkInterface*> links(void);
    
165 166
    int manualControlReservedButtonCount(void);
    
Don Gagne's avatar
Don Gagne committed
167 168
    MissionManager* missionManager(void) { return _missionManager; }
    
169 170 171
    bool homePositionAvailable(void);
    QGeoCoordinate homePosition(void);
    
Don Gagne's avatar
Don Gagne committed
172 173 174 175 176 177 178 179 180 181 182
    bool armed(void) { return _armed; }
    void setArmed(bool armed);

    bool flightModeSetAvailable(void);
    QStringList flightModes(void);
    QString flightMode(void);
    void setFlightMode(const QString& flightMode);

    bool hilMode(void);
    void setHilMode(bool hilMode);
    
183 184
    bool missingParameters(void);
    
185 186 187 188 189 190 191 192 193 194 195 196 197 198 199 200 201 202 203 204 205 206 207 208 209 210 211 212 213 214 215 216 217 218 219 220 221 222 223 224 225 226 227 228 229 230 231 232 233 234 235 236 237 238
    typedef enum {
        MessageNone,
        MessageNormal,
        MessageWarning,
        MessageError
    } MessageType_t;
    
    enum {
        ROLL_CHANGED,
        PITCH_CHANGED,
        HEADING_CHANGED,
        GROUNDSPEED_CHANGED,
        AIRSPEED_CHANGED,
        CLIMBRATE_CHANGED,
        ALTITUDERELATIVE_CHANGED,
        ALTITUDEWGS84_CHANGED,
        ALTITUDEAMSL_CHANGED
    };
    
    // Called when the message drop-down is invoked to clear current count
    void resetMessages();
    
    
    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         latestError         () { return _latestError; }
    float           roll                () { return _roll; }
    float           pitch               () { return _pitch; }
    float           heading             () { return _heading; }
    float           groundSpeed         () { return _groundSpeed; }
    float           airSpeed            () { return _airSpeed; }
    float           climbRate           () { return _climbRate; }
    float           altitudeRelative    () { return _altitudeRelative; }
    float           altitudeWGS84       () { return _altitudeWGS84; }
    float           altitudeAMSL        () { return _altitudeAMSL; }
    float           latitude            () { return _latitude; }
    float           longitude           () { return _longitude; }
    bool            mavPresent          () { return _mav != NULL; }
    int             satelliteCount      () { return _satelliteCount; }
    double          batteryVoltage      () { return _batteryVoltage; }
    double          batteryPercent      () { return _batteryPercent; }
    double          batteryConsumed     () { return _batteryConsumed; }
    QString         systemPixmap        () { return _systemPixmap; }
    QString         currentState        () { return _currentState; }
    QString         systemName          () { return _systemName; }
    int             satelliteLock       () { return _satelliteLock; }
    double          waypointDistance    () { return _waypointDistance; }
    uint16_t        currentWaypoint     () { return _currentWaypoint; }
    unsigned int    heartbeatTimeout    () { return _currentHeartbeatTimeout; }
    
239 240 241 242
public slots:
    void setLatitude(double latitude);
    void setLongitude(double longitude);
    
243
signals:
244
    void allLinksDisconnected(Vehicle* vehicle);
245
    void coordinateChanged(QGeoCoordinate coordinate);
246
    void joystickModeChanged(int mode);
247 248
    void joystickEnabledChanged(bool enabled);
    void activeChanged(bool active);
Don Gagne's avatar
Don Gagne committed
249
    void mavlinkMessageReceived(const mavlink_message_t& message);
250 251
    void homePositionAvailableChanged(bool homePositionAvailable);
    void homePositionChanged(const QGeoCoordinate& homePosition);
Don Gagne's avatar
Don Gagne committed
252 253 254
    void armedChanged(bool armed);
    void flightModeChanged(const QString& flightMode);
    void hilModeChanged(bool hilMode);
255
    void missingParametersChanged(bool missingParameters);
256 257 258 259
    
    /// Used internally to move sendMessage call to main thread
    void _sendMessageOnThread(mavlink_message_t message);
    
260 261 262 263 264 265 266 267 268 269 270 271 272 273 274 275 276 277 278 279 280 281 282 283 284 285 286 287
    void messageTypeChanged     ();
    void newMessageCountChanged ();
    void messageCountChanged    ();
    void latestErrorChanged     ();
    void rollChanged            ();
    void pitchChanged           ();
    void headingChanged         ();
    void groundSpeedChanged     ();
    void airSpeedChanged        ();
    void climbRateChanged       ();
    void altitudeRelativeChanged();
    void altitudeWGS84Changed   ();
    void altitudeAMSLChanged    ();
    void latitudeChanged        ();
    void longitudeChanged       ();
    void batteryVoltageChanged  ();
    void batteryPercentChanged  ();
    void batteryConsumedChanged ();
    void heartbeatTimeoutChanged();
    void currentConfigChanged   ();
    void systemPixmapChanged    ();
    void satelliteCountChanged  ();
    void currentStateChanged    ();
    void systemNameChanged      ();
    void satelliteLockChanged   ();
    void waypointDistanceChanged();
    void currentWaypointChanged ();
    
288 289 290 291 292
private slots:
    void _mavlinkMessageReceived(LinkInterface* link, mavlink_message_t message);
    void _linkDisconnected(LinkInterface* link);
    void _sendMessage(mavlink_message_t message);
    
293 294 295 296 297 298 299 300 301 302 303 304 305 306 307 308 309 310 311 312 313 314
    void _handleTextMessage                 (int newCount);
    /** @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);
    /** @brief Speed */
    void _updateSpeed                       (UASInterface* uas, double _groundSpeed, double _airSpeed, quint64 timestamp);
    /** @brief Altitude */
    void _updateAltitude                    (UASInterface* uas, double _altitudeAMSL, double _altitudeWGS84, 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 _updateBatteryRemaining            (UASInterface*, double voltage, double, double percent, int);
    void _updateBatteryConsumedChanged      (UASInterface*, double current_consumed);
    void _updateState                       (UASInterface* system, QString name, QString description);
    void _updateName                        (const QString& name);
    void _setSystemType                     (UASInterface* uas, unsigned int systemType);
    void _heartbeatTimeout                  (bool timeout, unsigned int ms);
    void _updateCurrentWaypoint             (quint16 id);
    void _updateWaypointDistance            (double distance);
    void _setSatelliteCount                 (double val, QString name);
    void _setSatLoc                         (UASInterface* uas, int fix);
315
    void _updateWaypointViewOnly            (int uas, MissionItem* wp);
316 317
    void _waypointViewOnlyListChanged       ();

318 319 320
private:
    bool _containsLink(LinkInterface* link);
    void _addLink(LinkInterface* link);
321 322
    void _loadSettings(void);
    void _saveSettings(void);
323
    void _startJoystick(bool start);
Don Gagne's avatar
Don Gagne committed
324 325 326
    void _handleHomePosition(mavlink_message_t& message);
    void _handleHeartbeat(mavlink_message_t& message);

327 328 329
    bool    _isAirplane                     ();
    void    _addChange                      (int id);
    float   _oneDecimal                     (float value);
330

331
private:
332 333
    int     _id;            ///< Mavlink system id
    bool    _active;
334
    
335
    MAV_AUTOPILOT       _firmwareType;
336 337
    FirmwarePlugin*     _firmwarePlugin;
    AutoPilotPlugin*    _autopilotPlugin;
Don Gagne's avatar
Don Gagne committed
338
    MAVLinkProtocol*    _mavlink;
339 340 341 342 343 344
    
    /// List of all links associated with this vehicle. We keep SharedLinkInterface objects
    /// which are QSharedPointer's in order to maintain reference counts across threads.
    /// This way Link deletion works correctly.
    QList<SharedLinkInterface> _links;
    
345
    JoystickMode_t  _joystickMode;
346
    bool            _joystickEnabled;
347
    
348
    UAS* _uas;
349 350 351
    
    QGeoCoordinate  _geoCoordinate;
    
352 353 354
    bool            _homePositionAvailable;
    QGeoCoordinate  _homePosition;
    
355 356 357 358 359 360 361 362 363 364 365 366 367 368 369 370 371 372 373 374 375 376 377 378 379 380 381 382 383 384 385 386 387 388 389 390 391 392
    UASInterface*   _mav;
    int             _currentMessageCount;
    int             _messageCount;
    int             _currentErrorCount;
    int             _currentWarningCount;
    int             _currentNormalCount;
    MessageType_t   _currentMessageType;
    QString         _latestError;
    float           _roll;
    float           _pitch;
    float           _heading;
    float           _altitudeAMSL;
    float           _altitudeWGS84;
    float           _altitudeRelative;
    float           _groundSpeed;
    float           _airSpeed;
    float           _climbRate;
    float           _navigationAltitudeError;
    float           _navigationSpeedError;
    float           _navigationCrosstrackError;
    float           _navigationTargetBearing;
    float           _latitude;
    float           _longitude;
    QTimer*         _refreshTimer;
    QList<int>      _changes;
    double          _batteryVoltage;
    double          _batteryPercent;
    double          _batteryConsumed;
    QString         _currentState;
    QString         _systemName;
    QString         _systemPixmap;
    unsigned int    _currentHeartbeatTimeout;
    double          _waypointDistance;
    quint16         _currentWaypoint;
    int             _satelliteCount;
    int             _satelliteLock;
    UASWaypointManager* _wpm;
    int             _updateCount;
393
    
Don Gagne's avatar
Don Gagne committed
394
    MissionManager*     _missionManager;
395
    QmlObjectListModel  _missionItems;
396
    
Don Gagne's avatar
Don Gagne committed
397 398 399 400
    bool    _armed;         ///< true: vehicle is armed
    uint8_t _base_mode;     ///< base_mode from HEARTBEAT
    uint32_t _custom_mode;  ///< custom_mode from HEARTBEAT
    
401 402
    static const char* _settingsGroup;
    static const char* _joystickModeSettingsKey;
403
    static const char* _joystickEnabledSettingsKey;
404 405
};
#endif