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
1528a1c1
Commit
1528a1c1
authored
May 18, 2010
by
pixhawk
Browse files
minor fixes
parent
17aad9f5
Changes
4
Hide whitespace changes
Inline
Side-by-side
src/comm/MAVLinkSimulationLink.cc
View file @
1528a1c1
...
...
@@ -523,6 +523,9 @@ void MAVLinkSimulationLink::writeBytes(const char* data, qint64 size)
{
mavlink_action_t
action
;
mavlink_msg_action_decode
(
&
msg
,
&
action
);
qDebug
()
<<
"SIM"
<<
"received action"
<<
action
.
action
<<
"for system"
<<
action
.
target
;
switch
(
action
.
action
)
{
case
MAV_ACTION_LAUNCH
:
...
...
src/uas/UAS.cc
View file @
1528a1c1
...
...
@@ -834,10 +834,10 @@ void UAS::setWaypoint(Waypoint* wp)
mavlink_message_t
msg
;
mavlink_waypoint_set_t
set
;
set
.
id
=
wp
->
id
;
QString
name
=
wp
->
name
;
//
QString name = wp->name;
// FIXME Check if this works properly
name
.
truncate
(
MAVLINK_MSG_WAYPOINT_SET_FIELD_NAME_LEN
);
strcpy
((
char
*
)
set
.
name
,
name
.
toStdString
().
c_str
());
//
name.truncate(MAVLINK_MSG_WAYPOINT_SET_FIELD_NAME_LEN);
//
strcpy((char*)set.name, name.toStdString().c_str());
set
.
autocontinue
=
wp
->
autocontinue
;
set
.
target_component
=
0
;
set
.
target_system
=
uasId
;
...
...
src/ui/linechart/LinechartPlot.cc
View file @
1528a1c1
...
...
@@ -715,6 +715,7 @@ void TimeSeriesData::append(quint64 ms, double value)
}
this
->
ms
[
count
]
=
ms
;
this
->
value
[
count
]
=
value
;
this
->
lastValue
=
value
;
this
->
mean
=
0
;
QList
<
double
>
medianList
=
QList
<
double
>
();
for
(
unsigned
int
i
=
0
;
(
i
<
averageWindow
)
&&
(((
int
)
count
-
(
int
)
i
)
>=
0
);
++
i
)
...
...
@@ -824,7 +825,7 @@ double TimeSeriesData::getMedian()
double
TimeSeriesData
::
getCurrentValue
()
{
return
ms
.
last
()
;
return
last
Value
;
}
/**
...
...
src/ui/linechart/LinechartPlot.h
View file @
1528a1c1
...
...
@@ -149,9 +149,10 @@ protected:
quint64
plotCount
;
QString
friendlyName
;
double
minValue
;
double
maxValue
;
double
zeroValue
;
double
lastValue
;
///< The last inserted value
double
minValue
;
///< The smallest value in the dataset
double
maxValue
;
///< The largest value in the dataset
double
zeroValue
;
///< The expected value in the dataset
QMutex
dataMutex
;
...
...
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