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
55fafa52
Unverified
Commit
55fafa52
authored
Jan 26, 2018
by
Gus Grubba
Committed by
GitHub
Jan 26, 2018
Browse files
Merge pull request #6063 from mavlink/writeOnlyMetadata
Write only metadata
parents
261ff890
13e37492
Changes
9
Hide whitespace changes
Inline
Side-by-side
.appveyor.yml
View file @
55fafa52
...
@@ -15,7 +15,7 @@ environment:
...
@@ -15,7 +15,7 @@ environment:
install
:
install
:
-
git submodule update --init --recursive
-
git submodule update --init --recursive
-
call "%ProgramFiles(x86)%\Microsoft Visual Studio 14.0\VC\vcvarsall.bat" x86
-
call "%ProgramFiles(x86)%\Microsoft Visual Studio 14.0\VC\vcvarsall.bat" x86
-
set PATH=C:\Qt\Tools\QtCreator\bin;C:\Qt\5.9.
2
\msvc2015\bin;%PATH%
-
set PATH=C:\Qt\Tools\QtCreator\bin;C:\Qt\5.9.
3
\msvc2015\bin;%PATH%
-
mkdir %LOCALAPPDATA%\QtProject && copy test\qtlogging.ini %LOCALAPPDATA%\QtProject\
-
mkdir %LOCALAPPDATA%\QtProject && copy test\qtlogging.ini %LOCALAPPDATA%\QtProject\
-
ps
:
|
-
ps
:
|
Write-Host "Installing GStreamer..." -ForegroundColor Cyan
Write-Host "Installing GStreamer..." -ForegroundColor Cyan
...
@@ -35,7 +35,7 @@ install:
...
@@ -35,7 +35,7 @@ install:
Write-Host "Installed" -ForegroundColor Green
Write-Host "Installed" -ForegroundColor Green
build_script
:
build_script
:
-
mkdir %SHADOW_BUILD_DIR% && cd %SHADOW_BUILD_DIR% && C:\Qt\5.9.
2
\msvc2015\bin\qmake -r CONFIG-=debug_and_release CONFIG+=%CONFIG% CONFIG+=WarningsAsErrorsOn %APPVEYOR_BUILD_FOLDER%\qgroundcontrol.pro
-
mkdir %SHADOW_BUILD_DIR% && cd %SHADOW_BUILD_DIR% && C:\Qt\5.9.
3
\msvc2015\bin\qmake -r CONFIG-=debug_and_release CONFIG+=%CONFIG% CONFIG+=WarningsAsErrorsOn %APPVEYOR_BUILD_FOLDER%\qgroundcontrol.pro
-
cd %SHADOW_BUILD_DIR% && jom
-
cd %SHADOW_BUILD_DIR% && jom
-
if "%CONFIG%" EQU "installer" ( copy %SHADOW_BUILD_DIR%\release\QGroundControl-installer.exe %APPVEYOR_BUILD_FOLDER%\QGroundControl-installer.exe )
-
if "%CONFIG%" EQU "installer" ( copy %SHADOW_BUILD_DIR%\release\QGroundControl-installer.exe %APPVEYOR_BUILD_FOLDER%\QGroundControl-installer.exe )
# Generate the source server information to embed in the PDB
# Generate the source server information to embed in the PDB
...
...
src/Camera/QGCCameraControl.cc
View file @
55fafa52
...
@@ -40,6 +40,7 @@ static const char* kParameterrange = "parameterrange";
...
@@ -40,6 +40,7 @@ static const char* kParameterrange = "parameterrange";
static
const
char
*
kParameterranges
=
"parameterranges"
;
static
const
char
*
kParameterranges
=
"parameterranges"
;
static
const
char
*
kParameters
=
"parameters"
;
static
const
char
*
kParameters
=
"parameters"
;
static
const
char
*
kReadOnly
=
"readonly"
;
static
const
char
*
kReadOnly
=
"readonly"
;
static
const
char
*
kWriteOnly
=
"writeonly"
;
static
const
char
*
kRoption
=
"roption"
;
static
const
char
*
kRoption
=
"roption"
;
static
const
char
*
kStep
=
"step"
;
static
const
char
*
kStep
=
"step"
;
static
const
char
*
kStrings
=
"strings"
;
static
const
char
*
kStrings
=
"strings"
;
...
@@ -659,6 +660,13 @@ QGCCameraControl::_loadSettings(const QDomNodeList nodeList)
...
@@ -659,6 +660,13 @@ QGCCameraControl::_loadSettings(const QDomNodeList nodeList)
//-- Is it read only?
//-- Is it read only?
bool
readOnly
=
false
;
bool
readOnly
=
false
;
read_attribute
(
parameterNode
,
kReadOnly
,
readOnly
);
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
//-- Param type
bool
unknownType
;
bool
unknownType
;
FactMetaData
::
ValueType_t
factType
=
FactMetaData
::
stringToType
(
type
,
unknownType
);
FactMetaData
::
ValueType_t
factType
=
FactMetaData
::
stringToType
(
type
,
unknownType
);
...
@@ -689,6 +697,7 @@ QGCCameraControl::_loadSettings(const QDomNodeList nodeList)
...
@@ -689,6 +697,7 @@ QGCCameraControl::_loadSettings(const QDomNodeList nodeList)
metaData
->
setLongDescription
(
description
);
metaData
->
setLongDescription
(
description
);
metaData
->
setHasControl
(
control
);
metaData
->
setHasControl
(
control
);
metaData
->
setReadOnly
(
readOnly
);
metaData
->
setReadOnly
(
readOnly
);
metaData
->
setWriteOnly
(
writeOnly
);
//-- Options (enums)
//-- Options (enums)
QDomElement
optionElem
=
parameterNode
.
toElement
();
QDomElement
optionElem
=
parameterNode
.
toElement
();
QDomNodeList
optionsRoot
=
optionElem
.
elementsByTagName
(
kOptions
);
QDomNodeList
optionsRoot
=
optionElem
.
elementsByTagName
(
kOptions
);
...
@@ -797,7 +806,7 @@ QGCCameraControl::_loadSettings(const QDomNodeList nodeList)
...
@@ -797,7 +806,7 @@ QGCCameraControl::_loadSettings(const QDomNodeList nodeList)
metaData
->
setRawUnits
(
attr
);
metaData
->
setRawUnits
(
attr
);
}
}
}
}
qCDebug
(
CameraControlLog
)
<<
"New parameter:"
<<
factName
;
qCDebug
(
CameraControlLog
)
<<
"New parameter:"
<<
factName
<<
(
readOnly
?
"ReadOnly"
:
"Writable"
)
<<
(
writeOnly
?
"WriteOnly"
:
"Readable"
)
;
_nameToFactMetaDataMap
[
factName
]
=
metaData
;
_nameToFactMetaDataMap
[
factName
]
=
metaData
;
Fact
*
pFact
=
new
Fact
(
_compID
,
factName
,
factType
,
this
);
Fact
*
pFact
=
new
Fact
(
_compID
,
factName
,
factType
,
this
);
QQmlEngine
::
setObjectOwnership
(
pFact
,
QQmlEngine
::
CppOwnership
);
QQmlEngine
::
setObjectOwnership
(
pFact
,
QQmlEngine
::
CppOwnership
);
...
...
src/Camera/QGCCameraIO.cc
View file @
55fafa52
...
@@ -28,8 +28,13 @@ QGCCameraParamIO::QGCCameraParamIO(QGCCameraControl *control, Fact* fact, Vehicl
...
@@ -28,8 +28,13 @@ QGCCameraParamIO::QGCCameraParamIO(QGCCameraControl *control, Fact* fact, Vehicl
_paramWriteTimer
.
setInterval
(
3000
);
_paramWriteTimer
.
setInterval
(
3000
);
_paramRequestTimer
.
setSingleShot
(
true
);
_paramRequestTimer
.
setSingleShot
(
true
);
_paramRequestTimer
.
setInterval
(
3500
);
_paramRequestTimer
.
setInterval
(
3500
);
if
(
_fact
->
writeOnly
())
{
//-- Write mode is always "done" as it won't ever read
_done
=
true
;
}
else
{
connect
(
&
_paramRequestTimer
,
&
QTimer
::
timeout
,
this
,
&
QGCCameraParamIO
::
_paramRequestTimeout
);
}
connect
(
&
_paramWriteTimer
,
&
QTimer
::
timeout
,
this
,
&
QGCCameraParamIO
::
_paramWriteTimeout
);
connect
(
&
_paramWriteTimer
,
&
QTimer
::
timeout
,
this
,
&
QGCCameraParamIO
::
_paramWriteTimeout
);
connect
(
&
_paramRequestTimer
,
&
QTimer
::
timeout
,
this
,
&
QGCCameraParamIO
::
_paramRequestTimeout
);
connect
(
_fact
,
&
Fact
::
rawValueChanged
,
this
,
&
QGCCameraParamIO
::
_factChanged
);
connect
(
_fact
,
&
Fact
::
rawValueChanged
,
this
,
&
QGCCameraParamIO
::
_factChanged
);
connect
(
_fact
,
&
Fact
::
_containerRawValueChanged
,
this
,
&
QGCCameraParamIO
::
_containerRawValueChanged
);
connect
(
_fact
,
&
Fact
::
_containerRawValueChanged
,
this
,
&
QGCCameraParamIO
::
_containerRawValueChanged
);
_pMavlink
=
qgcApp
()
->
toolbox
()
->
mavlinkProtocol
();
_pMavlink
=
qgcApp
()
->
toolbox
()
->
mavlinkProtocol
();
...
@@ -38,31 +43,33 @@ QGCCameraParamIO::QGCCameraParamIO(QGCCameraControl *control, Fact* fact, Vehicl
...
@@ -38,31 +43,33 @@ QGCCameraParamIO::QGCCameraParamIO(QGCCameraControl *control, Fact* fact, Vehicl
switch
(
_fact
->
type
())
{
switch
(
_fact
->
type
())
{
case
FactMetaData
::
valueTypeUint8
:
case
FactMetaData
::
valueTypeUint8
:
case
FactMetaData
::
valueTypeBool
:
case
FactMetaData
::
valueTypeBool
:
_mavParamType
=
MAV_PARAM_TYPE_UINT8
;
_mavParamType
=
MAV_PARAM_
EXT_
TYPE_UINT8
;
break
;
break
;
case
FactMetaData
::
valueTypeInt8
:
case
FactMetaData
::
valueTypeInt8
:
_mavParamType
=
MAV_PARAM_TYPE_INT8
;
_mavParamType
=
MAV_PARAM_
EXT_
TYPE_INT8
;
break
;
break
;
case
FactMetaData
::
valueTypeUint16
:
case
FactMetaData
::
valueTypeUint16
:
_mavParamType
=
MAV_PARAM_TYPE_UINT16
;
_mavParamType
=
MAV_PARAM_
EXT_
TYPE_UINT16
;
break
;
break
;
case
FactMetaData
::
valueTypeInt16
:
case
FactMetaData
::
valueTypeInt16
:
_mavParamType
=
MAV_PARAM_TYPE_INT16
;
_mavParamType
=
MAV_PARAM_
EXT_
TYPE_INT16
;
break
;
break
;
case
FactMetaData
::
valueTypeUint32
:
case
FactMetaData
::
valueTypeUint32
:
_mavParamType
=
MAV_PARAM_TYPE_UINT32
;
_mavParamType
=
MAV_PARAM_
EXT_
TYPE_UINT32
;
break
;
break
;
case
FactMetaData
::
valueTypeFloat
:
case
FactMetaData
::
valueTypeFloat
:
_mavParamType
=
MAV_PARAM_TYPE_REAL32
;
_mavParamType
=
MAV_PARAM_
EXT_
TYPE_REAL32
;
break
;
break
;
//-- String and custom are the same for now
case
FactMetaData
::
valueTypeString
:
case
FactMetaData
::
valueTypeCustom
:
case
FactMetaData
::
valueTypeCustom
:
_mavParamType
=
(
MAV_PARAM_
TYPE
)
11
;
// MAV_PARAM
_TYPE_CUSTOM;
_mavParamType
=
MAV_PARAM_
EXT
_TYPE_CUSTOM
;
break
;
break
;
default:
default:
qWarning
()
<<
"Unsupported fact type"
<<
_fact
->
type
()
<<
"for"
<<
_fact
->
name
();
qWarning
()
<<
"Unsupported fact type"
<<
_fact
->
type
()
<<
"for"
<<
_fact
->
name
();
// Fall through
// Fall through
case
FactMetaData
::
valueTypeInt32
:
case
FactMetaData
::
valueTypeInt32
:
_mavParamType
=
MAV_PARAM_TYPE_INT32
;
_mavParamType
=
MAV_PARAM_
EXT_
TYPE_INT32
;
break
;
break
;
}
}
}
}
...
@@ -71,9 +78,11 @@ QGCCameraParamIO::QGCCameraParamIO(QGCCameraControl *control, Fact* fact, Vehicl
...
@@ -71,9 +78,11 @@ QGCCameraParamIO::QGCCameraParamIO(QGCCameraControl *control, Fact* fact, Vehicl
void
void
QGCCameraParamIO
::
setParamRequest
()
QGCCameraParamIO
::
setParamRequest
()
{
{
_paramRequestReceived
=
false
;
if
(
!
_fact
->
writeOnly
())
{
_requestRetries
=
0
;
_paramRequestReceived
=
false
;
_paramRequestTimer
.
start
();
_requestRetries
=
0
;
_paramRequestTimer
.
start
();
}
}
}
//-----------------------------------------------------------------------------
//-----------------------------------------------------------------------------
...
@@ -139,6 +148,8 @@ QGCCameraParamIO::_sendParameter()
...
@@ -139,6 +148,8 @@ QGCCameraParamIO::_sendParameter()
case
FactMetaData
::
valueTypeFloat
:
case
FactMetaData
::
valueTypeFloat
:
union_value
.
param_float
=
_fact
->
rawValue
().
toFloat
();
union_value
.
param_float
=
_fact
->
rawValue
().
toFloat
();
break
;
break
;
//-- String and custom are the same for now
case
FactMetaData
::
valueTypeString
:
case
FactMetaData
::
valueTypeCustom
:
case
FactMetaData
::
valueTypeCustom
:
{
{
QByteArray
custom
=
_fact
->
rawValue
().
toByteArray
();
QByteArray
custom
=
_fact
->
rawValue
().
toByteArray
();
...
@@ -250,28 +261,28 @@ QGCCameraParamIO::_valueFromMessage(const char* value, uint8_t param_type)
...
@@ -250,28 +261,28 @@ QGCCameraParamIO::_valueFromMessage(const char* value, uint8_t param_type)
param_ext_union_t
u
;
param_ext_union_t
u
;
memcpy
(
u
.
bytes
,
value
,
MAVLINK_MSG_PARAM_EXT_SET_FIELD_PARAM_VALUE_LEN
);
memcpy
(
u
.
bytes
,
value
,
MAVLINK_MSG_PARAM_EXT_SET_FIELD_PARAM_VALUE_LEN
);
switch
(
param_type
)
{
switch
(
param_type
)
{
case
MAV_PARAM_TYPE_REAL32
:
case
MAV_PARAM_
EXT_
TYPE_REAL32
:
var
=
QVariant
(
u
.
param_float
);
var
=
QVariant
(
u
.
param_float
);
break
;
break
;
case
MAV_PARAM_TYPE_UINT8
:
case
MAV_PARAM_
EXT_
TYPE_UINT8
:
var
=
QVariant
(
u
.
param_uint8
);
var
=
QVariant
(
u
.
param_uint8
);
break
;
break
;
case
MAV_PARAM_TYPE_INT8
:
case
MAV_PARAM_
EXT_
TYPE_INT8
:
var
=
QVariant
(
u
.
param_int8
);
var
=
QVariant
(
u
.
param_int8
);
break
;
break
;
case
MAV_PARAM_TYPE_UINT16
:
case
MAV_PARAM_
EXT_
TYPE_UINT16
:
var
=
QVariant
(
u
.
param_uint16
);
var
=
QVariant
(
u
.
param_uint16
);
break
;
break
;
case
MAV_PARAM_TYPE_INT16
:
case
MAV_PARAM_
EXT_
TYPE_INT16
:
var
=
QVariant
(
u
.
param_int16
);
var
=
QVariant
(
u
.
param_int16
);
break
;
break
;
case
MAV_PARAM_TYPE_UINT32
:
case
MAV_PARAM_
EXT_
TYPE_UINT32
:
var
=
QVariant
(
u
.
param_uint32
);
var
=
QVariant
(
u
.
param_uint32
);
break
;
break
;
case
MAV_PARAM_TYPE_INT32
:
case
MAV_PARAM_
EXT_
TYPE_INT32
:
var
=
QVariant
(
u
.
param_int32
);
var
=
QVariant
(
u
.
param_int32
);
break
;
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
));
var
=
QVariant
(
QByteArray
(
value
,
MAVLINK_MSG_PARAM_EXT_SET_FIELD_PARAM_VALUE_LEN
));
break
;
break
;
default:
default:
...
@@ -303,6 +314,14 @@ QGCCameraParamIO::_paramRequestTimeout()
...
@@ -303,6 +314,14 @@ QGCCameraParamIO::_paramRequestTimeout()
void
void
QGCCameraParamIO
::
paramRequest
(
bool
reset
)
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
)
{
if
(
reset
)
{
_requestRetries
=
0
;
_requestRetries
=
0
;
_forceUIUpdate
=
true
;
_forceUIUpdate
=
true
;
...
...
src/Camera/QGCCameraIO.h
View file @
55fafa52
...
@@ -67,7 +67,7 @@ private:
...
@@ -67,7 +67,7 @@ private:
QTimer
_paramRequestTimer
;
QTimer
_paramRequestTimer
;
bool
_done
;
bool
_done
;
bool
_updateOnSet
;
bool
_updateOnSet
;
MAV_PARAM_TYPE
_mavParamType
;
MAV_PARAM_
EXT_
TYPE
_mavParamType
;
MAVLinkProtocol
*
_pMavlink
;
MAVLinkProtocol
*
_pMavlink
;
bool
_forceUIUpdate
;
bool
_forceUIUpdate
;
};
};
...
...
src/FactSystem/Fact.cc
View file @
55fafa52
...
@@ -663,6 +663,16 @@ bool Fact::readOnly(void) const
...
@@ -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
bool
Fact
::
volatileValue
(
void
)
const
{
{
if
(
_metaData
)
{
if
(
_metaData
)
{
...
...
src/FactSystem/Fact.h
View file @
55fafa52
...
@@ -71,6 +71,7 @@ public:
...
@@ -71,6 +71,7 @@ public:
Q_PROPERTY
(
bool
typeIsBool
READ
typeIsBool
CONSTANT
)
Q_PROPERTY
(
bool
typeIsBool
READ
typeIsBool
CONSTANT
)
Q_PROPERTY
(
bool
hasControl
READ
hasControl
CONSTANT
)
Q_PROPERTY
(
bool
hasControl
READ
hasControl
CONSTANT
)
Q_PROPERTY
(
bool
readOnly
READ
readOnly
CONSTANT
)
Q_PROPERTY
(
bool
readOnly
READ
readOnly
CONSTANT
)
Q_PROPERTY
(
bool
writeOnly
READ
writeOnly
CONSTANT
)
Q_PROPERTY
(
bool
volatileValue
READ
volatileValue
CONSTANT
)
Q_PROPERTY
(
bool
volatileValue
READ
volatileValue
CONSTANT
)
/// Convert and validate value
/// Convert and validate value
...
@@ -119,7 +120,8 @@ public:
...
@@ -119,7 +120,8 @@ public:
bool
typeIsBool
(
void
)
const
{
return
type
()
==
FactMetaData
::
valueTypeBool
;
}
bool
typeIsBool
(
void
)
const
{
return
type
()
==
FactMetaData
::
valueTypeBool
;
}
bool
hasControl
(
void
)
const
;
bool
hasControl
(
void
)
const
;
bool
readOnly
(
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.
/// Returns the values as a string with full 18 digit precision if float/double.
QString
rawValueStringFullPrecision
(
void
)
const
;
QString
rawValueStringFullPrecision
(
void
)
const
;
...
...
src/FactSystem/FactMetaData.cc
View file @
55fafa52
...
@@ -94,6 +94,7 @@ FactMetaData::FactMetaData(QObject* parent)
...
@@ -94,6 +94,7 @@ FactMetaData::FactMetaData(QObject* parent)
,
_increment
(
std
::
numeric_limits
<
double
>::
quiet_NaN
())
,
_increment
(
std
::
numeric_limits
<
double
>::
quiet_NaN
())
,
_hasControl
(
true
)
,
_hasControl
(
true
)
,
_readOnly
(
false
)
,
_readOnly
(
false
)
,
_writeOnly
(
false
)
,
_volatile
(
false
)
,
_volatile
(
false
)
{
{
_category
=
kDefaultCategory
;
_category
=
kDefaultCategory
;
...
@@ -116,6 +117,7 @@ FactMetaData::FactMetaData(ValueType_t type, QObject* parent)
...
@@ -116,6 +117,7 @@ FactMetaData::FactMetaData(ValueType_t type, QObject* parent)
,
_increment
(
std
::
numeric_limits
<
double
>::
quiet_NaN
())
,
_increment
(
std
::
numeric_limits
<
double
>::
quiet_NaN
())
,
_hasControl
(
true
)
,
_hasControl
(
true
)
,
_readOnly
(
false
)
,
_readOnly
(
false
)
,
_writeOnly
(
false
)
,
_volatile
(
false
)
,
_volatile
(
false
)
{
{
_category
=
kDefaultCategory
;
_category
=
kDefaultCategory
;
...
@@ -145,6 +147,7 @@ FactMetaData::FactMetaData(ValueType_t type, const QString name, QObject* parent
...
@@ -145,6 +147,7 @@ FactMetaData::FactMetaData(ValueType_t type, const QString name, QObject* parent
,
_increment
(
std
::
numeric_limits
<
double
>::
quiet_NaN
())
,
_increment
(
std
::
numeric_limits
<
double
>::
quiet_NaN
())
,
_hasControl
(
true
)
,
_hasControl
(
true
)
,
_readOnly
(
false
)
,
_readOnly
(
false
)
,
_writeOnly
(
false
)
,
_volatile
(
false
)
,
_volatile
(
false
)
{
{
_category
=
kDefaultCategory
;
_category
=
kDefaultCategory
;
...
@@ -178,6 +181,7 @@ const FactMetaData& FactMetaData::operator=(const FactMetaData& other)
...
@@ -178,6 +181,7 @@ const FactMetaData& FactMetaData::operator=(const FactMetaData& other)
_increment
=
other
.
_increment
;
_increment
=
other
.
_increment
;
_hasControl
=
other
.
_hasControl
;
_hasControl
=
other
.
_hasControl
;
_readOnly
=
other
.
_readOnly
;
_readOnly
=
other
.
_readOnly
;
_writeOnly
=
other
.
_writeOnly
;
_volatile
=
other
.
_volatile
;
_volatile
=
other
.
_volatile
;
return
*
this
;
return
*
this
;
}
}
...
...
src/FactSystem/FactMetaData.h
View file @
55fafa52
...
@@ -104,6 +104,7 @@ public:
...
@@ -104,6 +104,7 @@ public:
bool
rebootRequired
(
void
)
const
{
return
_rebootRequired
;
}
bool
rebootRequired
(
void
)
const
{
return
_rebootRequired
;
}
bool
hasControl
(
void
)
const
{
return
_hasControl
;
}
bool
hasControl
(
void
)
const
{
return
_hasControl
;
}
bool
readOnly
(
void
)
const
{
return
_readOnly
;
}
bool
readOnly
(
void
)
const
{
return
_readOnly
;
}
bool
writeOnly
(
void
)
const
{
return
_writeOnly
;
}
bool
volatileValue
(
void
)
const
{
return
_volatile
;
}
bool
volatileValue
(
void
)
const
{
return
_volatile
;
}
/// Amount to increment value when used in controls such as spin button or slider with detents.
/// Amount to increment value when used in controls such as spin button or slider with detents.
...
@@ -135,6 +136,7 @@ public:
...
@@ -135,6 +136,7 @@ public:
void
setIncrement
(
double
increment
)
{
_increment
=
increment
;
}
void
setIncrement
(
double
increment
)
{
_increment
=
increment
;
}
void
setHasControl
(
bool
bValue
)
{
_hasControl
=
bValue
;
}
void
setHasControl
(
bool
bValue
)
{
_hasControl
=
bValue
;
}
void
setReadOnly
(
bool
bValue
)
{
_readOnly
=
bValue
;
}
void
setReadOnly
(
bool
bValue
)
{
_readOnly
=
bValue
;
}
void
setWriteOnly
(
bool
bValue
)
{
_writeOnly
=
bValue
;
}
void
setVolatileValue
(
bool
bValue
);
void
setVolatileValue
(
bool
bValue
);
void
setTranslators
(
Translator
rawTranslator
,
Translator
cookedTranslator
);
void
setTranslators
(
Translator
rawTranslator
,
Translator
cookedTranslator
);
...
@@ -241,6 +243,7 @@ private:
...
@@ -241,6 +243,7 @@ private:
double
_increment
;
double
_increment
;
bool
_hasControl
;
bool
_hasControl
;
bool
_readOnly
;
bool
_readOnly
;
bool
_writeOnly
;
bool
_volatile
;
bool
_volatile
;
// Exact conversion constants
// Exact conversion constants
...
...
src/VideoStreaming/VideoStreaming.cc
View file @
55fafa52
...
@@ -155,6 +155,8 @@ void initializeVideoStreaming(int &argc, char* argv[], char* logpath, char* debu
...
@@ -155,6 +155,8 @@ void initializeVideoStreaming(int &argc, char* argv[], char* logpath, char* debu
#else
#else
Q_UNUSED
(
argc
);
Q_UNUSED
(
argc
);
Q_UNUSED
(
argv
);
Q_UNUSED
(
argv
);
Q_UNUSED
(
logpath
);
Q_UNUSED
(
debuglevel
);
#endif
#endif
qmlRegisterType
<
VideoItem
>
(
"QGroundControl.QgcQtGStreamer"
,
1
,
0
,
"VideoItem"
);
qmlRegisterType
<
VideoItem
>
(
"QGroundControl.QgcQtGStreamer"
,
1
,
0
,
"VideoItem"
);
qmlRegisterUncreatableType
<
VideoSurface
>
(
"QGroundControl.QgcQtGStreamer"
,
1
,
0
,
"VideoSurface"
,
QLatin1String
(
"VideoSurface from QML is not supported"
));
qmlRegisterUncreatableType
<
VideoSurface
>
(
"QGroundControl.QgcQtGStreamer"
,
1
,
0
,
"VideoSurface"
,
QLatin1String
(
"VideoSurface from QML is not supported"
));
...
...
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