Vehicle.h 26.1 KB
Newer Older
1
/*=====================================================================
dogmaphobic's avatar
dogmaphobic committed
2

3
 QGroundControl Open Source Ground Control Station
dogmaphobic's avatar
dogmaphobic committed
4

5
 (c) 2009 - 2014 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org>
dogmaphobic's avatar
dogmaphobic committed
6

7
 This file is part of the QGROUNDCONTROL project
dogmaphobic's avatar
dogmaphobic committed
8

9 10 11 12
 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.
dogmaphobic's avatar
dogmaphobic committed
13

14 15 16 17
 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.
dogmaphobic's avatar
dogmaphobic committed
18

19 20
 You should have received a copy of the GNU General Public License
 along with QGROUNDCONTROL. If not, see <http://www.gnu.org/licenses/>.
dogmaphobic's avatar
dogmaphobic committed
21

22 23 24 25 26 27 28 29 30
 ======================================================================*/

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

#ifndef Vehicle_H
#define Vehicle_H

#include <QObject>
31
#include <QGeoCoordinate>
32

Don Gagne's avatar
Don Gagne committed
33
#include "FactGroup.h"
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"
dogmaphobic's avatar
dogmaphobic committed
39
#include "UASMessageHandler.h"
40

41 42
class UAS;
class UASInterface;
43
class FirmwarePlugin;
44
class FirmwarePluginManager;
45
class AutoPilotPlugin;
46
class AutoPilotPluginManager;
Don Gagne's avatar
Don Gagne committed
47
class MissionManager;
48
class ParameterLoader;
49
class JoystickManager;
dogmaphobic's avatar
dogmaphobic committed
50
class UASMessage;
51 52 53

Q_DECLARE_LOGGING_CATEGORY(VehicleLog)

Don Gagne's avatar
Don Gagne committed
54 55 56 57 58 59 60 61 62 63 64 65 66 67 68 69 70 71 72 73 74 75 76 77 78 79 80 81 82 83 84 85 86 87 88 89 90 91 92 93 94 95 96 97 98 99
class Vehicle;

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; }

    void setVehicle(Vehicle* vehicle);

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;

    static const char* _hdopFactName;
    static const char* _vdopFactName;
    static const char* _courseOverGroundFactName;
    static const char* _countFactName;
    static const char* _lockFactName;
};

class Vehicle : public FactGroup
100 101
{
    Q_OBJECT
dogmaphobic's avatar
dogmaphobic committed
102

103
public:
104 105 106 107 108 109 110
    Vehicle(LinkInterface*          link,
            int                     vehicleId,
            MAV_AUTOPILOT           firmwareType,
            MAV_TYPE                vehicleType,
            FirmwarePluginManager*  firmwarePluginManager,
            AutoPilotPluginManager* autopilotPluginManager,
            JoystickManager*        joystickManager);
111
    ~Vehicle();
dogmaphobic's avatar
dogmaphobic committed
112

113 114
    Q_PROPERTY(int                  id                      READ id                                     CONSTANT)
    Q_PROPERTY(AutoPilotPlugin*     autopilot               MEMBER _autopilotPlugin                     CONSTANT)
115 116 117 118 119 120 121 122 123 124 125 126
    Q_PROPERTY(QGeoCoordinate       coordinate              READ coordinate                             NOTIFY coordinateChanged)
    Q_PROPERTY(bool                 coordinateValid         READ coordinateValid                        NOTIFY coordinateValidChanged)
    Q_PROPERTY(MissionManager*      missionManager          MEMBER _missionManager                      CONSTANT)
    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(bool                 missingParameters       READ missingParameters                      NOTIFY missingParametersChanged)
    Q_PROPERTY(QmlObjectListModel*  trajectoryPoints        READ trajectoryPoints                       CONSTANT)
127 128 129 130 131 132 133 134 135 136 137 138 139
    Q_PROPERTY(float                latitude                READ latitude                               NOTIFY coordinateChanged)
    Q_PROPERTY(float                longitude               READ longitude                              NOTIFY coordinateChanged)
    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              currentState            READ currentState                           NOTIFY currentStateChanged)
    Q_PROPERTY(QmlObjectListModel*  missionItems            READ missionItemsModel                      CONSTANT)
    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)
dogmaphobic's avatar
dogmaphobic committed
140 141
    Q_PROPERTY(QString              formatedMessages        READ formatedMessages                       NOTIFY formatedMessagesChanged)
    Q_PROPERTY(QString              formatedMessage         READ formatedMessage                        NOTIFY formatedMessageChanged)
142 143 144 145
    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)
dogmaphobic's avatar
dogmaphobic committed
146 147
    Q_PROPERTY(bool                 active                  READ active             WRITE setActive     NOTIFY activeChanged)
    Q_PROPERTY(int                  flowImageIndex          READ flowImageIndex                         NOTIFY flowImageIndexChanged)
Don Gagne's avatar
Don Gagne committed
148
    Q_PROPERTY(int                  rcRSSI                  READ rcRSSI                                 NOTIFY rcRSSIChanged)
Don Gagne's avatar
Don Gagne committed
149 150 151
    Q_PROPERTY(bool                 px4Firmware             READ px4Firmware                            CONSTANT)
    Q_PROPERTY(bool                 apmFirmware             READ apmFirmware                            CONSTANT)
    Q_PROPERTY(bool                 genericFirmware         READ genericFirmware                        CONSTANT)
152 153
    Q_PROPERTY(bool                 connectionLost          READ connectionLost                         NOTIFY connectionLostChanged)
    Q_PROPERTY(bool                 connectionLostEnabled   READ connectionLostEnabled  WRITE setConnectionLostEnabled NOTIFY connectionLostEnabledChanged)
154 155 156
    Q_PROPERTY(uint                 messagesReceived        READ messagesReceived                       NOTIFY messagesReceivedChanged)
    Q_PROPERTY(uint                 messagesSent            READ messagesSent                           NOTIFY messagesSentChanged)
    Q_PROPERTY(uint                 messagesLost            READ messagesLost                           NOTIFY messagesLostChanged)
157 158
    Q_PROPERTY(bool                 fixedWing               READ fixedWing                              CONSTANT)
    Q_PROPERTY(bool                 multiRotor              READ multiRotor                             CONSTANT)
Don Gagne's avatar
Don Gagne committed
159
    Q_PROPERTY(bool                 autoDisconnect          MEMBER _autoDisconnect                      NOTIFY autoDisconnectChanged)
160

Don Gagne's avatar
Don Gagne committed
161 162 163 164 165 166 167 168 169 170 171 172 173 174
    // 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* altitudeWGS84      READ altitudeWGS84      CONSTANT)
    Q_PROPERTY(Fact* altitudeAMSL       READ altitudeAMSL       CONSTANT)

    Q_PROPERTY(FactGroup* gps   READ gpsFactGroup CONSTANT)

175 176
    /// Resets link status counters
    Q_INVOKABLE void resetCounters  ();
177 178 179 180 181 182 183 184

    /// 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();
Don Gagne's avatar
Don Gagne committed
185

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

Don Gagne's avatar
Don Gagne committed
189
    Q_INVOKABLE void virtualTabletJoystickValue(double roll, double pitch, double yaw, double thrust);
Don Gagne's avatar
Don Gagne committed
190
    Q_INVOKABLE void disconnectInactiveVehicle(void);
Don Gagne's avatar
Don Gagne committed
191

192
    // Property accessors
Don Gagne's avatar
Don Gagne committed
193

194 195
    QGeoCoordinate coordinate(void) { return _coordinate; }
    bool coordinateValid(void)      { return _coordinateValid; }
Don Gagne's avatar
Don Gagne committed
196
    void _setCoordinateValid(bool coordinateValid);
197
    QmlObjectListModel* missionItemsModel(void);
dogmaphobic's avatar
dogmaphobic committed
198

199
    typedef enum {
200
        JoystickModeRC,         ///< Joystick emulates an RC Transmitter
201 202 203 204 205 206
        JoystickModeAttitude,
        JoystickModePosition,
        JoystickModeForce,
        JoystickModeVelocity,
        JoystickModeMax
    } JoystickMode_t;
dogmaphobic's avatar
dogmaphobic committed
207

208 209
    int joystickMode(void);
    void setJoystickMode(int mode);
dogmaphobic's avatar
dogmaphobic committed
210

211 212
    /// List of joystick mode names
    QStringList joystickModes(void);
dogmaphobic's avatar
dogmaphobic committed
213

214 215
    bool joystickEnabled(void);
    void setJoystickEnabled(bool enabled);
dogmaphobic's avatar
dogmaphobic committed
216

217 218 219
    // Is vehicle active with respect to current active vehicle in QGC
    bool active(void);
    void setActive(bool active);
dogmaphobic's avatar
dogmaphobic committed
220

221 222
    // Property accesors
    int id(void) { return _id; }
223 224
    MAV_AUTOPILOT firmwareType(void) const { return _firmwareType; }
    MAV_TYPE vehicleType(void) const { return _vehicleType; }
dogmaphobic's avatar
dogmaphobic committed
225

226 227 228 229
    /// Returns the highest quality link available to the Vehicle
    LinkInterface* priorityLink(void);

    /// Sends a message to all links accociated with this vehicle
230
    void sendMessage(mavlink_message_t message);
dogmaphobic's avatar
dogmaphobic committed
231

232 233 234 235
    /// Sends a message to the specified link
    /// @return true: message sent, false: Link no longer connected
    bool sendMessageOnLink(LinkInterface* link, mavlink_message_t message);

236 237 238
    /// Sends the specified messages multiple times to the vehicle in order to attempt to
    /// guarantee that it makes it to the vehicle.
    void sendMessageMultiple(mavlink_message_t message);
dogmaphobic's avatar
dogmaphobic committed
239

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

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

Don Gagne's avatar
Don Gagne committed
246 247
    /// Provides access to the Firmware Plugin for this Vehicle
    FirmwarePlugin* firmwarePlugin(void) { return _firmwarePlugin; }
dogmaphobic's avatar
dogmaphobic committed
248

249
    int manualControlReservedButtonCount(void);
dogmaphobic's avatar
dogmaphobic committed
250

Don Gagne's avatar
Don Gagne committed
251
    MissionManager* missionManager(void) { return _missionManager; }
dogmaphobic's avatar
dogmaphobic committed
252

253 254
    bool homePositionAvailable(void);
    QGeoCoordinate homePosition(void);
dogmaphobic's avatar
dogmaphobic committed
255

Don Gagne's avatar
Don Gagne committed
256 257 258 259 260 261 262 263 264 265
    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);
dogmaphobic's avatar
dogmaphobic committed
266

267 268 269
    bool fixedWing(void) const;
    bool multiRotor(void) const;

270
    QmlObjectListModel* trajectoryPoints(void) { return &_mapTrajectoryList; }
dogmaphobic's avatar
dogmaphobic committed
271 272 273

    int  flowImageIndex() { return _flowImageIndex; }

274 275 276
    /// 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
277 278
    ///     @param sendMultiple Send multiple time to guarantee Vehicle reception
    void requestDataStream(MAV_DATA_STREAM stream, uint16_t rate, bool sendMultiple = true);
dogmaphobic's avatar
dogmaphobic committed
279

280
    bool missingParameters(void);
dogmaphobic's avatar
dogmaphobic committed
281

282 283 284 285 286 287
    typedef enum {
        MessageNone,
        MessageNormal,
        MessageWarning,
        MessageError
    } MessageType_t;
dogmaphobic's avatar
dogmaphobic committed
288

289 290 291 292 293 294
    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; }
dogmaphobic's avatar
dogmaphobic committed
295 296
    QString         formatedMessages    ();
    QString         formatedMessage     () { return _formatedMessage; }
297
    QString         latestError         () { return _latestError; }
298 299
    float           latitude            () { return _coordinate.latitude(); }
    float           longitude           () { return _coordinate.longitude(); }
300 301 302 303 304
    bool            mavPresent          () { return _mav != NULL; }
    double          batteryVoltage      () { return _batteryVoltage; }
    double          batteryPercent      () { return _batteryPercent; }
    double          batteryConsumed     () { return _batteryConsumed; }
    QString         currentState        () { return _currentState; }
Don Gagne's avatar
Don Gagne committed
305
    int             rcRSSI              () { return _rcRSSI; }
Don Gagne's avatar
Don Gagne committed
306 307 308
    bool            px4Firmware         () { return _firmwareType == MAV_AUTOPILOT_PX4; }
    bool            apmFirmware         () { return _firmwareType == MAV_AUTOPILOT_ARDUPILOTMEGA; }
    bool            genericFirmware     () { return !px4Firmware() && !apmFirmware(); }
309 310
    bool            connectionLost      () const { return _connectionLost; }
    bool            connectionLostEnabled() const { return _connectionLostEnabled; }
311 312 313
    uint            messagesReceived    () { return _messagesReceived; }
    uint            messagesSent        () { return _messagesSent; }
    uint            messagesLost        () { return _messagesLost; }
314

Don Gagne's avatar
Don Gagne committed
315 316 317 318 319 320 321 322 323 324 325 326
    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* altitudeWGS84     (void) { return &_altitudeWGS84Fact; }
    Fact* altitudeAMSL      (void) { return &_altitudeAMSLFact; }

    FactGroup* gpsFactGroup(void) { return &_gpsFactGroup; }

327
    void setConnectionLostEnabled(bool connectionLostEnabled);
328 329

    ParameterLoader* getParameterLoader(void);
dogmaphobic's avatar
dogmaphobic committed
330

Don Gagne's avatar
Don Gagne committed
331 332
    static const int cMaxRcChannels = 18;

Don Gagne's avatar
Don Gagne committed
333 334
    bool containsLink(LinkInterface* link) { return _links.contains(link); }

335 336 337
public slots:
    void setLatitude(double latitude);
    void setLongitude(double longitude);
dogmaphobic's avatar
dogmaphobic committed
338

339
signals:
Don Gagne's avatar
Don Gagne committed
340
    void allLinksInactive(Vehicle* vehicle);
341
    void coordinateChanged(QGeoCoordinate coordinate);
342
    void coordinateValidChanged(bool coordinateValid);
343
    void joystickModeChanged(int mode);
344 345
    void joystickEnabledChanged(bool enabled);
    void activeChanged(bool active);
Don Gagne's avatar
Don Gagne committed
346
    void mavlinkMessageReceived(const mavlink_message_t& message);
347 348
    void homePositionAvailableChanged(bool homePositionAvailable);
    void homePositionChanged(const QGeoCoordinate& homePosition);
Don Gagne's avatar
Don Gagne committed
349 350 351
    void armedChanged(bool armed);
    void flightModeChanged(const QString& flightMode);
    void hilModeChanged(bool hilMode);
352
    void missingParametersChanged(bool missingParameters);
353 354
    void connectionLostChanged(bool connectionLost);
    void connectionLostEnabledChanged(bool connectionLostEnabled);
Don Gagne's avatar
Don Gagne committed
355
    void autoDisconnectChanged(bool autoDisconnectChanged);
dogmaphobic's avatar
dogmaphobic committed
356

357 358 359 360
    void messagesReceivedChanged    ();
    void messagesSentChanged        ();
    void messagesLostChanged        ();

361 362
    /// Used internally to move sendMessage call to main thread
    void _sendMessageOnThread(mavlink_message_t message);
363
    void _sendMessageOnLinkOnThread(LinkInterface* link, mavlink_message_t message);
dogmaphobic's avatar
dogmaphobic committed
364

365 366 367
    void messageTypeChanged     ();
    void newMessageCountChanged ();
    void messageCountChanged    ();
dogmaphobic's avatar
dogmaphobic committed
368 369
    void formatedMessagesChanged();
    void formatedMessageChanged ();
370 371 372 373 374 375 376
    void latestErrorChanged     ();
    void longitudeChanged       ();
    void batteryVoltageChanged  ();
    void batteryPercentChanged  ();
    void batteryConsumedChanged ();
    void currentConfigChanged   ();
    void currentStateChanged    ();
dogmaphobic's avatar
dogmaphobic committed
377
    void flowImageIndexChanged  ();
Don Gagne's avatar
Don Gagne committed
378
    void rcRSSIChanged          (int rcRSSI);
dogmaphobic's avatar
dogmaphobic committed
379

Don Gagne's avatar
Don Gagne committed
380 381 382 383 384 385 386 387
    /// 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);

388 389 390 391 392
    void mavlinkRawImu(mavlink_message_t message);
    void mavlinkScaledImu1(mavlink_message_t message);
    void mavlinkScaledImu2(mavlink_message_t message);
    void mavlinkScaledImu3(mavlink_message_t message);

393 394
private slots:
    void _mavlinkMessageReceived(LinkInterface* link, mavlink_message_t message);
Don Gagne's avatar
Don Gagne committed
395
    void _linkInactiveOrDeleted(LinkInterface* link);
396
    void _sendMessage(mavlink_message_t message);
397
    void _sendMessageOnLink(LinkInterface* link, mavlink_message_t message);
398
    void _sendMessageMultipleNext(void);
399
    void _addNewMapTrajectoryPoint(void);
400
    void _parametersReady(bool parametersReady);
Don Gagne's avatar
Don Gagne committed
401
    void _remoteControlRSSIChanged(uint8_t rssi);
402

403
    void _handleTextMessage                 (int newCount);
dogmaphobic's avatar
dogmaphobic committed
404
    void _handletextMessageReceived         (UASMessage* message);
405 406 407 408 409 410 411 412 413 414 415 416
    /** @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);
    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);
dogmaphobic's avatar
dogmaphobic committed
417 418
    /** @brief A new camera image has arrived */
    void _imageReady                        (UASInterface* uas);
419
    void _connectionLostTimeout(void);
420

421 422 423
private:
    bool _containsLink(LinkInterface* link);
    void _addLink(LinkInterface* link);
424 425
    void _loadSettings(void);
    void _saveSettings(void);
426
    void _startJoystick(bool start);
Don Gagne's avatar
Don Gagne committed
427 428
    void _handleHomePosition(mavlink_message_t& message);
    void _handleHeartbeat(mavlink_message_t& message);
Don Gagne's avatar
Don Gagne committed
429 430
    void _handleRCChannels(mavlink_message_t& message);
    void _handleRCChannelsRaw(mavlink_message_t& message);
431
    void _missionManagerError(int errorCode, const QString& errorMsg);
432 433
    void _mapTrajectoryStart(void);
    void _mapTrajectoryStop(void);
434 435
    void _connectionActive(void);
    void _say(const QString& text, int severity);
Don Gagne's avatar
Don Gagne committed
436

437
private:
438 439
    int     _id;            ///< Mavlink system id
    bool    _active;
dogmaphobic's avatar
dogmaphobic committed
440

441
    MAV_AUTOPILOT       _firmwareType;
442
    MAV_TYPE            _vehicleType;
443 444
    FirmwarePlugin*     _firmwarePlugin;
    AutoPilotPlugin*    _autopilotPlugin;
Don Gagne's avatar
Don Gagne committed
445
    MAVLinkProtocol*    _mavlink;
dogmaphobic's avatar
dogmaphobic committed
446

Don Gagne's avatar
Don Gagne committed
447
    QList<LinkInterface*> _links;
dogmaphobic's avatar
dogmaphobic committed
448

449
    JoystickMode_t  _joystickMode;
450
    bool            _joystickEnabled;
dogmaphobic's avatar
dogmaphobic committed
451

452
    UAS* _uas;
dogmaphobic's avatar
dogmaphobic committed
453

454 455
    QGeoCoordinate  _coordinate;
    bool            _coordinateValid;       ///< true: vehicle has 3d lock and therefore valid location
dogmaphobic's avatar
dogmaphobic committed
456

457 458
    bool            _homePositionAvailable;
    QGeoCoordinate  _homePosition;
dogmaphobic's avatar
dogmaphobic committed
459

460 461 462 463 464 465 466 467 468 469 470 471 472 473 474 475 476 477
    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;
    double          _batteryVoltage;
    double          _batteryPercent;
    double          _batteryConsumed;
    QString         _currentState;
    int             _updateCount;
dogmaphobic's avatar
dogmaphobic committed
478
    QString         _formatedMessage;
Don Gagne's avatar
Don Gagne committed
479 480
    int             _rcRSSI;
    double          _rcRSSIstore;
Don Gagne's avatar
Don Gagne committed
481
    bool            _autoDisconnect;    ///< true: Automatically disconnect vehicle when last connection goes away or lost heartbeat
dogmaphobic's avatar
dogmaphobic committed
482

483 484 485 486 487 488
    // 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
489
    MissionManager*     _missionManager;
490
    bool                _missionManagerInitialRequestComplete;
491 492

    ParameterLoader*    _parameterLoader;
dogmaphobic's avatar
dogmaphobic committed
493

Don Gagne's avatar
Don Gagne committed
494 495 496
    bool    _armed;         ///< true: vehicle is armed
    uint8_t _base_mode;     ///< base_mode from HEARTBEAT
    uint32_t _custom_mode;  ///< custom_mode from HEARTBEAT
497 498 499 500 501 502

    /// Used to store a message being sent by sendMessageMultiple
    typedef struct {
        mavlink_message_t   message;    ///< Message to send multiple times
        int                 retryCount; ///< Number of retries left
    } SendMessageMultipleInfo_t;
dogmaphobic's avatar
dogmaphobic committed
503

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

506 507
    static const int _sendMessageMultipleRetries = 5;
    static const int _sendMessageMultipleIntraMessageDelay = 500;
dogmaphobic's avatar
dogmaphobic committed
508

509 510
    QTimer  _sendMultipleTimer;
    int     _nextSendMessageMultipleIndex;
dogmaphobic's avatar
dogmaphobic committed
511

512 513 514 515 516
    QTimer              _mapTrajectoryTimer;
    QmlObjectListModel  _mapTrajectoryList;
    QGeoCoordinate      _mapTrajectoryLastCoordinate;
    bool                _mapTrajectoryHaveFirstCoordinate;
    static const int    _mapTrajectoryMsecsBetweenPoints = 1000;
517

dogmaphobic's avatar
dogmaphobic committed
518 519 520 521 522 523
    FirmwarePluginManager*      _firmwarePluginManager;
    AutoPilotPluginManager*     _autopilotPluginManager;
    JoystickManager*            _joystickManager;

    int                         _flowImageIndex;

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

526 527 528 529 530 531 532
    uint                _messagesReceived;
    uint                _messagesSent;
    uint                _messagesLost;
    uint8_t             _messageSeq;
    uint8_t             _compID;
    bool                _heardFrom;

Don Gagne's avatar
Don Gagne committed
533 534 535 536 537 538 539 540 541 542 543 544 545 546 547 548 549 550 551 552 553 554 555 556 557 558 559
    // FactGroup facts

    Fact _rollFact;
    Fact _pitchFact;
    Fact _headingFact;
    Fact _groundSpeedFact;
    Fact _airSpeedFact;
    Fact _climbRateFact;
    Fact _altitudeRelativeFact;
    Fact _altitudeWGS84Fact;
    Fact _altitudeAMSLFact;

    VehicleGPSFactGroup _gpsFactGroup;

    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* _altitudeWGS84FactName;
    static const char* _altitudeAMSLFactName;
    static const char* _gpsFactGroupName;

    static const int _vehicleUIUpdateRateMSecs = 100;

560
    // Settings keys
561 562
    static const char* _settingsGroup;
    static const char* _joystickModeSettingsKey;
563
    static const char* _joystickEnabledSettingsKey;
Don Gagne's avatar
Don Gagne committed
564

565 566
};
#endif