14 constexpr int kMaxRetries = 3;
23 qCDebug(QGCCameraParamIOLog) <<
this;
25 _paramWriteTimer.setSingleShot(
true);
26 _paramWriteTimer.setInterval(3000);
27 _paramRequestTimer.setSingleShot(
true);
28 _paramRequestTimer.setInterval(3500);
34 (void) connect(&_paramRequestTimer, &QTimer::timeout,
this, &QGCCameraParamIO::_paramRequestTimeout);
36 (void) connect(&_paramWriteTimer, &QTimer::timeout,
this, &QGCCameraParamIO::_paramWriteTimeout);
40 switch (_fact->
type()) {
43 _mavParamType = MAV_PARAM_EXT_TYPE_UINT8;
46 _mavParamType = MAV_PARAM_EXT_TYPE_INT8;
49 _mavParamType = MAV_PARAM_EXT_TYPE_UINT16;
52 _mavParamType = MAV_PARAM_EXT_TYPE_INT16;
55 _mavParamType = MAV_PARAM_EXT_TYPE_UINT32;
58 _mavParamType = MAV_PARAM_EXT_TYPE_UINT64;
61 _mavParamType = MAV_PARAM_EXT_TYPE_INT64;
64 _mavParamType = MAV_PARAM_EXT_TYPE_REAL32;
67 _mavParamType = MAV_PARAM_EXT_TYPE_REAL64;
72 _mavParamType = MAV_PARAM_EXT_TYPE_CUSTOM;
75 qCWarning(QGCCameraParamIOLog) <<
"Unsupported fact type" << _fact->
type() <<
"for" << _fact->
name();
78 _mavParamType = MAV_PARAM_EXT_TYPE_INT32;
85 qCDebug(QGCCameraParamIOLog) <<
this;
88void QGCCameraParamIO::_paramRequestTimeout()
90 if (++_requestRetries > kMaxRetries) {
91 qCWarning(QGCCameraParamIOLog) <<
"No response for param request:" << _fact->
name();
98 qCDebug(QGCCameraParamIOLog) <<
"Param request retry:" << _fact->
name();
100 _paramRequestTimer.start();
104void QGCCameraParamIO::_paramWriteTimeout()
106 if (++_sentRetries > kMaxRetries) {
107 qCWarning(QGCCameraParamIOLog) <<
"No response for param set:" << _fact->
name();
108 _updateOnSet =
false;
111 qCDebug(QGCCameraParamIOLog) <<
"Param set retry:" << _fact->
name() << _sentRetries;
113 _paramWriteTimer.start();
117void QGCCameraParamIO::_factChanged(
const QVariant &value)
121 if (!_forceUIUpdate) {
122 qCDebug(QGCCameraParamIOLog) <<
"UI Fact" << _fact->
name() <<
"changed to" << value;
127void QGCCameraParamIO::_containerRawValueChanged(
const QVariant &value)
132 qCDebug(QGCCameraParamIOLog) <<
"Update Fact from camera" << _fact->
name();
138void QGCCameraParamIO::_sendParameter()
142 mavlink_param_ext_set_t p{};
143 p.param_type = _mavParamType;
145 QGCMAVLink::param_ext_union_t union_value{};
151 union_value.param_uint8 =
static_cast<uint8_t
>(_fact->
rawValue().toUInt(&ok));
154 union_value.param_int8 =
static_cast<int8_t
>(_fact->
rawValue().toInt(&ok));
157 union_value.param_uint16 =
static_cast<uint16_t
>(_fact->
rawValue().toUInt(&ok));
160 union_value.param_int16 =
static_cast<int16_t
>(_fact->
rawValue().toInt(&ok));
163 union_value.param_uint32 =
static_cast<uint32_t
>(_fact->
rawValue().toUInt(&ok));
166 union_value.param_int64 =
static_cast<int64_t
>(_fact->
rawValue().toLongLong(&ok));
169 union_value.param_uint64 =
static_cast<uint64_t
>(_fact->
rawValue().toULongLong(&ok));
172 union_value.param_float = _fact->
rawValue().toFloat(&ok);
175 union_value.param_double = _fact->
rawValue().toDouble(&ok);
180 const QByteArray custom = _fact->
rawValue().toByteArray();
185 qCCritical(QGCCameraParamIOLog) <<
"Unsupported fact type" << factType <<
"for" << _fact->
name();
188 union_value.param_int32 =
static_cast<int32_t
>(_fact->
rawValue().toInt(&ok));
193 qCCritical(QGCCameraParamIOLog) <<
"Invalid value for" << _fact->
name() <<
":" << _fact->
rawValue();
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);
202 (void) mavlink_msg_param_ext_set_encode_chan(
205 sharedLink->mavlinkChannel(),
212 _paramWriteTimer.start();
217 _paramWriteTimer.stop();
219 switch (ack.param_result) {
220 case PARAM_ACK_ACCEPTED: {
221 QVariant val = _valueFromMessage(ack.param_value, ack.param_type);
225 _updateOnSet =
false;
231 case PARAM_ACK_IN_PROGRESS:
233 qCDebug(QGCCameraParamIOLog) <<
"Param set in progress:" << _fact->
name();
234 _paramWriteTimer.start();
236 case PARAM_ACK_FAILED:
237 if (++_sentRetries < kMaxRetries) {
239 qCWarning(QGCCameraParamIOLog) <<
"Param set failed:" << _fact->
name() << _sentRetries;
240 _paramWriteTimer.start();
243 case PARAM_ACK_VALUE_UNSUPPORTED:
244 qCWarning(QGCCameraParamIOLog) <<
"Param set unsuported:" << _fact->
name();
248 QVariant val = _valueFromMessage(ack.param_value, ack.param_type);
259QVariant QGCCameraParamIO::_valueFromMessage(
const char *value, uint8_t param_type)
262 QGCMAVLink::param_ext_union_t u{};
264 switch (param_type) {
265 case MAV_PARAM_EXT_TYPE_REAL32:
266 var = QVariant(u.param_float);
268 case MAV_PARAM_EXT_TYPE_UINT8:
269 var = QVariant(u.param_uint8);
271 case MAV_PARAM_EXT_TYPE_INT8:
272 var = QVariant(u.param_int8);
274 case MAV_PARAM_EXT_TYPE_UINT16:
275 var = QVariant(u.param_uint16);
277 case MAV_PARAM_EXT_TYPE_INT16:
278 var = QVariant(u.param_int16);
280 case MAV_PARAM_EXT_TYPE_UINT32:
281 var = QVariant(u.param_uint32);
283 case MAV_PARAM_EXT_TYPE_INT32:
284 var = QVariant(u.param_int32);
286 case MAV_PARAM_EXT_TYPE_UINT64:
287 var = QVariant(
static_cast<quint64
>(u.param_uint64));
289 case MAV_PARAM_EXT_TYPE_INT64:
290 var = QVariant(
static_cast<qint64
>(u.param_int64));
292 case MAV_PARAM_EXT_TYPE_CUSTOM: {
296 const QString strValue(strValueWithNull);
297 var = QVariant(strValue);
302 qCCritical(QGCCameraParamIOLog) <<
"Invalid param_type used for camera setting:" << param_type;
311 _paramRequestTimer.stop();
313 QVariant newValue = _valueFromMessage(value.param_value, value.param_type);
318 _paramRequestReceived =
true;
320 if (_forceUIUpdate) {
323 _forceUIUpdate =
false;
331 qCDebug(QGCCameraParamIOLog) << QStringLiteral(
"handleParamValue() %1 %2").arg(_fact->
name(), _fact->
rawValueString());
347 _forceUIUpdate =
true;
350 qCDebug(QGCCameraParamIOLog) <<
"Request parameter:" << _fact->
name();
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);
356 (void) mavlink_msg_param_ext_request_read_pack_chan(
359 sharedLink->mavlinkChannel(),
361 static_cast<uint8_t
>(_vehicle->
id()),
362 static_cast<uint8_t
>(_control->
compID()),
368 _paramRequestTimer.start();
373 qCDebug(QGCCameraParamIOLog) <<
"Send Fact" << _fact->
name();
375 _updateOnSet = updateUI;
382 _paramRequestReceived =
false;
384 _paramRequestTimer.start();
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.
void containerSetRawValue(const QVariant &value)
Value coming from Vehicle. This does NOT send a _containerRawValueChanged signal.
void rawValueChanged(const QVariant &value)
FactMetaData::ValueType_t type() const
QString rawValueString() const
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.
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()
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.
virtual void _paramDone()=0
Camera parameter handler.
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()
bool sendMessageOnLinkThreadSafe(LinkInterface *link, mavlink_message_t message)