QGCCameraManager.h 4.49 KB
Newer Older
1 2 3
/*!
 * @file
 *   @brief Camera Controller
Gus Grubba's avatar
Gus Grubba committed
4
 *   @author Gus Grubba <gus@auterion.com>
5 6 7
 *
 */

Gus Grubba's avatar
Gus Grubba committed
8 9 10 11
/// @file
/// @brief  MAVLink Camera API. Camera Manager.
/// @author Gus Grubba <gus@auterion.com>

12 13 14 15 16 17 18 19 20 21 22 23
#pragma once

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

#include <QObject>
#include <QTimer>

Q_DECLARE_LOGGING_CATEGORY(CameraManagerLog)

24 25
class Joystick;

26
//-----------------------------------------------------------------------------
Gus Grubba's avatar
Gus Grubba committed
27
/// Camera Manager
28 29 30 31 32
class QGCCameraManager : public QObject
{
    Q_OBJECT
public:
    QGCCameraManager(Vehicle* vehicle);
Gus Grubba's avatar
Gus Grubba committed
33
    virtual ~QGCCameraManager();
34

35 36
    Q_PROPERTY(QmlObjectListModel*  cameras                 READ cameras                                        NOTIFY camerasChanged)
    Q_PROPERTY(QStringList          cameraLabels            READ cameraLabels                                   NOTIFY cameraLabelsChanged)
37
    Q_PROPERTY(QGCCameraControl*    currentCameraInstance   READ currentCameraInstance                          NOTIFY currentCameraChanged)
38
    Q_PROPERTY(int                  currentCamera           READ currentCamera      WRITE  setCurrentCamera     NOTIFY currentCameraChanged)
39 40

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

signals:
Gus Grubba's avatar
Gus Grubba committed
55 56 57
    void    camerasChanged          ();
    void    cameraLabelsChanged     ();
    void    currentCameraChanged    ();
58
    void    streamChanged           ();
59

Gus Grubba's avatar
Gus Grubba committed
60
protected slots:
Gus Grubba's avatar
Gus Grubba committed
61 62
    virtual void    _vehicleReady           (bool ready);
    virtual void    _mavlinkMessageReceived (const mavlink_message_t& message);
63 64
    virtual void    _activeJoystickChanged  (Joystick* joystick);
    virtual void    _stepZoom               (int direction);
65 66
    virtual void    _startZoom              (int direction);
    virtual void    _stopZoom               ();
67
    virtual void    _stepCamera             (int direction);
68
    virtual void    _stepStream             (int direction);
69
    virtual void    _cameraTimeout          ();
Gus Grubba's avatar
Gus Grubba committed
70 71 72 73
    virtual void    _triggerCamera          ();
    virtual void    _startVideoRecording    ();
    virtual void    _stopVideoRecording     ();
    virtual void    _toggleVideoRecording   ();
Gus Grubba's avatar
Gus Grubba committed
74 75

protected:
Gus Grubba's avatar
Gus Grubba committed
76 77 78 79 80 81 82 83 84
    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);
85 86
    virtual void    _handleVideoStreamInfo  (const mavlink_message_t& message);
    virtual void    _handleVideoStreamStatus(const mavlink_message_t& message);
87
    virtual void    _handleBatteryStatus    (const mavlink_message_t& message);
88

Gus Grubba's avatar
Gus Grubba committed
89
protected:
90 91 92

    class CameraStruct : public QObject {
    public:
93
        CameraStruct(QObject* parent, uint8_t compID_);
94
        QElapsedTimer lastHeartbeat;
95 96 97
        bool    infoReceived = false;
        bool    gaveUp       = false;
        int     tryCount     = 0;
98
        uint8_t compID       = 0;
99 100
    };

101 102 103 104
    Vehicle*            _vehicle            = nullptr;
    Joystick*           _activeJoystick     = nullptr;
    bool                _vehicleReadyState  = false;
    int                 _currentTask        = 0;
105
    QmlObjectListModel  _cameras;
Gus Grubba's avatar
Gus Grubba committed
106
    QStringList         _cameraLabels;
107
    int                 _currentCamera      = 0;
108 109
    QElapsedTimer       _lastZoomChange;
    QElapsedTimer       _lastCameraChange;
110
    QTimer              _cameraTimer;
111
    QMap<QString, CameraStruct*> _cameraInfoRequest;
112
};