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
4d66ea3d
Commit
4d66ea3d
authored
Sep 19, 2017
by
Gus Grubba
Browse files
Options
Browse Files
Download
Email Patches
Plain Diff
Adding support for custom value.
parent
032eef30
Changes
6
Hide whitespace changes
Inline
Side-by-side
Showing
6 changed files
with
68 additions
and
12 deletions
+68
-12
QGCCameraControl.cc
src/Camera/QGCCameraControl.cc
+4
-0
QGCCameraIO.cc
src/Camera/QGCCameraIO.cc
+17
-8
QGCCameraIO.h
src/Camera/QGCCameraIO.h
+15
-0
FactMetaData.cc
src/FactSystem/FactMetaData.cc
+23
-2
FactMetaData.h
src/FactSystem/FactMetaData.h
+1
-0
PX4ParameterMetaData.cc
src/FirmwarePlugin/PX4/PX4ParameterMetaData.cc
+8
-2
No files found.
src/Camera/QGCCameraControl.cc
View file @
4d66ea3d
...
...
@@ -603,6 +603,10 @@ QGCCameraControl::_loadSettings(const QDomNodeList nodeList)
qCritical
()
<<
QString
(
"Unknown type for parameter %1"
).
arg
(
factName
);
return
false
;
}
//-- By definition, custom types do not have control
if
(
factType
==
FactMetaData
::
valueTypeCustom
)
{
control
=
false
;
}
//-- Description
QString
description
;
if
(
!
read_value
(
parameterNode
,
kDescription
,
description
))
{
...
...
src/Camera/QGCCameraIO.cc
View file @
4d66ea3d
...
...
@@ -55,6 +55,9 @@ QGCCameraParamIO::QGCCameraParamIO(QGCCameraControl *control, Fact* fact, Vehicl
case
FactMetaData
:
:
valueTypeFloat
:
_mavParamType
=
MAV_PARAM_TYPE_REAL32
;
break
;
case
FactMetaData
:
:
valueTypeCustom
:
_mavParamType
=
(
MAV_PARAM_TYPE
)
11
;
// MAV_PARAM_TYPE_CUSTOM;
break
;
default:
qWarning
()
<<
"Unsupported fact type"
<<
_fact
->
type
()
<<
"for"
<<
_fact
->
name
();
// Fall through
...
...
@@ -111,11 +114,10 @@ QGCCameraParamIO::sendParameter(bool updateUI)
void
QGCCameraParamIO
::
_sendParameter
()
{
//-- TODO: We should use something other than mavlink_param_union_t for PARAM_EXT_SET
mavlink_param_ext_set_t
p
;
memset
(
&
p
,
0
,
sizeof
(
mavlink_param_ext_set_t
));
mavlink_param_union_t
union_value
;
mavlink_message_t
msg
;
param_ext_union_t
union_value
;
mavlink_message_t
msg
;
FactMetaData
::
ValueType_t
factType
=
_fact
->
type
();
p
.
param_type
=
_mavParamType
;
switch
(
factType
)
{
...
...
@@ -138,6 +140,12 @@ QGCCameraParamIO::_sendParameter()
case
FactMetaData
:
:
valueTypeFloat
:
union_value
.
param_float
=
_fact
->
rawValue
().
toFloat
();
break
;
case
FactMetaData
:
:
valueTypeCustom
:
{
QByteArray
custom
=
_fact
->
rawValue
().
toByteArray
();
memcpy
(
union_value
.
bytes
,
custom
.
data
(),
std
::
max
(
custom
.
size
(),
MAVLINK_MSG_PARAM_EXT_SET_FIELD_PARAM_VALUE_LEN
));
}
break
;
default:
qCritical
()
<<
"Unsupported fact type"
<<
factType
<<
"for"
<<
_fact
->
name
();
// fall through
...
...
@@ -145,7 +153,7 @@ QGCCameraParamIO::_sendParameter()
union_value
.
param_int32
=
(
int32_t
)
_fact
->
rawValue
().
toInt
();
break
;
}
memcpy
(
&
p
.
param_value
[
0
],
&
union_value
.
param_float
,
sizeof
(
float
)
);
memcpy
(
&
p
.
param_value
[
0
],
&
union_value
.
bytes
[
0
],
MAVLINK_MSG_PARAM_EXT_SET_FIELD_PARAM_VALUE_LEN
);
p
.
target_system
=
(
uint8_t
)
_vehicle
->
id
();
p
.
target_component
=
(
uint8_t
)
_control
->
compID
();
strncpy
(
p
.
param_id
,
_fact
->
name
().
toStdString
().
c_str
(),
MAVLINK_MSG_PARAM_EXT_SET_FIELD_PARAM_ID_LEN
);
...
...
@@ -239,11 +247,9 @@ QGCCameraParamIO::handleParamValue(const mavlink_param_ext_value_t& value)
QVariant
QGCCameraParamIO
::
_valueFromMessage
(
const
char
*
value
,
uint8_t
param_type
)
{
//-- TODO: Even though we don't use anything larger than 32-bit, this should
// probably be updated.
QVariant
var
;
mavlink_param
_union_t
u
;
memcpy
(
&
u
.
param_float
,
value
,
sizeof
(
float
)
);
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
:
var
=
QVariant
(
u
.
param_float
);
...
...
@@ -266,6 +272,9 @@ QGCCameraParamIO::_valueFromMessage(const char* value, uint8_t param_type)
case
MAV_PARAM_TYPE_INT32
:
var
=
QVariant
(
u
.
param_int32
);
break
;
case
11
:
//MAV_PARAM_TYPE_CUSTOM:
var
=
QVariant
(
QByteArray
(
value
,
MAVLINK_MSG_PARAM_EXT_SET_FIELD_PARAM_VALUE_LEN
));
break
;
default:
var
=
QVariant
(
0
);
qCritical
()
<<
"Invalid param_type used for camera setting:"
<<
param_type
;
...
...
src/Camera/QGCCameraIO.h
View file @
4d66ea3d
...
...
@@ -15,6 +15,21 @@ class QGCCameraControl;
Q_DECLARE_LOGGING_CATEGORY
(
CameraIOLog
)
Q_DECLARE_LOGGING_CATEGORY
(
CameraIOLogVerbose
)
MAVPACKED
(
typedef
struct
{
union
{
float
param_float
;
int32_t
param_int32
;
uint32_t
param_uint32
;
int16_t
param_int16
;
uint16_t
param_uint16
;
int8_t
param_int8
;
uint8_t
param_uint8
;
uint8_t
bytes
[
MAVLINK_MSG_PARAM_EXT_SET_FIELD_PARAM_VALUE_LEN
];
};
uint8_t
type
;
})
param_ext_union_t
;
//-----------------------------------------------------------------------------
class
QGCCameraParamIO
:
public
QObject
{
...
...
src/FactSystem/FactMetaData.cc
View file @
4d66ea3d
...
...
@@ -240,6 +240,8 @@ QVariant FactMetaData::_minForType(void) const
return
QVariant
(
0
);
case
valueTypeElapsedTimeInSeconds
:
return
QVariant
(
0.0
);
case
valueTypeCustom
:
return
QVariant
();
}
// Make windows compiler happy, even switch is full cased
...
...
@@ -270,6 +272,8 @@ QVariant FactMetaData::_maxForType(void) const
return
QVariant
();
case
valueTypeBool
:
return
QVariant
(
1
);
case
valueTypeCustom
:
return
QVariant
();
}
// Make windows compiler happy, even switch is full cased
...
...
@@ -328,6 +332,10 @@ bool FactMetaData::convertAndValidateRaw(const QVariant& rawValue, bool convertO
convertOk
=
true
;
typedValue
=
QVariant
(
rawValue
.
toBool
());
break
;
case
FactMetaData
:
:
valueTypeCustom
:
convertOk
=
true
;
typedValue
=
QVariant
(
rawValue
.
toByteArray
());
break
;
}
if
(
!
convertOk
)
{
...
...
@@ -389,6 +397,10 @@ bool FactMetaData::convertAndValidateCooked(const QVariant& cookedValue, bool co
convertOk
=
true
;
typedValue
=
QVariant
(
cookedValue
.
toBool
());
break
;
case
FactMetaData
:
:
valueTypeCustom
:
convertOk
=
true
;
typedValue
=
QVariant
(
cookedValue
.
toByteArray
());
break
;
}
if
(
!
convertOk
)
{
...
...
@@ -455,6 +467,10 @@ bool FactMetaData::clampValue(const QVariant& cookedValue, QVariant& typedValue)
convertOk
=
true
;
typedValue
=
QVariant
(
cookedValue
.
toBool
());
break
;
case
FactMetaData
:
:
valueTypeCustom
:
convertOk
=
true
;
typedValue
=
QVariant
(
cookedValue
.
toByteArray
());
break
;
}
return
convertOk
;
}
...
...
@@ -693,7 +709,8 @@ FactMetaData::ValueType_t FactMetaData::stringToType(const QString& typeString,
<<
QStringLiteral
(
"Double"
)
<<
QStringLiteral
(
"String"
)
<<
QStringLiteral
(
"Bool"
)
<<
QStringLiteral
(
"ElapsedSeconds"
);
<<
QStringLiteral
(
"ElapsedSeconds"
)
<<
QStringLiteral
(
"Custom"
);
knownTypes
<<
valueTypeUint8
<<
valueTypeInt8
...
...
@@ -705,7 +722,8 @@ FactMetaData::ValueType_t FactMetaData::stringToType(const QString& typeString,
<<
valueTypeDouble
<<
valueTypeString
<<
valueTypeBool
<<
valueTypeElapsedTimeInSeconds
;
<<
valueTypeElapsedTimeInSeconds
<<
valueTypeCustom
;
for
(
int
i
=
0
;
i
<
knownTypeStrings
.
count
();
i
++
)
{
if
(
knownTypeStrings
[
i
].
compare
(
typeString
,
Qt
::
CaseInsensitive
)
==
0
)
{
...
...
@@ -737,6 +755,9 @@ size_t FactMetaData::typeToSize(ValueType_t type)
case
valueTypeDouble
:
return
8
;
case
valueTypeCustom
:
return
MAVLINK_MSG_PARAM_EXT_SET_FIELD_PARAM_VALUE_LEN
;
default:
qWarning
()
<<
"Unsupported fact value type"
<<
type
;
return
0
;
...
...
src/FactSystem/FactMetaData.h
View file @
4d66ea3d
...
...
@@ -41,6 +41,7 @@ public:
valueTypeString
,
valueTypeBool
,
valueTypeElapsedTimeInSeconds
,
// Internally stored as double, valueString displays as HH:MM:SS
valueTypeCustom
,
// Internally stored as a QByteArray
}
ValueType_t
;
typedef
QVariant
(
*
Translator
)(
const
QVariant
&
from
);
...
...
src/FirmwarePlugin/PX4/PX4ParameterMetaData.cc
View file @
4d66ea3d
...
...
@@ -20,6 +20,8 @@
#include <QDir>
#include <QDebug>
static
const
char
*
kInvalidConverstion
=
"Internal Error: No support for string parameters"
;
QGC_LOGGING_CATEGORY
(
PX4ParameterMetaDataLog
,
"PX4ParameterMetaDataLog"
)
PX4ParameterMetaData
::
PX4ParameterMetaData
(
void
)
...
...
@@ -57,13 +59,17 @@ QVariant PX4ParameterMetaData::_stringToTypedVariant(const QString& string, Fact
convertTo
=
QVariant
::
Double
;
break
;
case
FactMetaData
:
:
valueTypeString
:
qWarning
()
<<
"Internal Error: No support for string parameters"
;
qWarning
()
<<
kInvalidConverstion
;
convertTo
=
QVariant
::
String
;
break
;
case
FactMetaData
:
:
valueTypeBool
:
qWarning
()
<<
"Internal Error: No support for string parameters"
;
qWarning
()
<<
kInvalidConverstion
;
convertTo
=
QVariant
::
Bool
;
break
;
case
FactMetaData
:
:
valueTypeCustom
:
qWarning
()
<<
kInvalidConverstion
;
convertTo
=
QVariant
::
ByteArray
;
break
;
}
*
convertOk
=
var
.
convert
(
convertTo
);
...
...
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