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
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
/*!
* @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)
MAVPACKED(
typedef struct {
union {
float param_float;
double param_double;
int64_t param_int64;
uint64_t param_uint64;
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;
//-----------------------------------------------------------------------------
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 ();
bool paramDone () { return _done; }
void paramRequest (bool reset = true);
void sendParameter (bool updateUI = false);
QStringList optNames;
QVariantList optVariants;
private slots:
void _paramWriteTimeout ();
void _paramRequestTimeout ();
void _factChanged (QVariant value);
void _containerRawValueChanged (const QVariant value);
private:
void _sendParameter ();
QVariant _valueFromMessage (const char* value, uint8_t param_type);
private:
QGCCameraControl* _control;
Fact* _fact;
Vehicle* _vehicle;
int _sentRetries;
int _requestRetries;
bool _paramRequestReceived;
QTimer _paramWriteTimer;
QTimer _paramRequestTimer;
bool _done;
bool _updateOnSet;
MAV_PARAM_EXT_TYPE _mavParamType;
MAVLinkProtocol* _pMavlink;
bool _forceUIUpdate;
};