MultiVehicleManager.h 6.04 KB
Newer Older
1 2
/****************************************************************************
 *
Gus Grubba's avatar
Gus Grubba committed
3
 * (c) 2009-2020 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org>
4 5 6 7 8
 *
 * 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 18

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

#ifndef MultiVehicleManager_H
#define MultiVehicleManager_H

#include "Vehicle.h"
#include "QGCMAVLink.h"
19
#include "QmlObjectListModel.h"
20
#include "QGCToolbox.h"
Don Gagne's avatar
Don Gagne committed
21
#include "QGCLoggingCategory.h"
22

23
class FirmwarePluginManager;
Jimmy Johnson's avatar
Jimmy Johnson committed
24
class FollowMe;
25 26 27 28
class JoystickManager;
class QGCApplication;
class MAVLinkProtocol;

Don Gagne's avatar
Don Gagne committed
29 30
Q_DECLARE_LOGGING_CATEGORY(MultiVehicleManagerLog)

31
class MultiVehicleManager : public QGCTool
32 33
{
    Q_OBJECT
dogmaphobic's avatar
dogmaphobic committed
34

35
public:
36
    MultiVehicleManager(QGCApplication* app, QGCToolbox* toolbox);
37

38 39
    Q_INVOKABLE void        saveSetting (const QString &key, const QString& value);
    Q_INVOKABLE QString     loadSetting (const QString &key, const QString& defaultValue);
dogmaphobic's avatar
dogmaphobic committed
40

41 42
    Q_PROPERTY(bool                 activeVehicleAvailable          READ activeVehicleAvailable                                         NOTIFY activeVehicleAvailableChanged)
    Q_PROPERTY(bool                 parameterReadyVehicleAvailable  READ parameterReadyVehicleAvailable                                 NOTIFY parameterReadyVehicleAvailableChanged)
43
    /// The current, active vehicle
44
    Q_PROPERTY(Vehicle*             activeVehicle                   READ activeVehicle                  WRITE setActiveVehicle          NOTIFY activeVehicleChanged)
45
    /// The list of all connected vehicles
46
    Q_PROPERTY(QmlObjectListModel*  vehicles                        READ vehicles                                                       CONSTANT)
47
    /// Enable sending heartbeats to the vehicle (defaults to true)
48
    Q_PROPERTY(bool                 gcsHeartBeatEnabled             READ gcsHeartbeatEnabled            WRITE setGcsHeartbeatEnabled    NOTIFY gcsHeartBeatEnabledChanged)
49 50
    /// A disconnected vehicle used for offline editing. It will match the vehicle type specified in Settings.
    Q_PROPERTY(Vehicle*             offlineEditingVehicle           READ offlineEditingVehicle                                          CONSTANT)
51
    /// The current vehicle's last known location
52 53
    Q_PROPERTY(QGeoCoordinate       lastKnownLocation               READ lastKnownLocation                                              NOTIFY lastKnownLocationChanged)

54
    // Methods
dogmaphobic's avatar
dogmaphobic committed
55

Don Gagne's avatar
Don Gagne committed
56
    Q_INVOKABLE Vehicle* getVehicleById(int vehicleId);
dogmaphobic's avatar
dogmaphobic committed
57

58
    UAS* activeUas(void) { return _activeVehicle ? _activeVehicle->uas() : nullptr; }
dogmaphobic's avatar
dogmaphobic committed
59

60
    // Property accessors
dogmaphobic's avatar
dogmaphobic committed
61

62
    bool activeVehicleAvailable(void) { return _activeVehicleAvailable; }
dogmaphobic's avatar
dogmaphobic committed
63

64
    bool parameterReadyVehicleAvailable(void) { return _parameterReadyVehicleAvailable; }
dogmaphobic's avatar
dogmaphobic committed
65

66 67
    Vehicle* activeVehicle(void) { return _activeVehicle; }
    void setActiveVehicle(Vehicle* vehicle);
dogmaphobic's avatar
dogmaphobic committed
68

69
    QmlObjectListModel* vehicles(void) { return &_vehicles; }
dogmaphobic's avatar
dogmaphobic committed
70

71 72 73
    bool gcsHeartbeatEnabled(void) const { return _gcsHeartbeatEnabled; }
    void setGcsHeartbeatEnabled(bool gcsHeartBeatEnabled);

74 75
    Vehicle* offlineEditingVehicle(void) { return _offlineEditingVehicle; }

76 77 78 79 80 81
    /// Determines if the link is in use by a Vehicle
    ///     @param link Link to test against
    ///     @param skipVehicle Don't consider this Vehicle as part of the test
    /// @return true: link is in use by one or more Vehicles
    bool linkInUse(LinkInterface* link, Vehicle* skipVehicle);

82 83 84
    // Override from QGCTool
    virtual void setToolbox(QGCToolbox *toolbox);

85 86
    QGeoCoordinate lastKnownLocation    () { return _lastKnownLocation; }

87
signals:
88 89 90
    void vehicleAdded                   (Vehicle* vehicle);
    void vehicleRemoved                 (Vehicle* vehicle);
    void activeVehicleAvailableChanged  (bool activeVehicleAvailable);
91
    void parameterReadyVehicleAvailableChanged(bool parameterReadyVehicleAvailable);
92 93 94
    void activeVehicleChanged           (Vehicle* activeVehicle);
    void gcsHeartBeatEnabledChanged     (bool gcsHeartBeatEnabled);
    void lastKnownLocationChanged       ();
95
#ifndef DOXYGEN_SKIP
96
    void _deleteVehiclePhase2Signal     (void);
97
#endif
dogmaphobic's avatar
dogmaphobic committed
98

99
private slots:
100 101 102 103 104 105 106 107
    void _deleteVehiclePhase1           (Vehicle* vehicle);
    void _deleteVehiclePhase2           (void);
    void _setActiveVehiclePhase2        (void);
    void _vehicleParametersReadyChanged (bool parametersReady);
    void _sendGCSHeartbeat              (void);
    void _vehicleHeartbeatInfo          (LinkInterface* link, int vehicleId, int componentId, int vehicleFirmwareType, int vehicleType);
    void _requestProtocolVersion        (unsigned version);
    void _coordinateChanged             (QGeoCoordinate coordinate);
dogmaphobic's avatar
dogmaphobic committed
108

109 110
private:
    bool _vehicleExists(int vehicleId);
dogmaphobic's avatar
dogmaphobic committed
111

112 113 114
    bool        _activeVehicleAvailable;            ///< true: An active vehicle is available
    bool        _parameterReadyVehicleAvailable;    ///< true: An active vehicle with ready parameters is available
    Vehicle*    _activeVehicle;                     ///< Currently active vehicle from a ui perspective
115
    Vehicle*    _offlineEditingVehicle;             ///< Disconnected vechicle used for offline editing
dogmaphobic's avatar
dogmaphobic committed
116

Don Gagne's avatar
Don Gagne committed
117 118
    QList<Vehicle*> _vehiclesBeingDeleted;          ///< List of Vehicles being deleted in queued phases
    Vehicle*        _vehicleBeingSetActive;         ///< Vehicle being set active in queued phases
dogmaphobic's avatar
dogmaphobic committed
119

120
    QList<int>  _ignoreVehicleIds;          ///< List of vehicle id for which we ignore further communication
dogmaphobic's avatar
dogmaphobic committed
121

122
    QmlObjectListModel  _vehicles;
123

dogmaphobic's avatar
dogmaphobic committed
124 125 126
    FirmwarePluginManager*      _firmwarePluginManager;
    JoystickManager*            _joystickManager;
    MAVLinkProtocol*            _mavlinkProtocol;
127
    QGeoCoordinate              _lastKnownLocation;
dogmaphobic's avatar
dogmaphobic committed
128

129 130 131 132
    QTimer              _gcsHeartbeatTimer;             ///< Timer to emit heartbeats
    bool                _gcsHeartbeatEnabled;           ///< Enabled/disable heartbeat emission
    static const int    _gcsHeartbeatRateMSecs = 1000;  ///< Heartbeat rate
    static const char*  _gcsHeartbeatEnabledKey;
133 134 135
};

#endif