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
5c30eb07
Unverified
Commit
5c30eb07
authored
Feb 11, 2020
by
Don Gagne
Committed by
GitHub
Feb 11, 2020
Browse files
Options
Browse Files
Download
Plain Diff
Merge pull request #8312 from DonLakeFlyer/InfiniteLogDownload
Infinite retries to log download
parents
f47271c8
be09dc03
Changes
2
Hide whitespace changes
Inline
Side-by-side
Showing
2 changed files
with
32 additions
and
19 deletions
+32
-19
LogDownloadController.cc
src/AnalyzeView/LogDownloadController.cc
+30
-17
LogDownloadController.h
src/AnalyzeView/LogDownloadController.h
+2
-2
No files found.
src/AnalyzeView/LogDownloadController.cc
View file @
5c30eb07
...
...
@@ -293,6 +293,24 @@ LogDownloadController::_findMissingEntries()
}
}
void
LogDownloadController
::
_updateDataRate
(
void
)
{
if
(
_downloadData
->
elapsed
.
elapsed
()
>=
kGUIRateMilliseconds
)
{
//-- Update download rate
qreal
rrate
=
_downloadData
->
rate_bytes
/
(
_downloadData
->
elapsed
.
elapsed
()
/
1000.0
);
_downloadData
->
rate_avg
=
(
_downloadData
->
rate_avg
*
0.95
)
+
(
rrate
*
0.05
);
_downloadData
->
rate_bytes
=
0
;
//-- Update status
const
QString
status
=
QString
(
"%1 (%2/s)"
).
arg
(
QGCMapEngine
::
bigSizeToString
(
_downloadData
->
written
),
QGCMapEngine
::
bigSizeToString
(
_downloadData
->
rate_avg
));
_downloadData
->
entry
->
setStatus
(
status
);
_downloadData
->
elapsed
.
start
();
}
}
//----------------------------------------------------------------------------------------
void
LogDownloadController
::
_logData
(
UASInterface
*
uas
,
uint32_t
ofs
,
uint16_t
id
,
uint8_t
count
,
const
uint8_t
*
data
)
...
...
@@ -337,19 +355,7 @@ LogDownloadController::_logData(UASInterface* uas, uint32_t ofs, uint16_t id, ui
if
(
_downloadData
->
file
.
write
((
const
char
*
)
data
,
count
))
{
_downloadData
->
written
+=
count
;
_downloadData
->
rate_bytes
+=
count
;
if
(
_downloadData
->
elapsed
.
elapsed
()
>=
kGUIRateMilliseconds
)
{
//-- Update download rate
qreal
rrate
=
_downloadData
->
rate_bytes
/
(
_downloadData
->
elapsed
.
elapsed
()
/
1000.0
);
_downloadData
->
rate_avg
=
_downloadData
->
rate_avg
*
0.95
+
rrate
*
0.05
;
_downloadData
->
rate_bytes
=
0
;
//-- Update status
const
QString
status
=
QString
(
"%1 (%2/s)"
).
arg
(
QGCMapEngine
::
bigSizeToString
(
_downloadData
->
written
),
QGCMapEngine
::
bigSizeToString
(
_downloadData
->
rate_avg
));
_downloadData
->
entry
->
setStatus
(
status
);
_downloadData
->
elapsed
.
start
();
}
_updateDataRate
();
result
=
true
;
//-- reset retries
_retries
=
0
;
...
...
@@ -422,13 +428,20 @@ LogDownloadController::_findMissingData()
_downloadData
->
advanceChunk
();
}
if
(
_retries
++
>
2
)
{
_retries
++
;
#if 0
// Trying the change to infinite log download. This way if retries hit 100% failure the data rate will
// slowly fall to 0 and the user can Cancel. This should work better on really crappy links.
if(_retries > 5) {
_downloadData->entry->setStatus(tr("Timed Out"));
//-- Give up
qWarning() << "Too many errors retreiving log data. Giving up.";
_receivedAllData();
return;
}
#endif
_updateDataRate
();
uint16_t
start
=
0
,
end
=
0
;
const
int
size
=
_downloadData
->
chunk_table
.
size
();
...
...
@@ -446,17 +459,17 @@ LogDownloadController::_findMissingData()
const
uint32_t
pos
=
_downloadData
->
current_chunk
*
kChunkSize
+
start
*
MAVLINK_MSG_LOG_DATA_FIELD_DATA_LEN
,
len
=
(
end
-
start
)
*
MAVLINK_MSG_LOG_DATA_FIELD_DATA_LEN
;
_requestLogData
(
_downloadData
->
ID
,
pos
,
len
);
_requestLogData
(
_downloadData
->
ID
,
pos
,
len
,
_retries
);
}
//----------------------------------------------------------------------------------------
void
LogDownloadController
::
_requestLogData
(
uint16_t
id
,
uint32_t
offset
,
uint32_t
count
)
LogDownloadController
::
_requestLogData
(
uint16_t
id
,
uint32_t
offset
,
uint32_t
count
,
int
retryCount
)
{
if
(
_vehicle
)
{
//-- APM "Fix"
id
+=
_apmOneBased
;
qCDebug
(
LogDownloadLog
)
<<
"Request log data (id:"
<<
id
<<
"offset:"
<<
offset
<<
"size:"
<<
count
<<
")"
;
qCDebug
(
LogDownloadLog
)
<<
"Request log data (id:"
<<
id
<<
"offset:"
<<
offset
<<
"size:"
<<
count
<<
"
retryCount"
<<
retryCount
<<
"
)"
;
mavlink_message_t
msg
;
mavlink_msg_log_request_data_pack_chan
(
qgcApp
()
->
toolbox
()
->
mavlinkProtocol
()
->
getSystemId
(),
...
...
src/AnalyzeView/LogDownloadController.h
View file @
5c30eb07
...
...
@@ -144,7 +144,6 @@ private slots:
void
_processDownload
();
private:
bool
_entriesComplete
();
bool
_chunkComplete
()
const
;
bool
_logComplete
()
const
;
...
...
@@ -154,10 +153,11 @@ private:
void
_resetSelection
(
bool
canceled
=
false
);
void
_findMissingData
();
void
_requestLogList
(
uint32_t
start
,
uint32_t
end
);
void
_requestLogData
(
uint16_t
id
,
uint32_t
offset
=
0
,
uint32_t
count
=
0xFFFFFFFF
);
void
_requestLogData
(
uint16_t
id
,
uint32_t
offset
,
uint32_t
count
,
int
retryCount
=
0
);
bool
_prepareLogDownload
();
void
_setDownloading
(
bool
active
);
void
_setListing
(
bool
active
);
void
_updateDataRate
();
QGCLogEntry
*
_getNextSelected
();
...
...
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