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
fbd6ad0c
Commit
fbd6ad0c
authored
Aug 23, 2012
by
Lorenz Meier
Browse files
Options
Browse Files
Download
Plain Diff
Merge pull request #156 from jjhall89/mavParamType
Replaced MAVLINK_TYPE with MAV_PARAM_TYPE where neccessary.
parents
813bae19
512a339e
Changes
3
Hide whitespace changes
Inline
Side-by-side
Showing
3 changed files
with
16 additions
and
16 deletions
+16
-16
MAVLinkSimulationLink.cc
src/comm/MAVLinkSimulationLink.cc
+4
-4
UAS.cc
src/uas/UAS.cc
+6
-6
QGCParamWidget.cc
src/ui/QGCParamWidget.cc
+6
-6
No files found.
src/comm/MAVLinkSimulationLink.cc
View file @
fbd6ad0c
...
@@ -785,7 +785,7 @@ void MAVLinkSimulationLink::writeBytes(const char* data, qint64 size)
...
@@ -785,7 +785,7 @@ void MAVLinkSimulationLink::writeBytes(const char* data, qint64 size)
for
(
i
=
onboardParams
.
begin
();
i
!=
onboardParams
.
end
();
++
i
)
{
for
(
i
=
onboardParams
.
begin
();
i
!=
onboardParams
.
end
();
++
i
)
{
if
(
j
!=
5
)
{
if
(
j
!=
5
)
{
// Pack message and get size of encoded byte string
// Pack message and get size of encoded byte string
mavlink_msg_param_value_pack
(
read
.
target_system
,
componentId
,
&
msg
,
i
.
key
().
toStdString
().
c_str
(),
i
.
value
(),
MAV
LINK_TYPE_FLOAT
,
onboardParams
.
size
(),
j
);
mavlink_msg_param_value_pack
(
read
.
target_system
,
componentId
,
&
msg
,
i
.
key
().
toStdString
().
c_str
(),
i
.
value
(),
MAV
_PARAM_TYPE_REAL32
,
onboardParams
.
size
(),
j
);
// Allocate buffer with packet data
// Allocate buffer with packet data
bufferlength
=
mavlink_msg_to_send_buffer
(
buffer
,
&
msg
);
bufferlength
=
mavlink_msg_to_send_buffer
(
buffer
,
&
msg
);
//add data into datastream
//add data into datastream
...
@@ -816,7 +816,7 @@ void MAVLinkSimulationLink::writeBytes(const char* data, qint64 size)
...
@@ -816,7 +816,7 @@ void MAVLinkSimulationLink::writeBytes(const char* data, qint64 size)
onboardParams
.
insert
(
key
,
set
.
param_value
);
onboardParams
.
insert
(
key
,
set
.
param_value
);
// Pack message and get size of encoded byte string
// Pack message and get size of encoded byte string
mavlink_msg_param_value_pack
(
set
.
target_system
,
componentId
,
&
msg
,
key
.
toStdString
().
c_str
(),
set
.
param_value
,
MAV
LINK_TYPE_FLOAT
,
onboardParams
.
size
(),
onboardParams
.
keys
().
indexOf
(
key
));
mavlink_msg_param_value_pack
(
set
.
target_system
,
componentId
,
&
msg
,
key
.
toStdString
().
c_str
(),
set
.
param_value
,
MAV
_PARAM_TYPE_REAL32
,
onboardParams
.
size
(),
onboardParams
.
keys
().
indexOf
(
key
));
// Allocate buffer with packet data
// Allocate buffer with packet data
bufferlength
=
mavlink_msg_to_send_buffer
(
buffer
,
&
msg
);
bufferlength
=
mavlink_msg_to_send_buffer
(
buffer
,
&
msg
);
//add data into datastream
//add data into datastream
...
@@ -839,7 +839,7 @@ void MAVLinkSimulationLink::writeBytes(const char* data, qint64 size)
...
@@ -839,7 +839,7 @@ void MAVLinkSimulationLink::writeBytes(const char* data, qint64 size)
float
paramValue
=
onboardParams
.
value
(
key
);
float
paramValue
=
onboardParams
.
value
(
key
);
// Pack message and get size of encoded byte string
// Pack message and get size of encoded byte string
mavlink_msg_param_value_pack
(
read
.
target_system
,
componentId
,
&
msg
,
key
.
toStdString
().
c_str
(),
paramValue
,
MAV
LINK_TYPE_FLOAT
,
onboardParams
.
size
(),
onboardParams
.
keys
().
indexOf
(
key
));
mavlink_msg_param_value_pack
(
read
.
target_system
,
componentId
,
&
msg
,
key
.
toStdString
().
c_str
(),
paramValue
,
MAV
_PARAM_TYPE_REAL32
,
onboardParams
.
size
(),
onboardParams
.
keys
().
indexOf
(
key
));
// Allocate buffer with packet data
// Allocate buffer with packet data
bufferlength
=
mavlink_msg_to_send_buffer
(
buffer
,
&
msg
);
bufferlength
=
mavlink_msg_to_send_buffer
(
buffer
,
&
msg
);
//add data into datastream
//add data into datastream
...
@@ -853,7 +853,7 @@ void MAVLinkSimulationLink::writeBytes(const char* data, qint64 size)
...
@@ -853,7 +853,7 @@ void MAVLinkSimulationLink::writeBytes(const char* data, qint64 size)
float
paramValue
=
onboardParams
.
value
(
key
);
float
paramValue
=
onboardParams
.
value
(
key
);
// Pack message and get size of encoded byte string
// Pack message and get size of encoded byte string
mavlink_msg_param_value_pack
(
read
.
target_system
,
componentId
,
&
msg
,
key
.
toStdString
().
c_str
(),
paramValue
,
MAV
LINK_TYPE_FLOAT
,
onboardParams
.
size
(),
onboardParams
.
keys
().
indexOf
(
key
));
mavlink_msg_param_value_pack
(
read
.
target_system
,
componentId
,
&
msg
,
key
.
toStdString
().
c_str
(),
paramValue
,
MAV
_PARAM_TYPE_REAL32
,
onboardParams
.
size
(),
onboardParams
.
keys
().
indexOf
(
key
));
// Allocate buffer with packet data
// Allocate buffer with packet data
bufferlength
=
mavlink_msg_to_send_buffer
(
buffer
,
&
msg
);
bufferlength
=
mavlink_msg_to_send_buffer
(
buffer
,
&
msg
);
//add data into datastream
//add data into datastream
...
...
src/uas/UAS.cc
View file @
fbd6ad0c
...
@@ -772,7 +772,7 @@ void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message)
...
@@ -772,7 +772,7 @@ void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message)
// Insert with correct type
// Insert with correct type
switch
(
value
.
param_type
)
switch
(
value
.
param_type
)
{
{
case
MAV
LINK_TYPE_FLOAT
:
case
MAV
_PARAM_TYPE_REAL32
:
{
{
// Variant
// Variant
QVariant
param
(
val
.
param_float
);
QVariant
param
(
val
.
param_float
);
...
@@ -783,7 +783,7 @@ void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message)
...
@@ -783,7 +783,7 @@ void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message)
qDebug
()
<<
"RECEIVED PARAM:"
<<
param
;
qDebug
()
<<
"RECEIVED PARAM:"
<<
param
;
}
}
break
;
break
;
case
MAV
LINK_TYPE_UINT32_T
:
case
MAV
_PARAM_TYPE_UINT32
:
{
{
// Variant
// Variant
QVariant
param
(
val
.
param_uint32
);
QVariant
param
(
val
.
param_uint32
);
...
@@ -794,7 +794,7 @@ void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message)
...
@@ -794,7 +794,7 @@ void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message)
qDebug
()
<<
"RECEIVED PARAM:"
<<
param
;
qDebug
()
<<
"RECEIVED PARAM:"
<<
param
;
}
}
break
;
break
;
case
MAV
LINK_TYPE_INT32_T
:
case
MAV
_PARAM_TYPE_INT32
:
{
{
// Variant
// Variant
QVariant
param
(
val
.
param_int32
);
QVariant
param
(
val
.
param_int32
);
...
@@ -2001,15 +2001,15 @@ void UAS::setParameter(const int component, const QString& id, const QVariant& v
...
@@ -2001,15 +2001,15 @@ void UAS::setParameter(const int component, const QString& id, const QVariant& v
{
{
case
QVariant
:
:
Int
:
case
QVariant
:
:
Int
:
union_value
.
param_int32
=
value
.
toInt
();
union_value
.
param_int32
=
value
.
toInt
();
p
.
param_type
=
MAV
LINK_TYPE_INT32_T
;
p
.
param_type
=
MAV
_PARAM_TYPE_INT32
;
break
;
break
;
case
QVariant
:
:
UInt
:
case
QVariant
:
:
UInt
:
union_value
.
param_uint32
=
value
.
toUInt
();
union_value
.
param_uint32
=
value
.
toUInt
();
p
.
param_type
=
MAV
LINK_TYPE_UINT32_T
;
p
.
param_type
=
MAV
_PARAM_TYPE_UINT32
;
break
;
break
;
case
QMetaType
:
:
Float
:
case
QMetaType
:
:
Float
:
union_value
.
param_float
=
value
.
toFloat
();
union_value
.
param_float
=
value
.
toFloat
();
p
.
param_type
=
MAV
LINK_TYPE_FLOAT
;
p
.
param_type
=
MAV
_PARAM_TYPE_REAL32
;
break
;
break
;
default:
default:
qCritical
()
<<
"ABORTED PARAM SEND, NO VALID QVARIANT TYPE"
;
qCritical
()
<<
"ABORTED PARAM SEND, NO VALID QVARIANT TYPE"
;
...
...
src/ui/QGCParamWidget.cc
View file @
fbd6ad0c
...
@@ -724,15 +724,15 @@ void QGCParamWidget::saveParameters()
...
@@ -724,15 +724,15 @@ void QGCParamWidget::saveParameters()
{
{
case
QVariant
:
:
Int
:
case
QVariant
:
:
Int
:
paramValue
=
paramValue
.
arg
(
j
.
value
().
toInt
());
paramValue
=
paramValue
.
arg
(
j
.
value
().
toInt
());
paramType
=
paramType
.
arg
(
MAV
LINK_TYPE_INT32_T
);
paramType
=
paramType
.
arg
(
MAV
_PARAM_TYPE_INT32
);
break
;
break
;
case
QVariant
:
:
UInt
:
case
QVariant
:
:
UInt
:
paramValue
=
paramValue
.
arg
(
j
.
value
().
toUInt
());
paramValue
=
paramValue
.
arg
(
j
.
value
().
toUInt
());
paramType
=
paramType
.
arg
(
MAV
LINK_TYPE_UINT32_T
);
paramType
=
paramType
.
arg
(
MAV
_PARAM_TYPE_UINT32
);
break
;
break
;
case
QMetaType
:
:
Float
:
case
QMetaType
:
:
Float
:
paramValue
=
paramValue
.
arg
(
j
.
value
().
toDouble
(),
25
,
'g'
,
12
);
paramValue
=
paramValue
.
arg
(
j
.
value
().
toDouble
(),
25
,
'g'
,
12
);
paramType
=
paramType
.
arg
(
MAV
LINK_TYPE_FLOAT
);
paramType
=
paramType
.
arg
(
MAV
_PARAM_TYPE_REAL32
);
break
;
break
;
default:
default:
qCritical
()
<<
"ABORTED PARAM WRITE TO FILE, NO VALID QVARIANT TYPE"
<<
j
.
value
();
qCritical
()
<<
"ABORTED PARAM WRITE TO FILE, NO VALID QVARIANT TYPE"
<<
j
.
value
();
...
@@ -789,13 +789,13 @@ void QGCParamWidget::loadParameters()
...
@@ -789,13 +789,13 @@ void QGCParamWidget::loadParameters()
switch
(
wpParams
.
at
(
3
).
toUInt
())
switch
(
wpParams
.
at
(
3
).
toUInt
())
{
{
case
MAV
LINK_TYPE_FLOAT
:
case
MAV
_PARAM_TYPE_REAL32
:
changedValues
.
value
(
wpParams
.
at
(
1
).
toInt
())
->
insert
(
wpParams
.
at
(
2
),
wpParams
.
at
(
3
).
toFloat
());
changedValues
.
value
(
wpParams
.
at
(
1
).
toInt
())
->
insert
(
wpParams
.
at
(
2
),
wpParams
.
at
(
3
).
toFloat
());
break
;
break
;
case
MAV
LINK_TYPE_UINT32_T
:
case
MAV
_PARAM_TYPE_UINT32
:
changedValues
.
value
(
wpParams
.
at
(
1
).
toInt
())
->
insert
(
wpParams
.
at
(
2
),
wpParams
.
at
(
3
).
toUInt
());
changedValues
.
value
(
wpParams
.
at
(
1
).
toInt
())
->
insert
(
wpParams
.
at
(
2
),
wpParams
.
at
(
3
).
toUInt
());
break
;
break
;
case
MAV
LINK_TYPE_INT32_T
:
case
MAV
_PARAM_TYPE_INT32
:
changedValues
.
value
(
wpParams
.
at
(
1
).
toInt
())
->
insert
(
wpParams
.
at
(
2
),
wpParams
.
at
(
3
).
toInt
());
changedValues
.
value
(
wpParams
.
at
(
1
).
toInt
())
->
insert
(
wpParams
.
at
(
2
),
wpParams
.
at
(
3
).
toInt
());
break
;
break
;
}
}
...
...
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