Vehicle.h 38.6 KB
Newer Older
1 2 3 4 5 6 7 8
/****************************************************************************
 *
 *   (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.
 *
 ****************************************************************************/
dogmaphobic's avatar
dogmaphobic committed
9

10 11 12 13 14 15 16 17

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

#ifndef Vehicle_H
#define Vehicle_H

#include <QObject>
18
#include <QGeoCoordinate>
19
#include <QElapsedTimer>
20

Don Gagne's avatar
Don Gagne committed
21
#include "FactGroup.h"
22 23
#include "LinkInterface.h"
#include "QGCMAVLink.h"
24
#include "QmlObjectListModel.h"
Don Gagne's avatar
Don Gagne committed
25
#include "MAVLinkProtocol.h"
dogmaphobic's avatar
dogmaphobic committed
26
#include "UASMessageHandler.h"
27
#include "SettingsFact.h"
28

29 30
class UAS;
class UASInterface;
31
class FirmwarePlugin;
32
class FirmwarePluginManager;
33
class AutoPilotPlugin;
34
class AutoPilotPluginManager;
Don Gagne's avatar
Don Gagne committed
35
class MissionManager;
36
class ParameterLoader;
37
class JoystickManager;
dogmaphobic's avatar
dogmaphobic committed
38
class UASMessage;
39 40 41

Q_DECLARE_LOGGING_CATEGORY(VehicleLog)

Don Gagne's avatar
Don Gagne committed
42 43
class Vehicle;

44 45 46 47 48 49 50 51 52 53 54 55 56 57
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)

58 59 60 61 62 63
    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; }
64 65 66 67 68 69 70 71 72 73 74 75 76 77 78 79 80 81 82 83

    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
84 85 86 87 88 89 90 91 92 93 94
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)

95 96 97
    Fact* direction     (void) { return &_directionFact; }
    Fact* speed         (void) { return &_speedFact; }
    Fact* verticalSpeed (void) { return &_verticalSpeedFact; }
Don Gagne's avatar
Don Gagne committed
98 99 100 101 102 103 104 105 106 107 108 109 110 111

    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
112 113 114 115 116 117 118 119 120 121 122 123 124
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)

125 126 127 128 129
    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
130 131 132

    void setVehicle(Vehicle* vehicle);

Don Gagne's avatar
Don Gagne committed
133 134 135 136 137 138
    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
139 140 141 142 143 144 145 146 147 148 149 150 151 152
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
153
};
Don Gagne's avatar
Don Gagne committed
154

Don Gagne's avatar
Don Gagne committed
155 156 157 158 159 160 161 162 163 164 165 166
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)
167 168 169 170 171 172 173
    Q_PROPERTY(Fact* cellCount          READ cellCount          CONSTANT)

    /// If percentRemaining falls below this value, warning will be output through speech
    Q_PROPERTY(Fact* percentRemainingAnnounce READ percentRemainingAnnounce CONSTANT)

    Fact* voltage                   (void) { return &_voltageFact; }
    Fact* percentRemaining          (void) { return &_percentRemainingFact; }
174
    Fact* percentRemainingAnnounce  (void);
175 176 177 178
    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
179 180 181 182 183 184


    void setVehicle(Vehicle* vehicle);

    static const char* _voltageFactName;
    static const char* _percentRemainingFactName;
185
    static const char* _percentRemainingAnnounceFactName;
Don Gagne's avatar
Don Gagne committed
186 187 188 189 190
    static const char* _mahConsumedFactName;
    static const char* _currentFactName;
    static const char* _temperatureFactName;
    static const char* _cellCountFactName;

191 192 193
    static const char* _settingsGroup;
    static const int   _percentRemainingAnnounceDefault;

Don Gagne's avatar
Don Gagne committed
194 195 196 197 198 199 200 201
    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:
202 203 204 205 206 207 208 209
    Vehicle*        _vehicle;
    Fact            _voltageFact;
    Fact            _percentRemainingFact;
    Fact            _mahConsumedFact;
    Fact            _currentFact;
    Fact            _temperatureFact;
    Fact            _cellCountFact;

210 211 212
    /// This fact is global to all Vehicles. We must allocated the first time we need it so we don't
    /// run into QSettings application setup ordering issues.
    static SettingsFact* _percentRemainingAnnounceFact;
Don Gagne's avatar
Don Gagne committed
213 214 215
};

class Vehicle : public FactGroup
216 217
{
    Q_OBJECT
dogmaphobic's avatar
dogmaphobic committed
218

219
public:
220 221 222 223 224 225 226
    Vehicle(LinkInterface*          link,
            int                     vehicleId,
            MAV_AUTOPILOT           firmwareType,
            MAV_TYPE                vehicleType,
            FirmwarePluginManager*  firmwarePluginManager,
            AutoPilotPluginManager* autopilotPluginManager,
            JoystickManager*        joystickManager);
227 228 229 230 231

    // The following is used to create a disconnected Vehicle. A disconnected vehicle is primarily used to access FactGroup information
    // without needing a real connection.
    Vehicle(QObject* parent = NULL);

232
    ~Vehicle();
dogmaphobic's avatar
dogmaphobic committed
233

234 235 236 237 238 239 240 241 242 243 244 245 246 247 248 249 250 251 252 253 254 255 256 257 258 259 260 261 262 263 264 265 266 267 268 269 270 271 272 273 274 275 276 277
    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(bool                 missingParameters       READ missingParameters                                      NOTIFY missingParametersChanged)
    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)
278
    Q_PROPERTY(bool                 supportsManualControl   READ supportsManualControl                                  CONSTANT)
279
    Q_PROPERTY(bool        supportsThrottleModeCenterZero   READ supportsThrottleModeCenterZero                         CONSTANT)
280
    Q_PROPERTY(bool                 supportsJSButton        READ supportsJSButton                                       CONSTANT)
281
    Q_PROPERTY(bool                 sub                     READ sub                                                    CONSTANT)
282 283
    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
284 285 286
    Q_PROPERTY(int                  motorCount              READ motorCount                                             CONSTANT)
    Q_PROPERTY(bool                 coaxialMotors           READ coaxialMotors                                          CONSTANT)
    Q_PROPERTY(bool                 xConfigMotors           READ xConfigMotors                                          CONSTANT)
287

Don Gagne's avatar
Don Gagne committed
288 289 290 291 292 293 294 295 296 297 298 299
    /// 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)

300 301 302
    /// true: Orbit mode is supported by this vehicle
    Q_PROPERTY(bool orbitModeSupported READ orbitModeSupported CONSTANT)

Don Gagne's avatar
Don Gagne committed
303 304 305 306 307 308 309 310 311 312 313
    // 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
314 315
    Q_PROPERTY(FactGroup* gps       READ gpsFactGroup       CONSTANT)
    Q_PROPERTY(FactGroup* battery   READ batteryFactGroup   CONSTANT)
316 317
    Q_PROPERTY(FactGroup* wind      READ windFactGroup      CONSTANT)
    Q_PROPERTY(FactGroup* vibration READ vibrationFactGroup CONSTANT)
Don Gagne's avatar
Don Gagne committed
318

319 320 321 322 323 324
    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)

325 326
    /// Resets link status counters
    Q_INVOKABLE void resetCounters  ();
327 328 329 330 331 332 333 334

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

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

Don Gagne's avatar
Don Gagne committed
339
    Q_INVOKABLE void virtualTabletJoystickValue(double roll, double pitch, double yaw, double thrust);
Don Gagne's avatar
Don Gagne committed
340
    Q_INVOKABLE void disconnectInactiveVehicle(void);
Don Gagne's avatar
Don Gagne committed
341

342 343
    Q_INVOKABLE void clearTrajectoryPoints(void);

Don Gagne's avatar
Don Gagne committed
344 345 346 347 348 349 350 351 352 353 354 355 356 357 358
    /// 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);

359 360 361 362 363 364 365
    /// 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
366 367 368 369 370 371 372
    /// 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);

373 374 375
    /// Alter the current mission item on the vehicle
    Q_INVOKABLE void setCurrentMissionSequence(int seq);

376 377 378
    /// Reboot vehicle
    Q_INVOKABLE void rebootVehicle();

dogmaphobic's avatar
dogmaphobic committed
379 380 381
    /// Clear Messages
    Q_INVOKABLE void clearMessages();

Don Gagne's avatar
Don Gagne committed
382 383
#if 0
    // Temporarily removed, waiting for new command implementation
Don Gagne's avatar
Don Gagne committed
384 385 386 387 388
    /// 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
389
#endif
Don Gagne's avatar
Don Gagne committed
390

Don Gagne's avatar
Don Gagne committed
391 392
    bool guidedModeSupported(void) const;
    bool pauseVehicleSupported(void) const;
393
    bool orbitModeSupported(void) const;
Don Gagne's avatar
Don Gagne committed
394

395
    // Property accessors
Don Gagne's avatar
Don Gagne committed
396

397 398
    QGeoCoordinate coordinate(void) { return _coordinate; }
    bool coordinateValid(void)      { return _coordinateValid; }
Don Gagne's avatar
Don Gagne committed
399
    void _setCoordinateValid(bool coordinateValid);
dogmaphobic's avatar
dogmaphobic committed
400

401
    typedef enum {
402
        JoystickModeRC,         ///< Joystick emulates an RC Transmitter
403 404 405 406 407 408
        JoystickModeAttitude,
        JoystickModePosition,
        JoystickModeForce,
        JoystickModeVelocity,
        JoystickModeMax
    } JoystickMode_t;
dogmaphobic's avatar
dogmaphobic committed
409

410 411
    int joystickMode(void);
    void setJoystickMode(int mode);
dogmaphobic's avatar
dogmaphobic committed
412

413 414
    /// List of joystick mode names
    QStringList joystickModes(void);
dogmaphobic's avatar
dogmaphobic committed
415

416 417
    bool joystickEnabled(void);
    void setJoystickEnabled(bool enabled);
dogmaphobic's avatar
dogmaphobic committed
418

419 420 421
    // Is vehicle active with respect to current active vehicle in QGC
    bool active(void);
    void setActive(bool active);
dogmaphobic's avatar
dogmaphobic committed
422

423 424
    // Property accesors
    int id(void) { return _id; }
425 426
    MAV_AUTOPILOT firmwareType(void) const { return _firmwareType; }
    MAV_TYPE vehicleType(void) const { return _vehicleType; }
427
    Q_INVOKABLE QString vehicleTypeName(void) const;
dogmaphobic's avatar
dogmaphobic committed
428

429 430 431 432 433 434 435
    /// 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);

436 437 438 439
    /// Sends a message to the priority link
    /// @return true: message sent, false: Link no longer connected
    bool sendMessageOnPriorityLink(mavlink_message_t message) { return sendMessageOnLink(priorityLink(), message); }

440 441 442
    /// 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
443

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

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

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

453
    int manualControlReservedButtonCount(void);
dogmaphobic's avatar
dogmaphobic committed
454

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

457 458
    bool homePositionAvailable(void);
    QGeoCoordinate homePosition(void);
dogmaphobic's avatar
dogmaphobic committed
459

Don Gagne's avatar
Don Gagne committed
460 461 462 463 464
    bool armed(void) { return _armed; }
    void setArmed(bool armed);

    bool flightModeSetAvailable(void);
    QStringList flightModes(void);
Don Gagne's avatar
Don Gagne committed
465
    QString flightMode(void) const;
Don Gagne's avatar
Don Gagne committed
466 467 468 469
    void setFlightMode(const QString& flightMode);

    bool hilMode(void);
    void setHilMode(bool hilMode);
dogmaphobic's avatar
dogmaphobic committed
470

471 472
    bool fixedWing(void) const;
    bool multiRotor(void) const;
Don Gagne's avatar
Don Gagne committed
473
    bool vtol(void) const;
Don Gagne's avatar
Don Gagne committed
474
    bool rover(void) const;
475
    bool sub(void) const;
476

477
    bool supportsManualControl(void) const;
478
    bool supportsThrottleModeCenterZero(void) const;
479
    bool supportsRadio(void) const;
480
    bool supportsJSButton(void) const;
481

Don Gagne's avatar
Don Gagne committed
482 483 484
    void setFlying(bool flying);
    void setGuidedMode(bool guidedMode);

Don Gagne's avatar
Don Gagne committed
485 486 487
    QString prearmError(void) const { return _prearmError; }
    void setPrearmError(const QString& prearmError);

488
    QmlObjectListModel* trajectoryPoints(void) { return &_mapTrajectoryList; }
dogmaphobic's avatar
dogmaphobic committed
489 490 491

    int  flowImageIndex() { return _flowImageIndex; }

492 493 494
    /// 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
495 496
    ///     @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
497

498
    bool missingParameters(void);
dogmaphobic's avatar
dogmaphobic committed
499

500 501 502 503 504 505
    typedef enum {
        MessageNone,
        MessageNormal,
        MessageWarning,
        MessageError
    } MessageType_t;
dogmaphobic's avatar
dogmaphobic committed
506

507 508 509 510 511 512
    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
513 514
    QString         formatedMessages    ();
    QString         formatedMessage     () { return _formatedMessage; }
515
    QString         latestError         () { return _latestError; }
516 517
    float           latitude            () { return _coordinate.latitude(); }
    float           longitude           () { return _coordinate.longitude(); }
518 519
    bool            mavPresent          () { return _mav != NULL; }
    QString         currentState        () { return _currentState; }
Don Gagne's avatar
Don Gagne committed
520
    int             rcRSSI              () { return _rcRSSI; }
Don Gagne's avatar
Don Gagne committed
521 522 523
    bool            px4Firmware         () const { return _firmwareType == MAV_AUTOPILOT_PX4; }
    bool            apmFirmware         () const { return _firmwareType == MAV_AUTOPILOT_ARDUPILOTMEGA; }
    bool            genericFirmware     () const { return !px4Firmware() && !apmFirmware(); }
524 525
    bool            connectionLost      () const { return _connectionLost; }
    bool            connectionLostEnabled() const { return _connectionLostEnabled; }
526 527 528
    uint            messagesReceived    () { return _messagesReceived; }
    uint            messagesSent        () { return _messagesSent; }
    uint            messagesLost        () { return _messagesLost; }
Don Gagne's avatar
Don Gagne committed
529 530
    bool            flying              () const { return _flying; }
    bool            guidedMode          () const;
531 532
    uint8_t         baseMode            () const { return _base_mode; }
    uint32_t        customMode          () const { return _custom_mode; }
533

Don Gagne's avatar
Don Gagne committed
534 535 536 537 538 539 540 541 542
    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; }

543 544 545 546
    FactGroup* gpsFactGroup         (void) { return &_gpsFactGroup; }
    FactGroup* batteryFactGroup     (void) { return &_batteryFactGroup; }
    FactGroup* windFactGroup        (void) { return &_windFactGroup; }
    FactGroup* vibrationFactGroup   (void) { return &_vibrationFactGroup; }
Don Gagne's avatar
Don Gagne committed
547

548
    void setConnectionLostEnabled(bool connectionLostEnabled);
549 550

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

Don Gagne's avatar
Don Gagne committed
552 553
    static const int cMaxRcChannels = 18;

Don Gagne's avatar
Don Gagne committed
554
    bool containsLink(LinkInterface* link) { return _links.contains(link); }
Don Gagne's avatar
Don Gagne committed
555
    void doCommandLong(int component, MAV_CMD command, float param1 = 0.0f, float param2 = 0.0f, float param3 = 0.0f, float param4 = 0.0f, float param5 = 0.0f, float param6 = 0.0f, float param7 = 0.0f);
Don Gagne's avatar
Don Gagne committed
556

Don Gagne's avatar
Don Gagne committed
557 558 559
    int firmwareMajorVersion(void) const { return _firmwareMajorVersion; }
    int firmwareMinorVersion(void) const { return _firmwareMinorVersion; }
    int firmwarePatchVersion(void) const { return _firmwarePatchVersion; }
560 561 562
    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);
563
    static const int versionNotSetValue = -1;
Don Gagne's avatar
Don Gagne committed
564

565 566 567
    bool soloFirmware(void) const { return _soloFirmware; }
    void setSoloFirmware(bool soloFirmware);

Don Gagne's avatar
Don Gagne committed
568 569
    int defaultComponentId(void);

Don Gagne's avatar
Don Gagne committed
570 571 572 573 574 575 576 577 578
    /// @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);

579 580 581
public slots:
    void setLatitude(double latitude);
    void setLongitude(double longitude);
dogmaphobic's avatar
dogmaphobic committed
582

583
signals:
Don Gagne's avatar
Don Gagne committed
584
    void allLinksInactive(Vehicle* vehicle);
585
    void coordinateChanged(QGeoCoordinate coordinate);
586
    void coordinateValidChanged(bool coordinateValid);
587
    void joystickModeChanged(int mode);
588 589
    void joystickEnabledChanged(bool enabled);
    void activeChanged(bool active);
Don Gagne's avatar
Don Gagne committed
590
    void mavlinkMessageReceived(const mavlink_message_t& message);
591 592
    void homePositionAvailableChanged(bool homePositionAvailable);
    void homePositionChanged(const QGeoCoordinate& homePosition);
Don Gagne's avatar
Don Gagne committed
593 594 595
    void armedChanged(bool armed);
    void flightModeChanged(const QString& flightMode);
    void hilModeChanged(bool hilMode);
596
    void missingParametersChanged(bool missingParameters);
597 598
    void connectionLostChanged(bool connectionLost);
    void connectionLostEnabledChanged(bool connectionLostEnabled);
Don Gagne's avatar
Don Gagne committed
599
    void autoDisconnectChanged(bool autoDisconnectChanged);
Don Gagne's avatar
Don Gagne committed
600 601
    void flyingChanged(bool flying);
    void guidedModeChanged(bool guidedMode);
Don Gagne's avatar
Don Gagne committed
602
    void prearmErrorChanged(const QString& prearmError);
603
    void commandLongAck(uint8_t compID, uint16_t command, uint8_t result);
604
    void soloFirmwareChanged(bool soloFirmware);
dogmaphobic's avatar
dogmaphobic committed
605

606 607 608 609
    void messagesReceivedChanged    ();
    void messagesSentChanged        ();
    void messagesLostChanged        ();

610
    /// Used internally to move sendMessage call to main thread
611
    void _sendMessageOnLinkOnThread(LinkInterface* link, mavlink_message_t message);
dogmaphobic's avatar
dogmaphobic committed
612

613 614 615
    void messageTypeChanged     ();
    void newMessageCountChanged ();
    void messageCountChanged    ();
dogmaphobic's avatar
dogmaphobic committed
616 617
    void formatedMessagesChanged();
    void formatedMessageChanged ();
618 619 620 621
    void latestErrorChanged     ();
    void longitudeChanged       ();
    void currentConfigChanged   ();
    void currentStateChanged    ();
dogmaphobic's avatar
dogmaphobic committed
622
    void flowImageIndexChanged  ();
Don Gagne's avatar
Don Gagne committed
623
    void rcRSSIChanged          (int rcRSSI);
dogmaphobic's avatar
dogmaphobic committed
624

625 626 627 628 629
    void firmwareMajorVersionChanged(int major);
    void firmwareMinorVersionChanged(int minor);
    void firmwarePatchVersionChanged(int patch);
    void firmwareVersionTypeChanged(int type);

Don Gagne's avatar
Don Gagne committed
630 631 632 633 634 635 636 637
    /// 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);

638 639 640 641 642
    void mavlinkRawImu(mavlink_message_t message);
    void mavlinkScaledImu1(mavlink_message_t message);
    void mavlinkScaledImu2(mavlink_message_t message);
    void mavlinkScaledImu3(mavlink_message_t message);

643 644
private slots:
    void _mavlinkMessageReceived(LinkInterface* link, mavlink_message_t message);
Don Gagne's avatar
Don Gagne committed
645
    void _linkInactiveOrDeleted(LinkInterface* link);
646
    void _sendMessageOnLink(LinkInterface* link, mavlink_message_t message);
647
    void _sendMessageMultipleNext(void);
648
    void _addNewMapTrajectoryPoint(void);
649
    void _parametersReady(bool parametersReady);
Don Gagne's avatar
Don Gagne committed
650
    void _remoteControlRSSIChanged(uint8_t rssi);
Don Gagne's avatar
Don Gagne committed
651
    void _handleFlightModeChanged(const QString& flightMode);
652
    void _announceArmedChanged(bool armed);
653

654
    void _handleTextMessage                 (int newCount);
dogmaphobic's avatar
dogmaphobic committed
655
    void _handletextMessageReceived         (UASMessage* message);
656 657 658 659 660
    /** @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
661
    void _updateAltitude                    (UASInterface* uas, double _altitudeAMSL, double _altitudeRelative, double _climbRate, quint64 timestamp);
662 663 664 665
    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
666 667
    /** @brief A new camera image has arrived */
    void _imageReady                        (UASInterface* uas);
668
    void _connectionLostTimeout(void);
Don Gagne's avatar
Don Gagne committed
669
    void _prearmErrorTimeout(void);
670

671 672 673
private:
    bool _containsLink(LinkInterface* link);
    void _addLink(LinkInterface* link);
674 675
    void _loadSettings(void);
    void _saveSettings(void);
676
    void _startJoystick(bool start);
Don Gagne's avatar
Don Gagne committed
677 678
    void _handleHomePosition(mavlink_message_t& message);
    void _handleHeartbeat(mavlink_message_t& message);
Don Gagne's avatar
Don Gagne committed
679 680
    void _handleRCChannels(mavlink_message_t& message);
    void _handleRCChannelsRaw(mavlink_message_t& message);
Don Gagne's avatar
Don Gagne committed
681 682
    void _handleBatteryStatus(mavlink_message_t& message);
    void _handleSysStatus(mavlink_message_t& message);
683
    void _handleWindCov(mavlink_message_t& message);
Don Gagne's avatar
Don Gagne committed
684
    void _handleWind(mavlink_message_t& message);
685
    void _handleVibration(mavlink_message_t& message);
Don Gagne's avatar
Don Gagne committed
686
    void _handleExtendedSysState(mavlink_message_t& message);
687
    void _handleCommandAck(mavlink_message_t& message);
688
    void _handleAutopilotVersion(mavlink_message_t& message);
689
    void _missionManagerError(int errorCode, const QString& errorMsg);
690 691
    void _mapTrajectoryStart(void);
    void _mapTrajectoryStop(void);
692
    void _connectionActive(void);
693 694
    void _say(const QString& text);
    QString _vehicleIdSpeech(void);
Don Gagne's avatar
Don Gagne committed
695

696
private:
697 698
    int     _id;            ///< Mavlink system id
    bool    _active;
699
    bool    _disconnectedVehicle;   ///< This Vehicle is a "disconnected" vehicle for ui use when no active vehicle is available
dogmaphobic's avatar
dogmaphobic committed
700

701
    MAV_AUTOPILOT       _firmwareType;
702
    MAV_TYPE            _vehicleType;
703 704
    FirmwarePlugin*     _firmwarePlugin;
    AutoPilotPlugin*    _autopilotPlugin;
Don Gagne's avatar
Don Gagne committed
705
    MAVLinkProtocol*    _mavlink;
706
    bool                _soloFirmware;
dogmaphobic's avatar
dogmaphobic committed
707

Don Gagne's avatar
Don Gagne committed
708
    QList<LinkInterface*> _links;
dogmaphobic's avatar
dogmaphobic committed
709

710
    JoystickMode_t  _joystickMode;
711
    bool            _joystickEnabled;
dogmaphobic's avatar
dogmaphobic committed
712

713
    UAS* _uas;
dogmaphobic's avatar
dogmaphobic committed
714

715 716
    QGeoCoordinate  _coordinate;
    bool            _coordinateValid;       ///< true: vehicle has 3d lock and therefore valid location
dogmaphobic's avatar
dogmaphobic committed
717

718 719
    bool            _homePositionAvailable;
    QGeoCoordinate  _homePosition;
dogmaphobic's avatar
dogmaphobic committed
720

721 722 723 724 725 726 727 728 729 730 731 732 733 734 735
    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
736
    QString         _formatedMessage;
Don Gagne's avatar
Don Gagne committed
737 738
    int             _rcRSSI;
    double          _rcRSSIstore;
Don Gagne's avatar
Don Gagne committed
739
    bool            _autoDisconnect;    ///< true: Automatically disconnect vehicle when last connection goes away or lost heartbeat
Don Gagne's avatar
Don Gagne committed
740
    bool            _flying;
dogmaphobic's avatar
dogmaphobic committed
741

Don Gagne's avatar
Don Gagne committed
742 743 744 745
    QString             _prearmError;
    QTimer              _prearmErrorTimer;
    static const int    _prearmErrorTimeoutMSecs = 35 * 1000;   ///< Take away prearm error after 35 seconds

746 747 748 749 750 751
    // 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
752
    MissionManager*     _missionManager;
753
    bool                _missionManagerInitialRequestComplete;
754 755

    ParameterLoader*    _parameterLoader;
dogmaphobic's avatar
dogmaphobic committed
756

Don Gagne's avatar
Don Gagne committed
757 758 759
    bool    _armed;         ///< true: vehicle is armed
    uint8_t _base_mode;     ///< base_mode from HEARTBEAT
    uint32_t _custom_mode;  ///< custom_mode from HEARTBEAT
760 761 762 763 764 765

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

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

769 770
    static const int _sendMessageMultipleRetries = 5;
    static const int _sendMessageMultipleIntraMessageDelay = 500;
dogmaphobic's avatar
dogmaphobic committed
771

772 773
    QTimer  _sendMultipleTimer;
    int     _nextSendMessageMultipleIndex;
dogmaphobic's avatar
dogmaphobic committed
774

775 776 777 778 779
    QTimer              _mapTrajectoryTimer;
    QmlObjectListModel  _mapTrajectoryList;
    QGeoCoordinate      _mapTrajectoryLastCoordinate;
    bool                _mapTrajectoryHaveFirstCoordinate;
    static const int    _mapTrajectoryMsecsBetweenPoints = 1000;
780

781
    // Toolbox references
dogmaphobic's avatar
dogmaphobic committed
782 783 784 785 786 787
    FirmwarePluginManager*      _firmwarePluginManager;
    AutoPilotPluginManager*     _autopilotPluginManager;
    JoystickManager*            _joystickManager;

    int                         _flowImageIndex;

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

790 791 792 793 794 795 796
    uint                _messagesReceived;
    uint                _messagesSent;
    uint                _messagesLost;
    uint8_t             _messageSeq;
    uint8_t             _compID;
    bool                _heardFrom;

Don Gagne's avatar
Don Gagne committed
797 798 799
    int _firmwareMajorVersion;
    int _firmwareMinorVersion;
    int _firmwarePatchVersion;
800
    FIRMWARE_VERSION_TYPE _firmwareVersionType;
Don Gagne's avatar
Don Gagne committed
801

802 803 804
    static const int    _lowBatteryAnnounceRepeatMSecs; // Amount of time in between each low battery announcement
    QElapsedTimer       _lowBatteryAnnounceTimer;

Don Gagne's avatar
Don Gagne committed
805 806 807 808 809 810 811 812 813 814 815
    // FactGroup facts

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

816 817 818 819
    VehicleGPSFactGroup         _gpsFactGroup;
    VehicleBatteryFactGroup     _batteryFactGroup;
    VehicleWindFactGroup        _windFactGroup;
    VehicleVibrationFactGroup   _vibrationFactGroup;
Don Gagne's avatar
Don Gagne committed
820 821 822 823 824 825 826 827 828

    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
829

Don Gagne's avatar
Don Gagne committed
830
    static const char* _gpsFactGroupName;
Don Gagne's avatar
Don Gagne committed
831
    static const char* _batteryFactGroupName;
Don Gagne's avatar
Don Gagne committed
832
    static const char* _windFactGroupName;
833
    static const char* _vibrationFactGroupName;
Don Gagne's avatar
Don Gagne committed
834 835 836

    static const int _vehicleUIUpdateRateMSecs = 100;

837
    // Settings keys
838 839
    static const char* _settingsGroup;
    static const char* _joystickModeSettingsKey;
840
    static const char* _joystickEnabledSettingsKey;
Don Gagne's avatar
Don Gagne committed
841

842 843
};
#endif