QGroundControl
Ground Control Station for MAVLink Drones
Loading...
Searching...
No Matches
QGCCameraIO.h
Go to the documentation of this file.
1#pragma once
2
3#include <QtCore/QLoggingCategory>
4#include <QtCore/QTimer>
5
6#include "MAVLinkLib.h"
7
9class Fact;
10class Vehicle;
11
13Q_DECLARE_LOGGING_CATEGORY(CameraIOLogVerbose)
14
15
16class QGCCameraParamIO : public QObject
17{
18public:
19 QGCCameraParamIO(MavlinkCameraControl *control, Fact *fact, Vehicle *vehicle);
21
22 void handleParamAck(const mavlink_param_ext_ack_t &ack);
23 void handleParamValue(const mavlink_param_ext_value_t &value);
24 void setParamRequest();
25 bool paramDone() const { return _done; }
26 void paramRequest(bool reset = true);
27 void sendParameter(bool updateUI = false);
28
29private slots:
30 void _paramWriteTimeout();
31 void _paramRequestTimeout();
32 void _factChanged(const QVariant &value);
33 void _containerRawValueChanged(const QVariant &value);
34
35private:
36 void _sendParameter();
37 QVariant _valueFromMessage(const char *value, uint8_t param_type);
38
39 MavlinkCameraControl *_control = nullptr;
40 Fact *_fact = nullptr;
41 Vehicle *_vehicle = nullptr;
42
43 bool _done = false;
44 bool _forceUIUpdate = false;
45 bool _paramRequestReceived = false;
46 bool _updateOnSet = false;
47 int _requestRetries = 0;
48 int _sentRetries = 0;
49 MAV_PARAM_EXT_TYPE _mavParamType = MAV_PARAM_EXT_TYPE_UINT8;
50 QTimer _paramRequestTimer;
51 QTimer _paramWriteTimer;
52};
Q_DECLARE_LOGGING_CATEGORY(AndroidSerialLog)
A Fact is used to hold a single value within the system.
Definition Fact.h:19
Abstract base class for all camera controls: real and simulated.
Camera parameter handler.
Definition QGCCameraIO.h:17
bool paramDone() const
Definition QGCCameraIO.h:25