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
186d9c7d
Commit
186d9c7d
authored
May 12, 2014
by
Lorenz Meier
Browse files
Merge branch 'master' of github.com:mavlink/qgroundcontrol into thread_test
parents
e6824e20
8371276c
Changes
2
Show whitespace changes
Inline
Side-by-side
src/uas/UAS.cc
View file @
186d9c7d
...
...
@@ -2554,76 +2554,110 @@ void UAS::processParamValueMsg(mavlink_message_t& msg, const QString& paramName,
parameters
.
insert
(
compId
,
new
QMap
<
QString
,
QVariant
>
());
}
// Insert parameter into registry
if
(
parameters
.
value
(
compId
)
->
contains
(
paramName
))
{
parameters
.
value
(
compId
)
->
remove
(
paramName
);
}
QVariant
param
;
// Insert with correct type
// TODO: This is a hack for MAV_AUTOPILOT_ARDUPILOTMEGA until the new version of MAVLink and a fix for their param handling.
switch
(
rawValue
.
param_type
)
{
switch
(
rawValue
.
param_type
)
{
case
MAV_PARAM_TYPE_REAL32
:
{
if
(
getAutopilotType
()
==
MAV_AUTOPILOT_ARDUPILOTMEGA
)
{
param
=
QVariant
(
paramValue
.
param_float
);
}
else
{
}
else
{
param
=
QVariant
(
paramValue
.
param_float
);
}
parameters
.
value
(
compId
)
->
insert
(
paramName
,
param
);
// Emit change
emit
parameterChanged
(
uasId
,
compId
,
paramName
,
param
);
emit
parameterChanged
(
uasId
,
compId
,
rawValue
.
param_count
,
rawValue
.
param_index
,
paramName
,
param
);
// qDebug() << "RECEIVED PARAM:" << param;
}
break
;
case
MAV_PARAM_TYPE_UINT8
:
{
if
(
getAutopilotType
()
==
MAV_AUTOPILOT_ARDUPILOTMEGA
)
{
param
=
QVariant
(
QChar
((
unsigned
char
)
paramValue
.
param_float
));
}
else
{
param
=
QVariant
(
QChar
((
quint8
)
paramValue
.
param_float
));
}
else
{
param
=
QVariant
(
QChar
((
unsigned
char
)
paramValue
.
param_uint8
));
}
parameters
.
value
(
compId
)
->
insert
(
paramName
,
param
);
// Emit change
emit
parameterChanged
(
uasId
,
compId
,
paramName
,
param
);
emit
parameterChanged
(
uasId
,
compId
,
rawValue
.
param_count
,
rawValue
.
param_index
,
paramName
,
param
);
//qDebug() << "RECEIVED PARAM:" << param;
}
break
;
case
MAV_PARAM_TYPE_INT8
:
{
if
(
getAutopilotType
()
==
MAV_AUTOPILOT_ARDUPILOTMEGA
)
{
param
=
QVariant
(
QChar
((
char
)
paramValue
.
param_float
));
}
else
{
param
=
QVariant
(
QChar
((
qint8
)
paramValue
.
param_float
));
}
else
{
param
=
QVariant
(
QChar
((
char
)
paramValue
.
param_int8
));
}
parameters
.
value
(
compId
)
->
insert
(
paramName
,
param
);
// Emit change
emit
parameterChanged
(
uasId
,
compId
,
paramName
,
param
);
emit
parameterChanged
(
uasId
,
compId
,
rawValue
.
param_count
,
rawValue
.
param_index
,
paramName
,
param
);
//qDebug() << "RECEIVED PARAM:" << param;
}
break
;
case
MAV_PARAM_TYPE_INT16
:
{
if
(
getAutopilotType
()
==
MAV_AUTOPILOT_ARDUPILOTMEGA
)
{
param
=
QVariant
((
short
)
paramValue
.
param_float
);
}
else
{
param
=
QVariant
((
qint16
)
paramValue
.
param_float
);
}
break
;
case
MAV_PARAM_TYPE_UINT16
:
if
(
getAutopilotType
()
==
MAV_AUTOPILOT_ARDUPILOTMEGA
)
{
param
=
QVariant
((
unsigned
short
)
paramValue
.
param_float
);
}
else
{
param
=
QVariant
((
quint16
)
paramValue
.
param_float
);
else
{
param
=
QVariant
(
paramValue
.
param_int16
);
}
parameters
.
value
(
compId
)
->
insert
(
paramName
,
param
);
// Emit change
emit
parameterChanged
(
uasId
,
compId
,
paramName
,
param
);
emit
parameterChanged
(
uasId
,
compId
,
rawValue
.
param_count
,
rawValue
.
param_index
,
paramName
,
param
);
//qDebug() << "RECEIVED PARAM:" << param;
}
break
;
case
MAV_PARAM_TYPE_UINT32
:
{
if
(
getAutopilotType
()
==
MAV_AUTOPILOT_ARDUPILOTMEGA
)
{
param
=
QVariant
((
unsigned
int
)
paramValue
.
param_float
);
}
else
{
param
=
QVariant
((
quint32
)
paramValue
.
param_float
);
}
else
{
param
=
QVariant
(
paramValue
.
param_uint32
);
}
parameters
.
value
(
compId
)
->
insert
(
paramName
,
param
);
// Emit change
emit
parameterChanged
(
uasId
,
compId
,
paramName
,
param
);
emit
parameterChanged
(
uasId
,
compId
,
rawValue
.
param_count
,
rawValue
.
param_index
,
paramName
,
param
);
}
break
;
case
MAV_PARAM_TYPE_INT32
:
{
if
(
getAutopilotType
()
==
MAV_AUTOPILOT_ARDUPILOTMEGA
)
{
param
=
QVariant
((
int
)
paramValue
.
param_float
);
}
else
{
param
=
QVariant
((
qint32
)
paramValue
.
param_float
);
}
break
;
default:
qCritical
()
<<
"INVALID DATA TYPE USED AS PARAMETER VALUE: "
<<
rawValue
.
param_type
;
return
;
}
//switch (value.param_type)
// We did not return a critical error, now insert parameter into registry
if
(
parameters
.
value
(
compId
)
->
contains
(
paramName
))
{
parameters
.
value
(
compId
)
->
remove
(
paramName
);
else
{
param
=
QVariant
(
paramValue
.
param_int32
);
}
// add new values
parameters
.
value
(
compId
)
->
insert
(
paramName
,
param
);
// Emit change
emit
parameterChanged
(
uasId
,
compId
,
paramName
,
param
);
emit
parameterChanged
(
uasId
,
compId
,
rawValue
.
param_count
,
rawValue
.
param_index
,
paramName
,
param
);
// qDebug() << "RECEIVED PARAM:" << param;
}
break
;
default:
qCritical
()
<<
"INVALID DATA TYPE USED AS PARAMETER VALUE: "
<<
rawValue
.
param_type
;
}
//switch (value.param_type)
}
/**
...
...
src/ui/uas/UASView.cc
View file @
186d9c7d
...
...
@@ -634,16 +634,26 @@ void UASView::refresh()
// Thrust
m_ui
->
thrustBar
->
setValue
(
thrust
*
100
);
// Time Elapsed
//QDateTime time = MG::TIME::msecToQDateTime(uas->getUptime());
quint64
filterTime
=
uas
->
getUptime
()
/
1000
;
int
hours
=
static_cast
<
int
>
(
filterTime
/
3600
);
int
min
=
static_cast
<
int
>
((
filterTime
-
3600
*
hours
)
/
60
);
int
sec
=
static_cast
<
int
>
(
filterTime
-
60
*
min
-
3600
*
hours
);
QString
timeText
;
timeText
=
timeText
.
sprintf
(
"%02d:%02d:%02d"
,
hours
,
min
,
sec
);
m_ui
->
timeElapsedLabel
->
setText
(
timeText
);
if
(
this
->
timeRemaining
>
1
&&
this
->
timeRemaining
<
QGC
::
MAX_FLIGHT_TIME
)
{
// Filter output to get a higher stability
filterTime
=
static_cast
<
int
>
(
this
->
timeRemaining
);
filterTime
=
0.8
*
filterTime
+
0.2
*
static_cast
<
int
>
(
this
->
timeRemaining
);
int
sec
=
static_cast
<
int
>
(
filterTime
-
static_cast
<
int
>
(
filterTime
/
60
.0
f
)
*
6
0
);
int
min
=
static_cast
<
int
>
(
filterTime
/
60
);
int
hours
=
static_cast
<
int
>
(
filterTime
-
min
*
60
-
sec
);
//
filterTime = 0.8 * filterTime + 0.2 * static_cast<int>(this->timeRemaining);
hours
=
static_cast
<
int
>
(
filterTime
/
3
600
);
min
=
static_cast
<
int
>
(
(
filterTime
-
3600
*
hours
)
/
60
);
sec
=
static_cast
<
int
>
(
filterTime
-
60
*
min
-
3600
*
hours
);
QString
timeText
;
timeText
=
timeText
.
sprintf
(
"%02d:%02d:%02d"
,
hours
,
min
,
sec
);
m_ui
->
timeRemainingLabel
->
setText
(
timeText
);
}
...
...
@@ -652,16 +662,7 @@ void UASView::refresh()
m_ui
->
timeRemainingLabel
->
setText
(
tr
(
"Calc.."
));
}
// Time Elapsed
//QDateTime time = MG::TIME::msecToQDateTime(uas->getUptime());
quint64
filterTime
=
uas
->
getUptime
()
/
1000
;
int
sec
=
static_cast
<
int
>
(
filterTime
-
static_cast
<
int
>
(
filterTime
/
60
)
*
60
);
int
min
=
static_cast
<
int
>
(
filterTime
/
60
);
int
hours
=
static_cast
<
int
>
(
filterTime
-
min
*
60
-
sec
);
QString
timeText
;
timeText
=
timeText
.
sprintf
(
"%02d:%02d:%02d"
,
hours
,
min
,
sec
);
m_ui
->
timeElapsedLabel
->
setText
(
timeText
);
}
generalUpdateCount
++
;
...
...
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