QGCCameraManager.h 2.94 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

Gus Grubba's avatar
Gus Grubba committed
30 31 32
    Q_PROPERTY(QmlObjectListModel*  cameras             READ cameras            NOTIFY camerasChanged)
    Q_PROPERTY(QStringList          cameraLabels        READ cameraLabels       NOTIFY cameraLabelsChanged)
    Q_PROPERTY(int                  currentCamera       READ currentCamera      WRITE  setCurrentCamera     NOTIFY currentCameraChanged)
33 34

    //-- Return a list of cameras provided by this vehicle
Gus Grubba's avatar
Gus Grubba committed
35 36 37 38 39 40 41
    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; }
    //-- Set current camera
    virtual void                setCurrentCamera    (int sel);
42 43

signals:
Gus Grubba's avatar
Gus Grubba committed
44 45 46
    void    camerasChanged          ();
    void    cameraLabelsChanged     ();
    void    currentCameraChanged    ();
47

Gus Grubba's avatar
Gus Grubba committed
48
protected slots:
Gus Grubba's avatar
Gus Grubba committed
49 50
    virtual void    _vehicleReady           (bool ready);
    virtual void    _mavlinkMessageReceived (const mavlink_message_t& message);
51 52 53
    virtual void    _activeJoystickChanged  (Joystick* joystick);
    virtual void    _stepZoom               (int direction);
    virtual void    _stepCamera             (int direction);
Gus Grubba's avatar
Gus Grubba committed
54 55

protected:
Gus Grubba's avatar
Gus Grubba committed
56 57 58 59 60 61 62 63 64
    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);
65

Gus Grubba's avatar
Gus Grubba committed
66
protected:
67 68 69 70
    Vehicle*            _vehicle            = nullptr;
    Joystick*           _activeJoystick     = nullptr;
    bool                _vehicleReadyState  = false;
    int                 _currentTask        = 0;
71
    QmlObjectListModel  _cameras;
Gus Grubba's avatar
Gus Grubba committed
72
    QStringList         _cameraLabels;
73
    QMap<int, bool>     _cameraInfoRequested;
74 75 76
    int                 _currentCamera      = 0;
    QTime               _lastZoomChange;
    QTime               _lastCameraChange;
77
};