QGroundControl
Ground Control Station for MAVLink Drones
Loading...
Searching...
No Matches
QGCCameraIO.cc
Go to the documentation of this file.
1#include "QGCCameraIO.h"
2#include "MAVLinkLib.h"
4#include "LinkInterface.h"
5#include "MAVLinkProtocol.h"
7#include "Vehicle.h"
9
10QGC_LOGGING_CATEGORY(QGCCameraParamIOLog, "Camera.QGCCameraParamIO")
11QGC_LOGGING_CATEGORY(QGCCameraParamIOVerbose, "Camera.QGCCameraParamIO:verbose")
12
13namespace {
14 constexpr int kMaxRetries = 3;
15}
16
18 : QObject(control)
19 , _control(control)
20 , _fact(fact)
21 , _vehicle(vehicle)
22{
23 qCDebug(QGCCameraParamIOLog) << this;
24
25 _paramWriteTimer.setSingleShot(true);
26 _paramWriteTimer.setInterval(3000);
27 _paramRequestTimer.setSingleShot(true);
28 _paramRequestTimer.setInterval(3500);
29
30 if (_fact->writeOnly()) {
31 // Write mode is always "done" as it won't ever read
32 _done = true;
33 } else {
34 (void) connect(&_paramRequestTimer, &QTimer::timeout, this, &QGCCameraParamIO::_paramRequestTimeout);
35 }
36 (void) connect(&_paramWriteTimer, &QTimer::timeout, this, &QGCCameraParamIO::_paramWriteTimeout);
37 (void) connect(_fact, &Fact::rawValueChanged, this, &QGCCameraParamIO::_factChanged);
38 (void) connect(_fact, &Fact::containerRawValueChanged, this, &QGCCameraParamIO::_containerRawValueChanged);
39
40 switch (_fact->type()) {
43 _mavParamType = MAV_PARAM_EXT_TYPE_UINT8;
44 break;
46 _mavParamType = MAV_PARAM_EXT_TYPE_INT8;
47 break;
49 _mavParamType = MAV_PARAM_EXT_TYPE_UINT16;
50 break;
52 _mavParamType = MAV_PARAM_EXT_TYPE_INT16;
53 break;
55 _mavParamType = MAV_PARAM_EXT_TYPE_UINT32;
56 break;
58 _mavParamType = MAV_PARAM_EXT_TYPE_UINT64;
59 break;
61 _mavParamType = MAV_PARAM_EXT_TYPE_INT64;
62 break;
64 _mavParamType = MAV_PARAM_EXT_TYPE_REAL32;
65 break;
67 _mavParamType = MAV_PARAM_EXT_TYPE_REAL64;
68 break;
69 // String and custom are the same for now
72 _mavParamType = MAV_PARAM_EXT_TYPE_CUSTOM;
73 break;
74 default:
75 qCWarning(QGCCameraParamIOLog) << "Unsupported fact type" << _fact->type() << "for" << _fact->name();
76 Q_FALLTHROUGH();
78 _mavParamType = MAV_PARAM_EXT_TYPE_INT32;
79 break;
80 }
81}
82
84{
85 qCDebug(QGCCameraParamIOLog) << this;
86}
87
88void QGCCameraParamIO::_paramRequestTimeout()
89{
90 if (++_requestRetries > kMaxRetries) {
91 qCWarning(QGCCameraParamIOLog) << "No response for param request:" << _fact->name();
92 if (!_done) {
93 _done = true;
94 _control->_paramDone();
95 }
96 } else {
97 // Request it again
98 qCDebug(QGCCameraParamIOLog) << "Param request retry:" << _fact->name();
99 paramRequest(false);
100 _paramRequestTimer.start();
101 }
102}
103
104void QGCCameraParamIO::_paramWriteTimeout()
105{
106 if (++_sentRetries > kMaxRetries) {
107 qCWarning(QGCCameraParamIOLog) << "No response for param set:" << _fact->name();
108 _updateOnSet = false;
109 } else {
110 // Send it again
111 qCDebug(QGCCameraParamIOLog) << "Param set retry:" << _fact->name() << _sentRetries;
112 _sendParameter();
113 _paramWriteTimer.start();
114 }
115}
116
117void QGCCameraParamIO::_factChanged(const QVariant &value)
118{
119 Q_UNUSED(value);
120
121 if (!_forceUIUpdate) {
122 qCDebug(QGCCameraParamIOLog) << "UI Fact" << _fact->name() << "changed to" << value;
123 _control->factChanged(_fact);
124 }
125}
126
127void QGCCameraParamIO::_containerRawValueChanged(const QVariant &value)
128{
129 Q_UNUSED(value);
130
131 if (!_fact->readOnly()) {
132 qCDebug(QGCCameraParamIOLog) << "Update Fact from camera" << _fact->name();
133 _sentRetries = 0;
134 _sendParameter();
135 }
136}
137
138void QGCCameraParamIO::_sendParameter()
139{
140 SharedLinkInterfacePtr sharedLink = _vehicle->vehicleLinkManager()->primaryLink().lock();
141 if (sharedLink) {
142 mavlink_param_ext_set_t p{};
143 p.param_type = _mavParamType;
144
145 QGCMAVLink::param_ext_union_t union_value{};
146 const FactMetaData::ValueType_t factType = _fact->type();
147 bool ok = true;
148 switch (factType) {
151 union_value.param_uint8 = static_cast<uint8_t>(_fact->rawValue().toUInt(&ok));
152 break;
154 union_value.param_int8 = static_cast<int8_t>(_fact->rawValue().toInt(&ok));
155 break;
157 union_value.param_uint16 = static_cast<uint16_t>(_fact->rawValue().toUInt(&ok));
158 break;
160 union_value.param_int16 = static_cast<int16_t>(_fact->rawValue().toInt(&ok));
161 break;
163 union_value.param_uint32 = static_cast<uint32_t>(_fact->rawValue().toUInt(&ok));
164 break;
166 union_value.param_int64 = static_cast<int64_t>(_fact->rawValue().toLongLong(&ok));
167 break;
169 union_value.param_uint64 = static_cast<uint64_t>(_fact->rawValue().toULongLong(&ok));
170 break;
172 union_value.param_float = _fact->rawValue().toFloat(&ok);
173 break;
175 union_value.param_double = _fact->rawValue().toDouble(&ok);
176 break;
177 // String and custom are the same for now
180 const QByteArray custom = _fact->rawValue().toByteArray();
181 (void) memcpy(union_value.bytes, custom.constData(), static_cast<size_t>(std::max(custom.size(), static_cast<qsizetype>(MAVLINK_MSG_PARAM_EXT_SET_FIELD_PARAM_VALUE_LEN))));
182 break;
183 }
184 default:
185 qCCritical(QGCCameraParamIOLog) << "Unsupported fact type" << factType << "for" << _fact->name();
186 Q_FALLTHROUGH();
188 union_value.param_int32 = static_cast<int32_t>(_fact->rawValue().toInt(&ok));
189 break;
190 }
191
192 if (!ok) {
193 qCCritical(QGCCameraParamIOLog) << "Invalid value for" << _fact->name() << ":" << _fact->rawValue();
194 }
195
196 (void) memcpy(&p.param_value[0], &union_value.bytes[0], MAVLINK_MSG_PARAM_EXT_SET_FIELD_PARAM_VALUE_LEN);
197 p.target_system = static_cast<uint8_t>(_vehicle->id());
198 p.target_component = static_cast<uint8_t>(_control->compID());
199 (void) qstrncpy(p.param_id, _fact->name().toStdString().c_str(), MAVLINK_MSG_PARAM_EXT_SET_FIELD_PARAM_ID_LEN);
200
201 mavlink_message_t msg{};
202 (void) mavlink_msg_param_ext_set_encode_chan(
203 static_cast<uint8_t>(MAVLinkProtocol::instance()->getSystemId()),
204 static_cast<uint8_t>(MAVLinkProtocol::getComponentId()),
205 sharedLink->mavlinkChannel(),
206 &msg,
207 &p
208 );
209 (void) _vehicle->sendMessageOnLinkThreadSafe(sharedLink.get(), msg);
210 }
211
212 _paramWriteTimer.start();
213}
214
215void QGCCameraParamIO::handleParamAck(const mavlink_param_ext_ack_t &ack)
216{
217 _paramWriteTimer.stop();
218
219 switch (ack.param_result) {
220 case PARAM_ACK_ACCEPTED: {
221 QVariant val = _valueFromMessage(ack.param_value, ack.param_type);
222 if (_fact->rawValue() != val) {
223 _fact->containerSetRawValue(val);
224 if(_updateOnSet) {
225 _updateOnSet = false;
226 _control->factChanged(_fact);
227 }
228 }
229 break;
230 }
231 case PARAM_ACK_IN_PROGRESS:
232 // Wait a bit longer for this one
233 qCDebug(QGCCameraParamIOLog) << "Param set in progress:" << _fact->name();
234 _paramWriteTimer.start();
235 break;
236 case PARAM_ACK_FAILED:
237 if (++_sentRetries < kMaxRetries) {
238 // Try again
239 qCWarning(QGCCameraParamIOLog) << "Param set failed:" << _fact->name() << _sentRetries;
240 _paramWriteTimer.start();
241 }
242 break;
243 case PARAM_ACK_VALUE_UNSUPPORTED:
244 qCWarning(QGCCameraParamIOLog) << "Param set unsuported:" << _fact->name();
245 Q_FALLTHROUGH();
246 default: {
247 // If UI changed and value was not set, restore UI
248 QVariant val = _valueFromMessage(ack.param_value, ack.param_type);
249 if (_fact->rawValue() != val) {
250 if (_control->validateParameter(_fact, val)) {
251 _fact->containerSetRawValue(val);
252 }
253 }
254 break;
255 }
256 }
257}
258
259QVariant QGCCameraParamIO::_valueFromMessage(const char *value, uint8_t param_type)
260{
261 QVariant var;
262 QGCMAVLink::param_ext_union_t u{};
263 (void) memcpy(u.bytes, value, MAVLINK_MSG_PARAM_EXT_SET_FIELD_PARAM_VALUE_LEN);
264 switch (param_type) {
265 case MAV_PARAM_EXT_TYPE_REAL32:
266 var = QVariant(u.param_float);
267 break;
268 case MAV_PARAM_EXT_TYPE_UINT8:
269 var = QVariant(u.param_uint8);
270 break;
271 case MAV_PARAM_EXT_TYPE_INT8:
272 var = QVariant(u.param_int8);
273 break;
274 case MAV_PARAM_EXT_TYPE_UINT16:
275 var = QVariant(u.param_uint16);
276 break;
277 case MAV_PARAM_EXT_TYPE_INT16:
278 var = QVariant(u.param_int16);
279 break;
280 case MAV_PARAM_EXT_TYPE_UINT32:
281 var = QVariant(u.param_uint32);
282 break;
283 case MAV_PARAM_EXT_TYPE_INT32:
284 var = QVariant(u.param_int32);
285 break;
286 case MAV_PARAM_EXT_TYPE_UINT64:
287 var = QVariant(static_cast<quint64>(u.param_uint64));
288 break;
289 case MAV_PARAM_EXT_TYPE_INT64:
290 var = QVariant(static_cast<qint64>(u.param_int64));
291 break;
292 case MAV_PARAM_EXT_TYPE_CUSTOM: {
293 // This will null terminate the name string
294 char strValueWithNull[MAVLINK_MSG_PARAM_EXT_SET_FIELD_PARAM_VALUE_LEN + 1] = {};
295 (void) strncpy(strValueWithNull, value, MAVLINK_MSG_PARAM_EXT_SET_FIELD_PARAM_VALUE_LEN);
296 const QString strValue(strValueWithNull);
297 var = QVariant(strValue);
298 break;
299 }
300 default:
301 var = QVariant(0);
302 qCCritical(QGCCameraParamIOLog) << "Invalid param_type used for camera setting:" << param_type;
303 break;
304 }
305
306 return var;
307}
308
309void QGCCameraParamIO::handleParamValue(const mavlink_param_ext_value_t &value)
310{
311 _paramRequestTimer.stop();
312
313 QVariant newValue = _valueFromMessage(value.param_value, value.param_type);
314 if (_control->incomingParameter(_fact, newValue)) {
315 _fact->containerSetRawValue(newValue);
316 _control->factChanged(_fact);
317 }
318 _paramRequestReceived = true;
319
320 if (_forceUIUpdate) {
321 emit _fact->rawValueChanged(_fact->rawValue());
322 emit _fact->valueChanged(_fact->rawValue());
323 _forceUIUpdate = false;
324 }
325
326 if (!_done) {
327 _done = true;
328 _control->_paramDone();
329 }
330
331 qCDebug(QGCCameraParamIOLog) << QStringLiteral("handleParamValue() %1 %2").arg(_fact->name(), _fact->rawValueString());
332}
333
335{
336 // If it's write only, we don't request it.
337 if (_fact->writeOnly()) {
338 if (!_done) {
339 _done = true;
340 _control->_paramDone();
341 }
342 return;
343 }
344
345 if (reset) {
346 _requestRetries = 0;
347 _forceUIUpdate = true;
348 }
349
350 qCDebug(QGCCameraParamIOLog) << "Request parameter:" << _fact->name();
351 SharedLinkInterfacePtr sharedLink = _vehicle->vehicleLinkManager()->primaryLink().lock();
352 if (sharedLink) {
353 char param_id[MAVLINK_MSG_PARAM_EXT_REQUEST_READ_FIELD_PARAM_ID_LEN + 1] = {};
354 (void) strncpy(param_id, _fact->name().toStdString().c_str(), MAVLINK_MSG_PARAM_EXT_REQUEST_READ_FIELD_PARAM_ID_LEN);
355 mavlink_message_t msg{};
356 (void) mavlink_msg_param_ext_request_read_pack_chan(
357 static_cast<uint8_t>(MAVLinkProtocol::instance()->getSystemId()),
358 static_cast<uint8_t>(MAVLinkProtocol::getComponentId()),
359 sharedLink->mavlinkChannel(),
360 &msg,
361 static_cast<uint8_t>(_vehicle->id()),
362 static_cast<uint8_t>(_control->compID()),
363 param_id,
364 -1
365 );
366 _vehicle->sendMessageOnLinkThreadSafe(sharedLink.get(), msg);
367 }
368 _paramRequestTimer.start();
369}
370
372{
373 qCDebug(QGCCameraParamIOLog) << "Send Fact" << _fact->name();
374 _sentRetries = 0;
375 _updateOnSet = updateUI;
376 _sendParameter();
377}
378
380{
381 if (!_fact->writeOnly()) {
382 _paramRequestReceived = false;
383 _requestRetries = 0;
384 _paramRequestTimer.start();
385 }
386}
std::shared_ptr< LinkInterface > SharedLinkInterfacePtr
struct __mavlink_message mavlink_message_t
#define QGC_LOGGING_CATEGORY(name, categoryStr)
#define MAVLINK_MSG_PARAM_EXT_SET_FIELD_PARAM_VALUE_LEN
A Fact is used to hold a single value within the system.
Definition Fact.h:17
bool writeOnly() const
Definition Fact.cc:838
void containerSetRawValue(const QVariant &value)
Value coming from Vehicle. This does NOT send a _containerRawValueChanged signal.
Definition Fact.cc:192
bool readOnly() const
Definition Fact.cc:828
void rawValueChanged(const QVariant &value)
FactMetaData::ValueType_t type() const
Definition Fact.h:124
QString rawValueString() const
Definition Fact.cc:433
QString name() const
Definition Fact.h:121
void containerRawValueChanged(const QVariant &value)
This signal is meant for use by Fact container implementations. Used to send changed values to vehicl...
QVariant rawValue() const
Value after translation.
Definition Fact.h:85
void valueChanged(const QVariant &value)
This signal is only meant for use by the QT property system. It should not be connected to by client ...
static int getComponentId()
static MAVLinkProtocol * instance()
int getSystemId() const
Abstract base class for all camera controls: real and simulated.
virtual void factChanged(Fact *pFact)=0
Notify controller a parameter has changed.
virtual bool incomingParameter(Fact *pFact, QVariant &newValue)=0
Allow controller to modify or invalidate incoming parameter.
virtual int compID() const =0
virtual bool validateParameter(Fact *pFact, QVariant &newValue)=0
Allow controller to modify or invalidate parameter change.
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)
QGCCameraParamIO(MavlinkCameraControlInterface *control, Fact *fact, Vehicle *vehicle)
WeakLinkInterfacePtr primaryLink() const
VehicleLinkManager * vehicleLinkManager()
Definition Vehicle.h:575
int id() const
Definition Vehicle.h:425
bool sendMessageOnLinkThreadSafe(LinkInterface *link, mavlink_message_t message)
Definition Vehicle.cc:1389