QGCCameraManager.h 1.87 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 26 27 28 29 30 31 32 33 34 35 36 37 38 39 40 41 42 43 44 45 46 47 48 49 50 51 52 53 54 55 56 57 58 59 60
/*!
 * @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);
    ~QGCCameraManager();

    Q_PROPERTY(QmlObjectListModel*  cameras             READ cameras            NOTIFY camerasChanged)
    Q_PROPERTY(QString              controllerSource    READ controllerSource   NOTIFY controllerSourceChanged)

    //-- Return a list of cameras provided by this vehicle
    virtual QmlObjectListModel* cameras             () { return &_cameras; }
    //-- Camera controller source (QML)
    virtual QString             controllerSource    ();

private slots:
    void    _vehicleReady           (bool ready);
    void    _mavlinkMessageReceived (const mavlink_message_t& message);

signals:
    void    camerasChanged          ();
    void    controllerSourceChanged ();

private:
    QGCCameraControl* _findCamera   (int id);
    void    _requestCameraInfo      (int compID);
    void    _handleHeartbeat        (const mavlink_message_t& message);
    void    _handleCameraInfo       (const mavlink_message_t& message);
    void    _handleCameraSettings   (const mavlink_message_t& message);
    void    _handleParamAck         (const mavlink_message_t& message);
    void    _handleParamValue       (const mavlink_message_t& message);

private:
    Vehicle*            _vehicle;
    bool                _vehicleReadyState;
    int                 _cameraCount;
    int                 _currentTask;
    QmlObjectListModel  _cameras;
    QMap<int, bool>     _cameraInfoRequested;
};