QGCCameraIO.h 1.49 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
/*!
 * @file
 *   @brief Camera Controller
 *   @author Gus Grubba <mavlink@grubba.com>
 *
 */

#pragma once

#include "QGCApplication.h"
#include <QLoggingCategory>

class QGCCameraControl;

Q_DECLARE_LOGGING_CATEGORY(CameraIOLog)
Q_DECLARE_LOGGING_CATEGORY(CameraIOLogVerbose)

//-----------------------------------------------------------------------------
class QGCCameraParamIO : public QObject
{
public:
    QGCCameraParamIO(QGCCameraControl* control, Fact* fact, Vehicle* vehicle);

    void        handleParamAck          (const mavlink_param_ext_ack_t& ack);
    void        handleParamValue        (const mavlink_param_ext_value_t& value);
    void        setParamRequest         ();

private slots:
    void                _factChanged        (QVariant value);
Gus Grubba's avatar
Gus Grubba committed
30
    void                _containerRawValueChanged(const QVariant value);
31 32 33 34 35 36 37 38 39 40 41 42 43 44 45 46 47 48 49 50
    void                _paramWriteTimeout  ();
    void                _paramRequestTimeout();

private:
    void                _sendParameter      ();
    QVariant            _valueFromMessage   (const char* value, uint8_t param_type);
    MAV_PARAM_TYPE      _factTypeToMavType  (FactMetaData::ValueType_t factType);

private:
    QGCCameraControl*   _control;
    Fact*               _fact;
    Vehicle*            _vehicle;
    int                 _sentRetries;
    int                 _requestRetries;
    bool                _paramRequestReceived;
    mavlink_message_t   _msg;
    QTimer              _paramWriteTimer;
    QTimer              _paramRequestTimer;
};