Skip to content
Projects
Groups
Snippets
Help
Loading...
Help
Support
Submit feedback
Contribute to GitLab
Sign in
Toggle navigation
Q
qgroundcontrol
Project
Project
Details
Activity
Releases
Cycle Analytics
Repository
Repository
Files
Commits
Branches
Tags
Contributors
Graph
Compare
Charts
Issues
0
Issues
0
List
Boards
Labels
Milestones
Merge Requests
0
Merge Requests
0
CI / CD
CI / CD
Pipelines
Jobs
Schedules
Charts
Wiki
Wiki
Snippets
Snippets
Members
Members
Collapse sidebar
Close sidebar
Activity
Graph
Charts
Create a new issue
Jobs
Commits
Issue Boards
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
Options
Browse Files
Download
Plain Diff
Merge pull request #6063 from mavlink/writeOnlyMetadata
Write only metadata
parents
261ff890
13e37492
Changes
9
Hide whitespace changes
Inline
Side-by-side
Showing
9 changed files
with
74 additions
and
25 deletions
+74
-25
.appveyor.yml
.appveyor.yml
+2
-2
QGCCameraControl.cc
src/Camera/QGCCameraControl.cc
+10
-1
QGCCameraIO.cc
src/Camera/QGCCameraIO.cc
+39
-20
QGCCameraIO.h
src/Camera/QGCCameraIO.h
+1
-1
Fact.cc
src/FactSystem/Fact.cc
+10
-0
Fact.h
src/FactSystem/Fact.h
+3
-1
FactMetaData.cc
src/FactSystem/FactMetaData.cc
+4
-0
FactMetaData.h
src/FactSystem/FactMetaData.h
+3
-0
VideoStreaming.cc
src/VideoStreaming/VideoStreaming.cc
+2
-0
No files found.
.appveyor.yml
View file @
55fafa52
...
...
@@ -15,7 +15,7 @@ environment:
install
:
-
git submodule update --init --recursive
-
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\
-
ps
:
|
Write-Host "Installing GStreamer..." -ForegroundColor Cyan
...
...
@@ -35,7 +35,7 @@ install:
Write-Host "Installed" -ForegroundColor Green
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
-
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
...
...
src/Camera/QGCCameraControl.cc
View file @
55fafa52
...
...
@@ -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
);
...
...
@@ -797,7 +806,7 @@ QGCCameraControl::_loadSettings(const QDomNodeList nodeList)
metaData
->
setRawUnits
(
attr
);
}
}
qCDebug
(
CameraControlLog
)
<<
"New parameter:"
<<
factName
;
qCDebug
(
CameraControlLog
)
<<
"New parameter:"
<<
factName
<<
(
readOnly
?
"ReadOnly"
:
"Writable"
)
<<
(
writeOnly
?
"WriteOnly"
:
"Readable"
)
;
_nameToFactMetaDataMap
[
factName
]
=
metaData
;
Fact
*
pFact
=
new
Fact
(
_compID
,
factName
,
factType
,
this
);
QQmlEngine
::
setObjectOwnership
(
pFact
,
QQmlEngine
::
CppOwnership
);
...
...
src/Camera/QGCCameraIO.cc
View file @
55fafa52
...
...
@@ -28,8 +28,13 @@ QGCCameraParamIO::QGCCameraParamIO(QGCCameraControl *control, Fact* fact, Vehicl
_paramWriteTimer
.
setInterval
(
3000
);
_paramRequestTimer
.
setSingleShot
(
true
);
_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
(
&
_paramRequestTimer
,
&
QTimer
::
timeout
,
this
,
&
QGCCameraParamIO
::
_paramRequestTimeout
);
connect
(
_fact
,
&
Fact
::
rawValueChanged
,
this
,
&
QGCCameraParamIO
::
_factChanged
);
connect
(
_fact
,
&
Fact
::
_containerRawValueChanged
,
this
,
&
QGCCameraParamIO
::
_containerRawValueChanged
);
_pMavlink
=
qgcApp
()
->
toolbox
()
->
mavlinkProtocol
();
...
...
@@ -38,31 +43,33 @@ 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
;
//-- String and custom are the same for now
case
FactMetaData
:
:
valueTypeString
:
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
;
}
}
...
...
@@ -71,9 +78,11 @@ QGCCameraParamIO::QGCCameraParamIO(QGCCameraControl *control, Fact* fact, Vehicl
void
QGCCameraParamIO
::
setParamRequest
()
{
_paramRequestReceived
=
false
;
_requestRetries
=
0
;
_paramRequestTimer
.
start
();
if
(
!
_fact
->
writeOnly
())
{
_paramRequestReceived
=
false
;
_requestRetries
=
0
;
_paramRequestTimer
.
start
();
}
}
//-----------------------------------------------------------------------------
...
...
@@ -139,6 +148,8 @@ QGCCameraParamIO::_sendParameter()
case
FactMetaData
:
:
valueTypeFloat
:
union_value
.
param_float
=
_fact
->
rawValue
().
toFloat
();
break
;
//-- String and custom are the same for now
case
FactMetaData
:
:
valueTypeString
:
case
FactMetaData
:
:
valueTypeCustom
:
{
QByteArray
custom
=
_fact
->
rawValue
().
toByteArray
();
...
...
@@ -250,28 +261,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 +314,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
;
...
...
src/Camera/QGCCameraIO.h
View file @
55fafa52
...
...
@@ -67,7 +67,7 @@ private:
QTimer
_paramRequestTimer
;
bool
_done
;
bool
_updateOnSet
;
MAV_PARAM_
TYPE
_mavParamType
;
MAV_PARAM_
EXT_TYPE
_mavParamType
;
MAVLinkProtocol
*
_pMavlink
;
bool
_forceUIUpdate
;
};
...
...
src/FactSystem/Fact.cc
View file @
55fafa52
...
...
@@ -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
)
{
...
...
src/FactSystem/Fact.h
View file @
55fafa52
...
...
@@ -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
;
...
...
src/FactSystem/FactMetaData.cc
View file @
55fafa52
...
...
@@ -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
;
}
...
...
src/FactSystem/FactMetaData.h
View file @
55fafa52
...
...
@@ -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
...
...
src/VideoStreaming/VideoStreaming.cc
View file @
55fafa52
...
...
@@ -155,6 +155,8 @@ void initializeVideoStreaming(int &argc, char* argv[], char* logpath, char* debu
#else
Q_UNUSED
(
argc
);
Q_UNUSED
(
argv
);
Q_UNUSED
(
logpath
);
Q_UNUSED
(
debuglevel
);
#endif
qmlRegisterType
<
VideoItem
>
(
"QGroundControl.QgcQtGStreamer"
,
1
,
0
,
"VideoItem"
);
qmlRegisterUncreatableType
<
VideoSurface
>
(
"QGroundControl.QgcQtGStreamer"
,
1
,
0
,
"VideoSurface"
,
QLatin1String
(
"VideoSurface from QML is not supported"
));
...
...
Write
Preview
Markdown
is supported
0%
Try again
or
attach a new file
Attach a 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