Commit 357d73bc authored by Gus Grubba's avatar Gus Grubba

Add "write only" (extended) parameter attribute.

Move  MAV_PARAM_TYPE to  MAV_PARAM_EXT_TYPE as we're now using the proper MAVLink version.
parent e945aa15
......@@ -40,6 +40,7 @@ static const char* kParameterrange = "parameterrange";
static const char* kParameterranges = "parameterranges";
static const char* kParameters = "parameters";
static const char* kReadOnly = "readonly";
static const char* kWriteOnly = "writeonly";
static const char* kRoption = "roption";
static const char* kStep = "step";
static const char* kStrings = "strings";
......@@ -659,6 +660,13 @@ QGCCameraControl::_loadSettings(const QDomNodeList nodeList)
//-- Is it read only?
bool readOnly = false;
read_attribute(parameterNode, kReadOnly, readOnly);
//-- Is it write only?
bool writeOnly = false;
read_attribute(parameterNode, kWriteOnly, writeOnly);
//-- It can't be both
if(readOnly && writeOnly) {
qCritical() << QString("Parameter %1 cannot be both read only and write only").arg(factName);
}
//-- Param type
bool unknownType;
FactMetaData::ValueType_t factType = FactMetaData::stringToType(type, unknownType);
......@@ -689,6 +697,7 @@ QGCCameraControl::_loadSettings(const QDomNodeList nodeList)
metaData->setLongDescription(description);
metaData->setHasControl(control);
metaData->setReadOnly(readOnly);
metaData->setWriteOnly(writeOnly);
//-- Options (enums)
QDomElement optionElem = parameterNode.toElement();
QDomNodeList optionsRoot = optionElem.elementsByTagName(kOptions);
......
......@@ -38,31 +38,31 @@ QGCCameraParamIO::QGCCameraParamIO(QGCCameraControl *control, Fact* fact, Vehicl
switch (_fact->type()) {
case FactMetaData::valueTypeUint8:
case FactMetaData::valueTypeBool:
_mavParamType = MAV_PARAM_TYPE_UINT8;
_mavParamType = MAV_PARAM_EXT_TYPE_UINT8;
break;
case FactMetaData::valueTypeInt8:
_mavParamType = MAV_PARAM_TYPE_INT8;
_mavParamType = MAV_PARAM_EXT_TYPE_INT8;
break;
case FactMetaData::valueTypeUint16:
_mavParamType = MAV_PARAM_TYPE_UINT16;
_mavParamType = MAV_PARAM_EXT_TYPE_UINT16;
break;
case FactMetaData::valueTypeInt16:
_mavParamType = MAV_PARAM_TYPE_INT16;
_mavParamType = MAV_PARAM_EXT_TYPE_INT16;
break;
case FactMetaData::valueTypeUint32:
_mavParamType = MAV_PARAM_TYPE_UINT32;
_mavParamType = MAV_PARAM_EXT_TYPE_UINT32;
break;
case FactMetaData::valueTypeFloat:
_mavParamType = MAV_PARAM_TYPE_REAL32;
_mavParamType = MAV_PARAM_EXT_TYPE_REAL32;
break;
case FactMetaData::valueTypeCustom:
_mavParamType = (MAV_PARAM_TYPE)11; // MAV_PARAM_TYPE_CUSTOM;
_mavParamType = MAV_PARAM_EXT_TYPE_CUSTOM;
break;
default:
qWarning() << "Unsupported fact type" << _fact->type() << "for" << _fact->name();
// Fall through
case FactMetaData::valueTypeInt32:
_mavParamType = MAV_PARAM_TYPE_INT32;
_mavParamType = MAV_PARAM_EXT_TYPE_INT32;
break;
}
}
......@@ -250,28 +250,28 @@ QGCCameraParamIO::_valueFromMessage(const char* value, uint8_t param_type)
param_ext_union_t u;
memcpy(u.bytes, value, MAVLINK_MSG_PARAM_EXT_SET_FIELD_PARAM_VALUE_LEN);
switch (param_type) {
case MAV_PARAM_TYPE_REAL32:
case MAV_PARAM_EXT_TYPE_REAL32:
var = QVariant(u.param_float);
break;
case MAV_PARAM_TYPE_UINT8:
case MAV_PARAM_EXT_TYPE_UINT8:
var = QVariant(u.param_uint8);
break;
case MAV_PARAM_TYPE_INT8:
case MAV_PARAM_EXT_TYPE_INT8:
var = QVariant(u.param_int8);
break;
case MAV_PARAM_TYPE_UINT16:
case MAV_PARAM_EXT_TYPE_UINT16:
var = QVariant(u.param_uint16);
break;
case MAV_PARAM_TYPE_INT16:
case MAV_PARAM_EXT_TYPE_INT16:
var = QVariant(u.param_int16);
break;
case MAV_PARAM_TYPE_UINT32:
case MAV_PARAM_EXT_TYPE_UINT32:
var = QVariant(u.param_uint32);
break;
case MAV_PARAM_TYPE_INT32:
case MAV_PARAM_EXT_TYPE_INT32:
var = QVariant(u.param_int32);
break;
case 11: //MAV_PARAM_TYPE_CUSTOM:
case MAV_PARAM_EXT_TYPE_CUSTOM:
var = QVariant(QByteArray(value, MAVLINK_MSG_PARAM_EXT_SET_FIELD_PARAM_VALUE_LEN));
break;
default:
......@@ -303,6 +303,14 @@ QGCCameraParamIO::_paramRequestTimeout()
void
QGCCameraParamIO::paramRequest(bool reset)
{
//-- If it's write only, we don't request it.
if(_fact->writeOnly()) {
if(!_done) {
_done = true;
_control->_paramDone();
}
return;
}
if(reset) {
_requestRetries = 0;
_forceUIUpdate = true;
......
......@@ -67,7 +67,7 @@ private:
QTimer _paramRequestTimer;
bool _done;
bool _updateOnSet;
MAV_PARAM_TYPE _mavParamType;
MAV_PARAM_EXT_TYPE _mavParamType;
MAVLinkProtocol* _pMavlink;
bool _forceUIUpdate;
};
......
......@@ -663,6 +663,16 @@ bool Fact::readOnly(void) const
}
}
bool Fact::writeOnly(void) const
{
if (_metaData) {
return _metaData->writeOnly();
} else {
qWarning() << kMissingMetadata << name();
return false;
}
}
bool Fact::volatileValue(void) const
{
if (_metaData) {
......
......@@ -71,6 +71,7 @@ public:
Q_PROPERTY(bool typeIsBool READ typeIsBool CONSTANT)
Q_PROPERTY(bool hasControl READ hasControl CONSTANT)
Q_PROPERTY(bool readOnly READ readOnly CONSTANT)
Q_PROPERTY(bool writeOnly READ writeOnly CONSTANT)
Q_PROPERTY(bool volatileValue READ volatileValue CONSTANT)
/// Convert and validate value
......@@ -119,7 +120,8 @@ public:
bool typeIsBool (void) const { return type() == FactMetaData::valueTypeBool; }
bool hasControl (void) const;
bool readOnly (void) const;
bool volatileValue (void) const;
bool writeOnly (void) const;
bool volatileValue (void) const;
/// Returns the values as a string with full 18 digit precision if float/double.
QString rawValueStringFullPrecision(void) const;
......
......@@ -94,6 +94,7 @@ FactMetaData::FactMetaData(QObject* parent)
, _increment (std::numeric_limits<double>::quiet_NaN())
, _hasControl (true)
, _readOnly (false)
, _writeOnly (false)
, _volatile (false)
{
_category = kDefaultCategory;
......@@ -116,6 +117,7 @@ FactMetaData::FactMetaData(ValueType_t type, QObject* parent)
, _increment (std::numeric_limits<double>::quiet_NaN())
, _hasControl (true)
, _readOnly (false)
, _writeOnly (false)
, _volatile (false)
{
_category = kDefaultCategory;
......@@ -145,6 +147,7 @@ FactMetaData::FactMetaData(ValueType_t type, const QString name, QObject* parent
, _increment (std::numeric_limits<double>::quiet_NaN())
, _hasControl (true)
, _readOnly (false)
, _writeOnly (false)
, _volatile (false)
{
_category = kDefaultCategory;
......@@ -178,6 +181,7 @@ const FactMetaData& FactMetaData::operator=(const FactMetaData& other)
_increment = other._increment;
_hasControl = other._hasControl;
_readOnly = other._readOnly;
_writeOnly = other._writeOnly;
_volatile = other._volatile;
return *this;
}
......
......@@ -104,6 +104,7 @@ public:
bool rebootRequired (void) const { return _rebootRequired; }
bool hasControl (void) const { return _hasControl; }
bool readOnly (void) const { return _readOnly; }
bool writeOnly (void) const { return _writeOnly; }
bool volatileValue (void) const { return _volatile; }
/// Amount to increment value when used in controls such as spin button or slider with detents.
......@@ -135,6 +136,7 @@ public:
void setIncrement (double increment) { _increment = increment; }
void setHasControl (bool bValue) { _hasControl = bValue; }
void setReadOnly (bool bValue) { _readOnly = bValue; }
void setWriteOnly (bool bValue) { _writeOnly = bValue; }
void setVolatileValue (bool bValue);
void setTranslators(Translator rawTranslator, Translator cookedTranslator);
......@@ -241,6 +243,7 @@ private:
double _increment;
bool _hasControl;
bool _readOnly;
bool _writeOnly;
bool _volatile;
// Exact conversion constants
......
Markdown is supported
0% or
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment