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
cd6cb915
Commit
cd6cb915
authored
May 07, 2010
by
lm
Browse files
Options
Browse Files
Download
Email Patches
Plain Diff
Added PNGs for mac icon, moved UAS timestamps to microseconds instead of milliseconds
parent
5e416d5e
Changes
11
Hide whitespace changes
Inline
Side-by-side
Showing
11 changed files
with
20 additions
and
9 deletions
+20
-9
macx_128x128x32.png
images/icons/macx_128x128x32.png
+0
-0
macx_16x16x1.png
images/icons/macx_16x16x1.png
+0
-0
macx_16x16x32.png
images/icons/macx_16x16x32.png
+0
-0
macx_32x32x1.png
images/icons/macx_32x32x1.png
+0
-0
macx_32x32x32.png
images/icons/macx_32x32x32.png
+0
-0
macx_48x48x1.png
images/icons/macx_48x48x1.png
+0
-0
macx_48x48x32.png
images/icons/macx_48x48x32.png
+0
-0
MAVLinkProtocol.cc
src/comm/MAVLinkProtocol.cc
+12
-3
MAVLinkProtocol.h
src/comm/MAVLinkProtocol.h
+2
-0
UAS.cc
src/uas/UAS.cc
+5
-5
UASInfoWidget.cc
src/ui/uas/UASInfoWidget.cc
+1
-1
No files found.
images/icons/macx_128x128x32.png
0 → 100644
View file @
cd6cb915
26.6 KB
images/icons/macx_16x16x1.png
0 → 100644
View file @
cd6cb915
121 Bytes
images/icons/macx_16x16x32.png
0 → 100644
View file @
cd6cb915
761 Bytes
images/icons/macx_32x32x1.png
0 → 100644
View file @
cd6cb915
179 Bytes
images/icons/macx_32x32x32.png
0 → 100644
View file @
cd6cb915
2.28 KB
images/icons/macx_48x48x1.png
0 → 100644
View file @
cd6cb915
255 Bytes
images/icons/macx_48x48x32.png
0 → 100644
View file @
cd6cb915
4.57 KB
src/comm/MAVLinkProtocol.cc
View file @
cd6cb915
...
@@ -61,6 +61,8 @@ MAVLinkProtocol::MAVLinkProtocol() :
...
@@ -61,6 +61,8 @@ MAVLinkProtocol::MAVLinkProtocol() :
heartbeatTimer
->
start
(
1000
/
heartbeatRate
);
heartbeatTimer
->
start
(
1000
/
heartbeatRate
);
totalReceiveCounter
=
0
;
totalReceiveCounter
=
0
;
totalLossCounter
=
0
;
totalLossCounter
=
0
;
currReceiveCounter
=
0
;
currLossCounter
=
0
;
for
(
int
i
=
0
;
i
<
256
;
i
++
)
for
(
int
i
=
0
;
i
<
256
;
i
++
)
{
{
for
(
int
j
=
0
;
j
<
256
;
j
++
)
for
(
int
j
=
0
;
j
<
256
;
j
++
)
...
@@ -131,6 +133,7 @@ void MAVLinkProtocol::receiveBytes(LinkInterface* link)
...
@@ -131,6 +133,7 @@ void MAVLinkProtocol::receiveBytes(LinkInterface* link)
}
}
// Increase receive counter
// Increase receive counter
totalReceiveCounter
++
;
totalReceiveCounter
++
;
currReceiveCounter
++
;
qint64
lastLoss
=
totalLossCounter
;
qint64
lastLoss
=
totalLossCounter
;
// Update last packet index
// Update last packet index
if
(
lastIndex
[
message
.
sysid
][
message
.
compid
]
==
-
1
)
if
(
lastIndex
[
message
.
sysid
][
message
.
compid
]
==
-
1
)
...
@@ -150,7 +153,7 @@ void MAVLinkProtocol::receiveBytes(LinkInterface* link)
...
@@ -150,7 +153,7 @@ void MAVLinkProtocol::receiveBytes(LinkInterface* link)
int
safeguard
=
0
;
int
safeguard
=
0
;
//qDebug() << "SYSID" << message.sysid << "COMPID" << message.compid << "MSGID" << message.msgid << "LASTINDEX" << lastIndex[message.sysid][message.compid] << "SEQ" << message.seq;
//qDebug() << "SYSID" << message.sysid << "COMPID" << message.compid << "MSGID" << message.msgid << "LASTINDEX" << lastIndex[message.sysid][message.compid] << "SEQ" << message.seq;
while
(
lastIndex
[
message
.
sysid
][
message
.
compid
]
!=
message
.
seq
&&
safeguard
<
1
)
while
(
lastIndex
[
message
.
sysid
][
message
.
compid
]
!=
message
.
seq
&&
safeguard
<
255
)
{
{
if
(
lastIndex
[
message
.
sysid
][
message
.
compid
]
==
255
)
if
(
lastIndex
[
message
.
sysid
][
message
.
compid
]
==
255
)
{
{
...
@@ -161,6 +164,7 @@ void MAVLinkProtocol::receiveBytes(LinkInterface* link)
...
@@ -161,6 +164,7 @@ void MAVLinkProtocol::receiveBytes(LinkInterface* link)
lastIndex
[
message
.
sysid
][
message
.
compid
]
++
;
lastIndex
[
message
.
sysid
][
message
.
compid
]
++
;
}
}
totalLossCounter
++
;
totalLossCounter
++
;
currLossCounter
++
;
safeguard
++
;
safeguard
++
;
}
}
}
}
...
@@ -171,12 +175,17 @@ void MAVLinkProtocol::receiveBytes(LinkInterface* link)
...
@@ -171,12 +175,17 @@ void MAVLinkProtocol::receiveBytes(LinkInterface* link)
// while (lastCompIndex->value(message.compid, 0)+1 )
// while (lastCompIndex->value(message.compid, 0)+1 )
// }
// }
//if ()
//if ()
if
(
lastLoss
!=
totalLossCounter
||
(
totalReceiveCounter
/
64
)
==
0
)
// If a new loss was detected or we just hit one 128th packet step
if
(
lastLoss
!=
totalLossCounter
||
(
totalReceiveCounter
&
0
b1111111
)
==
0
)
{
{
// Calculate new loss ratio
// Calculate new loss ratio
// Receive loss
// Receive loss
float
receiveLoss
=
(
double
)
totalLossCounter
/
(
double
)(
totalReceiveCounter
+
total
LossCounter
);
float
receiveLoss
=
(
double
)
currLossCounter
/
(
double
)(
currReceiveCounter
+
curr
LossCounter
);
receiveLoss
*=
100.0
f
;
receiveLoss
*=
100.0
f
;
// qDebug() << "LOSSCHANGED" << receiveLoss;
currLossCounter
=
0
;
currReceiveCounter
=
0
;
emit
receiveLossChanged
(
receiveLoss
);
emit
receiveLossChanged
(
receiveLoss
);
}
}
...
...
src/comm/MAVLinkProtocol.h
View file @
cd6cb915
...
@@ -90,6 +90,8 @@ protected:
...
@@ -90,6 +90,8 @@ protected:
int
lastIndex
[
256
][
256
];
int
lastIndex
[
256
][
256
];
int
totalReceiveCounter
;
int
totalReceiveCounter
;
int
totalLossCounter
;
int
totalLossCounter
;
int
currReceiveCounter
;
int
currLossCounter
;
signals:
signals:
/** @brief Message received and directly copied via signal */
/** @brief Message received and directly copied via signal */
...
...
src/uas/UAS.cc
View file @
cd6cb915
...
@@ -225,15 +225,15 @@ void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message)
...
@@ -225,15 +225,15 @@ void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message)
{
{
mavlink_aux_status_t
status
;
mavlink_aux_status_t
status
;
mavlink_msg_aux_status_decode
(
&
message
,
&
status
);
mavlink_msg_aux_status_decode
(
&
message
,
&
status
);
emit
loadChanged
(
this
,
status
.
load
/
10
0
.0
f
);
emit
loadChanged
(
this
,
status
.
load
/
10.0
f
);
emit
valueChanged
(
this
,
"Load"
,
status
.
load
/
1000.0
f
,
MG
::
TIME
::
getGroundTimeNow
());
emit
valueChanged
(
this
,
"Load"
,
((
float
)
status
.
load
)
/
1000.0
f
,
MG
::
TIME
::
getGroundTimeNow
());
}
}
break
;
break
;
case
MAVLINK_MSG_ID_RAW_IMU
:
case
MAVLINK_MSG_ID_RAW_IMU
:
{
{
mavlink_raw_imu_t
raw
;
mavlink_raw_imu_t
raw
;
mavlink_msg_raw_imu_decode
(
&
message
,
&
raw
);
mavlink_msg_raw_imu_decode
(
&
message
,
&
raw
);
quint64
time
=
raw
.
msec
;
quint64
time
=
raw
.
msec
/
1000
;
if
(
time
==
0
)
if
(
time
==
0
)
{
{
time
=
MG
::
TIME
::
getGroundTimeNow
();
time
=
MG
::
TIME
::
getGroundTimeNow
();
...
@@ -285,7 +285,7 @@ void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message)
...
@@ -285,7 +285,7 @@ void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message)
{
{
mavlink_attitude_t
attitude
;
mavlink_attitude_t
attitude
;
mavlink_msg_attitude_decode
(
&
message
,
&
attitude
);
mavlink_msg_attitude_decode
(
&
message
,
&
attitude
);
quint64
time
=
mavlink_msg_attitude_get_msec
(
&
message
);
quint64
time
=
mavlink_msg_attitude_get_msec
(
&
message
)
/
1000
;
if
(
time
==
0
)
if
(
time
==
0
)
{
{
time
=
MG
::
TIME
::
getGroundTimeNow
();
time
=
MG
::
TIME
::
getGroundTimeNow
();
...
@@ -316,7 +316,7 @@ void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message)
...
@@ -316,7 +316,7 @@ void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message)
{
{
mavlink_position_t
pos
;
mavlink_position_t
pos
;
mavlink_msg_position_decode
(
&
message
,
&
pos
);
mavlink_msg_position_decode
(
&
message
,
&
pos
);
quint64
time
=
pos
.
msec
;
quint64
time
=
pos
.
msec
/
1000
;
if
(
time
==
0
)
if
(
time
==
0
)
{
{
time
=
MG
::
TIME
::
getGroundTimeNow
();
time
=
MG
::
TIME
::
getGroundTimeNow
();
...
...
src/ui/uas/UASInfoWidget.cc
View file @
cd6cb915
...
@@ -113,7 +113,7 @@ void UASInfoWidget::updateCPULoad(UASInterface* uas, double load)
...
@@ -113,7 +113,7 @@ void UASInfoWidget::updateCPULoad(UASInterface* uas, double load)
{
{
if
(
activeUAS
==
uas
)
if
(
activeUAS
==
uas
)
{
{
this
->
load
=
load
*
100.0
f
;
this
->
load
=
load
;
}
}
}
}
...
...
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