QGCCameraManager.h 1.74 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 28 29 30 31 32 33 34 35

    Q_PROPERTY(QmlObjectListModel*  cameras             READ cameras            NOTIFY camerasChanged)

    //-- Return a list of cameras provided by this vehicle
    virtual QmlObjectListModel* cameras             () { return &_cameras; }

signals:
    void    camerasChanged          ();

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

protected:
41 42 43 44
    QGCCameraControl* _findCamera   (int id);
    void    _requestCameraInfo      (int compID);
    void    _handleHeartbeat        (const mavlink_message_t& message);
    void    _handleCameraInfo       (const mavlink_message_t& message);
Gus Grubba's avatar
Gus Grubba committed
45
    void    _handleStorageInfo      (const mavlink_message_t& message);
46 47 48
    void    _handleCameraSettings   (const mavlink_message_t& message);
    void    _handleParamAck         (const mavlink_message_t& message);
    void    _handleParamValue       (const mavlink_message_t& message);
Gus Grubba's avatar
Gus Grubba committed
49
    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;
};