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
e13b3a0d
Commit
e13b3a0d
authored
Apr 08, 2013
by
Michael Carpenter
Browse files
Options
Browse Files
Download
Email Patches
Plain Diff
Addition of INT8 and INT16 MAV_PARAM_TYPE handling of incoming messages
parent
fa4c1e13
Changes
2
Hide whitespace changes
Inline
Side-by-side
Showing
2 changed files
with
26 additions
and
0 deletions
+26
-0
mavlink_types.h
libs/mavlink/include/mavlink/v1.0/mavlink_types.h
+2
-0
UAS.cc
src/uas/UAS.cc
+24
-0
No files found.
libs/mavlink/include/mavlink/v1.0/mavlink_types.h
View file @
e13b3a0d
...
...
@@ -35,6 +35,8 @@ typedef struct param_union {
uint32_t
param_uint32
;
uint8_t
param_uint8
;
uint8_t
bytes
[
4
];
int16_t
param_int16
;
int8_t
param_int8
;
};
uint8_t
type
;
}
mavlink_param_union_t
;
...
...
src/uas/UAS.cc
View file @
e13b3a0d
...
...
@@ -904,6 +904,26 @@ void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message)
emit
parameterChanged
(
uasId
,
message
.
compid
,
value
.
param_count
,
value
.
param_index
,
parameterName
,
param
);
//qDebug() << "RECEIVED PARAM:" << param;
}
case
MAV_PARAM_TYPE_INT8
:
{
// Variant
QVariant
param
(
val
.
param_int8
);
parameters
.
value
(
component
)
->
insert
(
parameterName
,
param
);
// Emit change
emit
parameterChanged
(
uasId
,
message
.
compid
,
parameterName
,
param
);
emit
parameterChanged
(
uasId
,
message
.
compid
,
value
.
param_count
,
value
.
param_index
,
parameterName
,
param
);
//qDebug() << "RECEIVED PARAM:" << param;
}
case
MAV_PARAM_TYPE_INT16
:
{
// Variant
QVariant
param
(
val
.
param_int16
);
parameters
.
value
(
component
)
->
insert
(
parameterName
,
param
);
// Emit change
emit
parameterChanged
(
uasId
,
message
.
compid
,
parameterName
,
param
);
emit
parameterChanged
(
uasId
,
message
.
compid
,
value
.
param_count
,
value
.
param_index
,
parameterName
,
param
);
//qDebug() << "RECEIVED PARAM:" << param;
}
case
MAV_PARAM_TYPE_UINT32
:
{
// Variant
...
...
@@ -2265,6 +2285,10 @@ void UAS::setParameter(const int component, const QString& id, const QVariant& v
// Assign correct value based on QVariant
switch
(
value
.
type
())
{
case
QVariant
:
:
Char
:
union_value
.
param_int8
=
value
.
toChar
().
toAscii
();
p
.
param_type
=
MAV_PARAM_TYPE_INT8
;
break
;
case
QVariant
:
:
Int
:
union_value
.
param_int32
=
value
.
toInt
();
p
.
param_type
=
MAV_PARAM_TYPE_INT32
;
...
...
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