/*! * @file * @brief Camera Controller * @author Gus Grubba * */ #pragma once #include "QGCApplication.h" #include #include "QmlObjectListModel.h" #include "QGCCameraControl.h" #include #include 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 _cameraInfoRequested; };