QGCCameraManager.h 1.81 KB
Newer Older
1 2 3 4 5 6 7 8 9 10 11 12 13 14 15 16 17 18 19 20 21 22 23 24 25
/*!
 * @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)

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

Gus Grubba's avatar
Gus Grubba committed
28
    Q_PROPERTY(QmlObjectListModel*  cameras     READ cameras    NOTIFY camerasChanged)
29 30

    //-- Return a list of cameras provided by this vehicle
Gus Grubba's avatar
Gus Grubba committed
31
    virtual QmlObjectListModel* cameras     () { return &_cameras; }
32 33

signals:
Gus Grubba's avatar
Gus Grubba committed
34
    void    camerasChanged                  ();
35

Gus Grubba's avatar
Gus Grubba committed
36
protected slots:
Gus Grubba's avatar
Gus Grubba committed
37 38
    virtual void    _vehicleReady           (bool ready);
    virtual void    _mavlinkMessageReceived (const mavlink_message_t& message);
Gus Grubba's avatar
Gus Grubba committed
39 40

protected:
Gus Grubba's avatar
Gus Grubba committed
41 42 43 44 45 46 47 48 49
    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);
50

Gus Grubba's avatar
Gus Grubba committed
51
protected:
52 53 54 55 56 57
    Vehicle*            _vehicle;
    bool                _vehicleReadyState;
    int                 _currentTask;
    QmlObjectListModel  _cameras;
    QMap<int, bool>     _cameraInfoRequested;
};