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/QTimer>
4
5#include "MAVLinkLib.h"
6
8class Fact;
9class Vehicle;
10
13class QGCCameraParamIO : public QObject
14{
15public:
18
19 void handleParamAck(const mavlink_param_ext_ack_t &ack);
20 void handleParamValue(const mavlink_param_ext_value_t &value);
21 void setParamRequest();
22 bool paramDone() const { return _done; }
23 void paramRequest(bool reset = true);
24 void sendParameter(bool updateUI = false);
25
26private slots:
27 void _paramWriteTimeout();
28 void _paramRequestTimeout();
29 void _factChanged(const QVariant &value);
30 void _containerRawValueChanged(const QVariant &value);
31
32private:
33 void _sendParameter();
34 QVariant _valueFromMessage(const char *value, uint8_t param_type);
35
36 MavlinkCameraControlInterface *_control = nullptr;
37 Fact *_fact = nullptr;
38 Vehicle *_vehicle = nullptr;
39
40 bool _done = false;
41 bool _forceUIUpdate = false;
42 bool _paramRequestReceived = false;
43 bool _updateOnSet = false;
44 int _requestRetries = 0;
45 int _sentRetries = 0;
46 MAV_PARAM_EXT_TYPE _mavParamType = MAV_PARAM_EXT_TYPE_UINT8;
47 QTimer _paramRequestTimer;
48 QTimer _paramWriteTimer;
49};
A Fact is used to hold a single value within the system.
Definition Fact.h:17
Abstract base class for all camera controls: real and simulated.
Camera parameter handler.
Definition QGCCameraIO.h:14
void handleParamAck(const mavlink_param_ext_ack_t &ack)
void sendParameter(bool updateUI=false)
void handleParamValue(const mavlink_param_ext_value_t &value)
void paramRequest(bool reset=true)
bool paramDone() const
Definition QGCCameraIO.h:22