QGCCameraManager.h 4 KB
Newer Older
1 2 3 4 5 6 7 8 9 10 11 12 13 14 15 16 17 18 19
/*!
 * @file
 *   @brief Camera Controller
 *   @author Gus Grubba <mavlink@grubba.com>
 *
 */

#pragma once

#include "QGCApplication.h"
#include <QLoggingCategory>
#include "QmlObjectListModel.h"
#include "QGCCameraControl.h"

#include <QObject>
#include <QTimer>

Q_DECLARE_LOGGING_CATEGORY(CameraManagerLog)

20 21
class Joystick;

22 23 24 25 26 27
//-----------------------------------------------------------------------------
class QGCCameraManager : public QObject
{
    Q_OBJECT
public:
    QGCCameraManager(Vehicle* vehicle);
Gus Grubba's avatar
Gus Grubba committed
28
    virtual ~QGCCameraManager();
29

30 31
    Q_PROPERTY(QmlObjectListModel*  cameras                 READ cameras                                        NOTIFY camerasChanged)
    Q_PROPERTY(QStringList          cameraLabels            READ cameraLabels                                   NOTIFY cameraLabelsChanged)
32
    Q_PROPERTY(QGCCameraControl*    currentCameraInstance   READ currentCameraInstance                          NOTIFY currentCameraChanged)
33
    Q_PROPERTY(int                  currentCamera           READ currentCamera      WRITE  setCurrentCamera     NOTIFY currentCameraChanged)
34 35

    //-- Return a list of cameras provided by this vehicle
Gus Grubba's avatar
Gus Grubba committed
36 37 38 39 40
    virtual QmlObjectListModel* cameras             () { return &_cameras; }
    //-- Camera names to show the user (for selection)
    virtual QStringList          cameraLabels       () { return _cameraLabels; }
    //-- Current selected camera
    virtual int                 currentCamera       () { return _currentCamera; }
41
    virtual QGCCameraControl*   currentCameraInstance();
Gus Grubba's avatar
Gus Grubba committed
42 43
    //-- Set current camera
    virtual void                setCurrentCamera    (int sel);
44 45
    //-- Current stream
    virtual QGCVideoStreamInfo* currentStreamInstance();
46 47
    //-- Current thermal stream
    virtual QGCVideoStreamInfo* thermalStreamInstance();
48 49

signals:
Gus Grubba's avatar
Gus Grubba committed
50 51 52
    void    camerasChanged          ();
    void    cameraLabelsChanged     ();
    void    currentCameraChanged    ();
53
    void    streamChanged           ();
54

Gus Grubba's avatar
Gus Grubba committed
55
protected slots:
Gus Grubba's avatar
Gus Grubba committed
56 57
    virtual void    _vehicleReady           (bool ready);
    virtual void    _mavlinkMessageReceived (const mavlink_message_t& message);
58 59 60
    virtual void    _activeJoystickChanged  (Joystick* joystick);
    virtual void    _stepZoom               (int direction);
    virtual void    _stepCamera             (int direction);
61
    virtual void    _stepStream             (int direction);
62
    virtual void    _cameraTimeout          ();
Gus Grubba's avatar
Gus Grubba committed
63 64

protected:
Gus Grubba's avatar
Gus Grubba committed
65 66 67 68 69 70 71 72 73
    virtual QGCCameraControl* _findCamera   (int id);
    virtual void    _requestCameraInfo      (int compID);
    virtual void    _handleHeartbeat        (const mavlink_message_t& message);
    virtual void    _handleCameraInfo       (const mavlink_message_t& message);
    virtual void    _handleStorageInfo      (const mavlink_message_t& message);
    virtual void    _handleCameraSettings   (const mavlink_message_t& message);
    virtual void    _handleParamAck         (const mavlink_message_t& message);
    virtual void    _handleParamValue       (const mavlink_message_t& message);
    virtual void    _handleCaptureStatus    (const mavlink_message_t& message);
74 75
    virtual void    _handleVideoStreamInfo  (const mavlink_message_t& message);
    virtual void    _handleVideoStreamStatus(const mavlink_message_t& message);
76

Gus Grubba's avatar
Gus Grubba committed
77
protected:
78 79 80

    class CameraStruct : public QObject {
    public:
81
        CameraStruct(QObject* parent, uint8_t compID_);
82 83 84 85
        QTime   lastHeartbeat;
        bool    infoReceived = false;
        bool    gaveUp       = false;
        int     tryCount     = 0;
86
        uint8_t compID       = 0;
87 88
    };

89 90 91 92
    Vehicle*            _vehicle            = nullptr;
    Joystick*           _activeJoystick     = nullptr;
    bool                _vehicleReadyState  = false;
    int                 _currentTask        = 0;
93
    QmlObjectListModel  _cameras;
Gus Grubba's avatar
Gus Grubba committed
94
    QStringList         _cameraLabels;
95 96 97
    int                 _currentCamera      = 0;
    QTime               _lastZoomChange;
    QTime               _lastCameraChange;
98
    QTimer              _cameraTimer;
99
    QMap<QString, CameraStruct*> _cameraInfoRequest;
100
};