Skip to content
GitLab
Projects
Groups
Snippets
/
Help
Help
Support
Community forum
Keyboard shortcuts
?
Submit feedback
Contribute to GitLab
Sign in
Toggle navigation
Menu
Open sidebar
Valentin Platzgummer
qgroundcontrol
Commits
8e1a3fd9
Commit
8e1a3fd9
authored
Apr 29, 2018
by
DonLakeFlyer
Browse files
Cleanup/Fixes for increment meta data usage
parent
512922c9
Changes
8
Show whitespace changes
Inline
Side-by-side
src/Camera/QGCCameraControl.cc
View file @
8e1a3fd9
...
...
@@ -790,7 +790,7 @@ QGCCameraControl::_loadSettings(const QDomNodeList nodeList)
QVariant
typedValue
;
QString
errorString
;
if
(
metaData
->
convertAndValidateRaw
(
attr
,
true
/* convertOnly */
,
typedValue
,
errorString
))
{
metaData
->
setIncrement
(
typedValue
.
toDouble
());
metaData
->
set
Raw
Increment
(
typedValue
.
toDouble
());
}
else
{
qWarning
()
<<
"Invalid step value for"
<<
factName
<<
" type:"
<<
metaData
->
type
()
...
...
src/FactSystem/Fact.cc
View file @
8e1a3fd9
...
...
@@ -8,6 +8,7 @@
****************************************************************************/
#include
"Fact.h"
#include
"FactValueSliderListModel.h"
#include
"QGCMAVLink.h"
#include
"QGCApplication.h"
#include
"QGCCorePlugin.h"
...
...
@@ -18,13 +19,14 @@
static
const
char
*
kMissingMetadata
=
"Meta data pointer missing"
;
Fact
::
Fact
(
QObject
*
parent
)
:
QObject
(
parent
)
,
_componentId
(
-
1
)
,
_rawValue
(
0
)
,
_type
(
FactMetaData
::
valueTypeInt32
)
,
_metaData
(
NULL
)
,
_sendValueChangedSignals
(
true
)
:
QObject
(
parent
)
,
_componentId
(
-
1
)
,
_rawValue
(
0
)
,
_type
(
FactMetaData
::
valueTypeInt32
)
,
_metaData
(
NULL
)
,
_sendValueChangedSignals
(
true
)
,
_deferredValueChangeSignal
(
false
)
,
_valueSliderModel
(
NULL
)
{
FactMetaData
*
metaData
=
new
FactMetaData
(
_type
,
this
);
setMetaData
(
metaData
);
...
...
@@ -34,14 +36,15 @@ Fact::Fact(QObject* parent)
}
Fact
::
Fact
(
int
componentId
,
QString
name
,
FactMetaData
::
ValueType_t
type
,
QObject
*
parent
)
:
QObject
(
parent
)
,
_name
(
name
)
,
_componentId
(
componentId
)
,
_rawValue
(
0
)
,
_type
(
type
)
,
_metaData
(
NULL
)
,
_sendValueChangedSignals
(
true
)
:
QObject
(
parent
)
,
_name
(
name
)
,
_componentId
(
componentId
)
,
_rawValue
(
0
)
,
_type
(
type
)
,
_metaData
(
NULL
)
,
_sendValueChangedSignals
(
true
)
,
_deferredValueChangeSignal
(
false
)
,
_valueSliderModel
(
NULL
)
{
FactMetaData
*
metaData
=
new
FactMetaData
(
_type
,
this
);
setMetaData
(
metaData
);
...
...
@@ -57,6 +60,7 @@ Fact::Fact(FactMetaData* metaData, QObject* parent)
,
_metaData
(
NULL
)
,
_sendValueChangedSignals
(
true
)
,
_deferredValueChangeSignal
(
false
)
,
_valueSliderModel
(
NULL
)
{
// Allow core plugin a chance to override the default value
qgcApp
()
->
toolbox
()
->
corePlugin
()
->
adjustSettingMetaData
(
*
metaData
);
...
...
@@ -78,7 +82,7 @@ const Fact& Fact::operator=(const Fact& other)
_type
=
other
.
_type
;
_sendValueChangedSignals
=
other
.
_sendValueChangedSignals
;
_deferredValueChangeSignal
=
other
.
_deferredValueChangeSignal
;
_valueSliderModel
=
NULL
;
if
(
_metaData
&&
other
.
_metaData
)
{
*
_metaData
=
*
other
.
_metaData
;
}
else
{
...
...
@@ -633,10 +637,10 @@ QString Fact::enumOrValueString(void)
return
QString
();
}
double
Fact
::
i
ncrement
(
void
)
const
double
Fact
::
rawI
ncrement
(
void
)
const
{
if
(
_metaData
)
{
return
_metaData
->
i
ncrement
();
return
_metaData
->
rawI
ncrement
();
}
else
{
qWarning
()
<<
kMissingMetadata
<<
name
();
}
...
...
@@ -692,3 +696,12 @@ bool Fact::volatileValue(void) const
return
false
;
}
}
FactValueSliderListModel
*
Fact
::
valueSliderModel
(
void
)
{
if
(
!
_valueSliderModel
)
{
_valueSliderModel
=
new
FactValueSliderListModel
(
*
this
);
QQmlEngine
::
setObjectOwnership
(
_valueSliderModel
,
QQmlEngine
::
JavaScriptOwnership
);
}
return
_valueSliderModel
;
}
src/FactSystem/Fact.h
View file @
8e1a3fd9
...
...
@@ -20,6 +20,9 @@
#include
<QString>
#include
<QVariant>
#include
<QDebug>
#include
<QAbstractListModel>
class
FactValueSliderListModel
;
/// @brief A Fact is used to hold a single value within the system.
class
Fact
:
public
QObject
...
...
@@ -115,7 +118,7 @@ public:
bool
valueEqualsDefault
(
void
)
const
;
bool
rebootRequired
(
void
)
const
;
QString
enumOrValueString
(
void
);
// This is not const, since an unknown value can modify the enum lists
double
i
ncrement
(
void
)
const
;
double
rawI
ncrement
(
void
)
const
;
double
cookedIncrement
(
void
)
const
;
bool
typeIsString
(
void
)
const
{
return
type
()
==
FactMetaData
::
valueTypeString
;
}
bool
typeIsBool
(
void
)
const
{
return
type
()
==
FactMetaData
::
valueTypeBool
;
}
...
...
@@ -124,6 +127,8 @@ public:
bool
writeOnly
(
void
)
const
;
bool
volatileValue
(
void
)
const
;
Q_INVOKABLE
FactValueSliderListModel
*
valueSliderModel
(
void
);
/// Returns the values as a string with full 18 digit precision if float/double.
QString
rawValueStringFullPrecision
(
void
)
const
;
...
...
@@ -193,6 +198,7 @@ protected:
FactMetaData
*
_metaData
;
bool
_sendValueChangedSignals
;
bool
_deferredValueChangeSignal
;
FactValueSliderListModel
*
_valueSliderModel
;
};
#endif
src/FactSystem/FactMetaData.cc
View file @
8e1a3fd9
...
...
@@ -78,6 +78,7 @@ const char* FactMetaData::_defaultValueJsonKey = "defaultValue";
const
char
*
FactMetaData
::
_mobileDefaultValueJsonKey
=
"mobileDefaultValue"
;
const
char
*
FactMetaData
::
_minJsonKey
=
"min"
;
const
char
*
FactMetaData
::
_maxJsonKey
=
"max"
;
const
char
*
FactMetaData
::
_incrementJsonKey
=
"increment"
;
const
char
*
FactMetaData
::
_hasControlJsonKey
=
"control"
;
FactMetaData
::
FactMetaData
(
QObject
*
parent
)
...
...
@@ -93,7 +94,7 @@ FactMetaData::FactMetaData(QObject* parent)
,
_rawTranslator
(
_defaultTranslator
)
,
_cookedTranslator
(
_defaultTranslator
)
,
_rebootRequired
(
false
)
,
_
i
ncrement
(
std
::
numeric_limits
<
double
>::
quiet_NaN
())
,
_
rawI
ncrement
(
std
::
numeric_limits
<
double
>::
quiet_NaN
())
,
_hasControl
(
true
)
,
_readOnly
(
false
)
,
_writeOnly
(
false
)
...
...
@@ -116,7 +117,7 @@ FactMetaData::FactMetaData(ValueType_t type, QObject* parent)
,
_rawTranslator
(
_defaultTranslator
)
,
_cookedTranslator
(
_defaultTranslator
)
,
_rebootRequired
(
false
)
,
_
i
ncrement
(
std
::
numeric_limits
<
double
>::
quiet_NaN
())
,
_
rawI
ncrement
(
std
::
numeric_limits
<
double
>::
quiet_NaN
())
,
_hasControl
(
true
)
,
_readOnly
(
false
)
,
_writeOnly
(
false
)
...
...
@@ -146,7 +147,7 @@ FactMetaData::FactMetaData(ValueType_t type, const QString name, QObject* parent
,
_rawTranslator
(
_defaultTranslator
)
,
_cookedTranslator
(
_defaultTranslator
)
,
_rebootRequired
(
false
)
,
_
i
ncrement
(
std
::
numeric_limits
<
double
>::
quiet_NaN
())
,
_
rawI
ncrement
(
std
::
numeric_limits
<
double
>::
quiet_NaN
())
,
_hasControl
(
true
)
,
_readOnly
(
false
)
,
_writeOnly
(
false
)
...
...
@@ -180,7 +181,7 @@ const FactMetaData& FactMetaData::operator=(const FactMetaData& other)
_rawTranslator
=
other
.
_rawTranslator
;
_cookedTranslator
=
other
.
_cookedTranslator
;
_rebootRequired
=
other
.
_rebootRequired
;
_
i
ncrement
=
other
.
_
i
ncrement
;
_
rawI
ncrement
=
other
.
_
rawI
ncrement
;
_hasControl
=
other
.
_hasControl
;
_readOnly
=
other
.
_readOnly
;
_writeOnly
=
other
.
_writeOnly
;
...
...
@@ -975,7 +976,7 @@ QString FactMetaData::appSettingsAreaUnitsString(void)
double
FactMetaData
::
cookedIncrement
(
void
)
const
{
return
_rawTranslator
(
this
->
i
ncrement
()).
toDouble
();
return
_rawTranslator
(
this
->
rawI
ncrement
()).
toDouble
();
}
int
FactMetaData
::
decimalPlaces
(
void
)
const
...
...
@@ -984,7 +985,7 @@ int FactMetaData::decimalPlaces(void) const
int
incrementDecimalPlaces
=
unknownDecimalPlaces
;
// First determine decimal places from increment
double
increment
=
_rawTranslator
(
this
->
i
ncrement
()).
toDouble
();
double
increment
=
_rawTranslator
(
this
->
rawI
ncrement
()).
toDouble
();
if
(
!
qIsNaN
(
increment
))
{
double
integralPart
;
...
...
@@ -1029,12 +1030,18 @@ FactMetaData* FactMetaData::createFromJsonObject(const QJsonObject& json, QObjec
return
new
FactMetaData
(
valueTypeUint32
,
metaDataParent
);
}
// Validate key types
QStringList
keys
;
QList
<
QJsonValue
::
Type
>
types
;
keys
<<
_nameJsonKey
<<
_decimalPlacesJsonKey
<<
_typeJsonKey
<<
_shortDescriptionJsonKey
<<
_longDescriptionJsonKey
<<
_unitsJsonKey
<<
_minJsonKey
<<
_maxJsonKey
<<
_hasControlJsonKey
;
types
<<
QJsonValue
::
String
<<
QJsonValue
::
Double
<<
QJsonValue
::
String
<<
QJsonValue
::
String
<<
QJsonValue
::
String
<<
QJsonValue
::
String
<<
QJsonValue
::
Double
<<
QJsonValue
::
Double
<<
QJsonValue
::
Bool
;
if
(
!
JsonHelper
::
validateKeyTypes
(
json
,
keys
,
types
,
errorString
))
{
QList
<
JsonHelper
::
KeyValidateInfo
>
keyInfoList
=
{
{
_nameJsonKey
,
QJsonValue
::
String
,
true
},
{
_typeJsonKey
,
QJsonValue
::
String
,
true
},
{
_shortDescriptionJsonKey
,
QJsonValue
::
String
,
false
},
{
_longDescriptionJsonKey
,
QJsonValue
::
String
,
false
},
{
_unitsJsonKey
,
QJsonValue
::
String
,
false
},
{
_decimalPlacesJsonKey
,
QJsonValue
::
Double
,
false
},
{
_minJsonKey
,
QJsonValue
::
Double
,
false
},
{
_maxJsonKey
,
QJsonValue
::
Double
,
false
},
{
_hasControlJsonKey
,
QJsonValue
::
Bool
,
false
},
};
if
(
!
JsonHelper
::
validateKeys
(
json
,
keyInfoList
,
errorString
))
{
qWarning
()
<<
errorString
;
return
new
FactMetaData
(
valueTypeUint32
,
metaDataParent
);
}
...
...
@@ -1100,6 +1107,20 @@ FactMetaData* FactMetaData::createFromJsonObject(const QJsonObject& json, QObjec
}
}
if
(
json
.
contains
(
_incrementJsonKey
))
{
QVariant
typedValue
;
QString
errorString
;
QVariant
initialValue
=
json
[
_incrementJsonKey
].
toVariant
();
if
(
metaData
->
convertAndValidateRaw
(
initialValue
,
true
/* convertOnly */
,
typedValue
,
errorString
))
{
metaData
->
setRawIncrement
(
typedValue
.
toDouble
());
}
else
{
qWarning
()
<<
"Invalid increment value, name:"
<<
metaData
->
name
()
<<
" type:"
<<
metaData
->
type
()
<<
" value:"
<<
initialValue
<<
" error:"
<<
errorString
;
}
}
if
(
json
.
contains
(
_minJsonKey
))
{
QVariant
typedValue
;
QString
errorString
;
...
...
src/FactSystem/FactMetaData.h
View file @
8e1a3fd9
...
...
@@ -111,7 +111,7 @@ public:
/// Amount to increment value when used in controls such as spin button or slider with detents.
/// NaN for no increment available.
double
i
ncrement
(
void
)
const
{
return
_
i
ncrement
;
}
double
rawI
ncrement
(
void
)
const
{
return
_
rawI
ncrement
;
}
double
cookedIncrement
(
void
)
const
;
Translator
rawTranslator
(
void
)
const
{
return
_rawTranslator
;
}
...
...
@@ -136,7 +136,7 @@ public:
void
setShortDescription
(
const
QString
&
shortDescription
)
{
_shortDescription
=
shortDescription
;
}
void
setRawUnits
(
const
QString
&
rawUnits
);
void
setRebootRequired
(
bool
rebootRequired
)
{
_rebootRequired
=
rebootRequired
;
}
void
setIncrement
(
double
increment
)
{
_
i
ncrement
=
increment
;
}
void
set
Raw
Increment
(
double
increment
)
{
_
rawI
ncrement
=
increment
;
}
void
setHasControl
(
bool
bValue
)
{
_hasControl
=
bValue
;
}
void
setReadOnly
(
bool
bValue
)
{
_readOnly
=
bValue
;
}
void
setWriteOnly
(
bool
bValue
)
{
_writeOnly
=
bValue
;
}
...
...
@@ -249,7 +249,7 @@ private:
Translator
_rawTranslator
;
Translator
_cookedTranslator
;
bool
_rebootRequired
;
double
_
i
ncrement
;
double
_
rawI
ncrement
;
bool
_hasControl
;
bool
_readOnly
;
bool
_writeOnly
;
...
...
@@ -286,6 +286,7 @@ private:
static
const
char
*
_mobileDefaultValueJsonKey
;
static
const
char
*
_minJsonKey
;
static
const
char
*
_maxJsonKey
;
static
const
char
*
_incrementJsonKey
;
static
const
char
*
_hasControlJsonKey
;
};
...
...
src/FirmwarePlugin/APM/APMParameterMetaData.cc
View file @
8e1a3fd9
...
...
@@ -584,7 +584,7 @@ void APMParameterMetaData::addMetaDataToFact(Fact* fact, MAV_TYPE vehicleType)
bool
ok
;
increment
=
rawMetaData
->
incrementSize
.
toDouble
(
&
ok
);
if
(
ok
)
{
metaData
->
setIncrement
(
increment
);
metaData
->
set
Raw
Increment
(
increment
);
}
else
{
qCDebug
(
APMParameterMetaDataLog
)
<<
"Invalid value for increment, name:"
<<
metaData
->
name
()
<<
" increment:"
<<
rawMetaData
->
incrementSize
;
}
...
...
src/FirmwarePlugin/PX4/PX4ParameterMetaData.cc
View file @
8e1a3fd9
...
...
@@ -332,7 +332,7 @@ void PX4ParameterMetaData::loadParameterFactMetaDataFile(const QString& metaData
QString
text
=
xml
.
readElementText
();
increment
=
text
.
toDouble
(
&
ok
);
if
(
ok
)
{
metaData
->
setIncrement
(
increment
);
metaData
->
set
Raw
Increment
(
increment
);
}
else
{
qCWarning
(
PX4ParameterMetaDataLog
)
<<
"Invalid value for increment, name:"
<<
metaData
->
name
()
<<
" increment:"
<<
text
;
}
...
...
src/MissionManager/CameraSection.FactMetaData.json
View file @
8e1a3fd9
...
...
@@ -32,6 +32,7 @@
"units"
:
"gimbal-degrees"
,
"min"
:
-90
,
"max"
:
0
,
"increment"
:
5
,
"decimalPlaces"
:
0
,
"defaultValue"
:
0
},
...
...
@@ -42,6 +43,7 @@
"units"
:
"deg"
,
"min"
:
-180.0
,
"max"
:
180.0
,
"increment"
:
5
,
"decimalPlaces"
:
0
,
"defaultValue"
:
0
},
...
...
Write
Preview
Supports
Markdown
0%
Try again
or
attach a new file
.
Cancel
You are about to add
0
people
to the discussion. Proceed with caution.
Finish editing this message first!
Cancel
Please
register
or
sign in
to comment