QGCCameraIO.h 2.43 KB
Newer Older
1 2 3
/*!
 * @file
 *   @brief Camera Controller
Gus Grubba's avatar
Gus Grubba committed
4
 *   @author Gus Grubba <gus@auterion.com>
5 6 7
 *
 */

Gus Grubba's avatar
Gus Grubba committed
8 9 10 11
/// @file
/// @brief  MAVLink Camera API. Camera parameter handler.
/// @author Gus Grubba <gus@auterion.com>

12 13 14 15 16 17 18 19 20 21
#pragma once

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

class QGCCameraControl;

Q_DECLARE_LOGGING_CATEGORY(CameraIOLog)
Q_DECLARE_LOGGING_CATEGORY(CameraIOLogVerbose)

22 23 24 25
MAVPACKED(
typedef struct {
    union {
        float       param_float;
26 27 28
        double      param_double;
        int64_t     param_int64;
        uint64_t    param_uint64;
29 30 31 32 33 34 35 36 37 38 39
        int32_t     param_int32;
        uint32_t    param_uint32;
        int16_t     param_int16;
        uint16_t    param_uint16;
        int8_t      param_int8;
        uint8_t     param_uint8;
        uint8_t     bytes[MAVLINK_MSG_PARAM_EXT_SET_FIELD_PARAM_VALUE_LEN];
    };
    uint8_t type;
}) param_ext_union_t;

40
//-----------------------------------------------------------------------------
Gus Grubba's avatar
Gus Grubba committed
41
/// Camera parameter handler.
42 43 44 45 46
class QGCCameraParamIO : public QObject
{
public:
    QGCCameraParamIO(QGCCameraControl* control, Fact* fact, Vehicle* vehicle);

47 48 49 50
    void        handleParamAck              (const mavlink_param_ext_ack_t& ack);
    void        handleParamValue            (const mavlink_param_ext_value_t& value);
    void        setParamRequest             ();
    bool        paramDone                   () { return _done; }
51 52 53 54 55
    void        paramRequest                (bool reset = true);
    void        sendParameter               (bool updateUI = false);

    QStringList  optNames;
    QVariantList optVariants;
56 57

private slots:
58 59 60 61
    void        _paramWriteTimeout          ();
    void        _paramRequestTimeout        ();
    void        _factChanged                (QVariant value);
    void        _containerRawValueChanged   (const QVariant value);
62 63

private:
64 65
    void        _sendParameter              ();
    QVariant    _valueFromMessage           (const char* value, uint8_t param_type);
66 67 68 69 70 71 72 73 74 75

private:
    QGCCameraControl*   _control;
    Fact*               _fact;
    Vehicle*            _vehicle;
    int                 _sentRetries;
    int                 _requestRetries;
    bool                _paramRequestReceived;
    QTimer              _paramWriteTimer;
    QTimer              _paramRequestTimer;
76
    bool                _done;
77
    bool                _updateOnSet;
78
    MAV_PARAM_EXT_TYPE  _mavParamType;
79
    MAVLinkProtocol*    _pMavlink;
80
    bool                _forceUIUpdate;
81 82
};