Skip to content
GitLab
Explore
Sign in
Primary navigation
Search or go to…
Project
Q
qgroundcontrol
Manage
Activity
Members
Labels
Plan
Issues
Issue boards
Milestones
Wiki
Code
Merge requests
Repository
Branches
Commits
Tags
Repository graph
Compare revisions
Snippets
Build
Pipelines
Jobs
Pipeline schedules
Artifacts
Deploy
Releases
Model registry
Operate
Environments
Monitor
Incidents
Analyze
Value stream analytics
Contributor analytics
CI/CD analytics
Repository analytics
Model experiments
Help
Help
Support
GitLab documentation
Compare GitLab plans
Community forum
Contribute to GitLab
Provide feedback
Keyboard shortcuts
?
Snippets
Groups
Projects
Show more breadcrumbs
Valentin Platzgummer
qgroundcontrol
Commits
46c9696f
Commit
46c9696f
authored
5 years ago
by
Gus Grubba
Browse files
Options
Downloads
Patches
Plain Diff
Don't allow ulog download if data persistence is disabled.
parent
c1cdc0fe
No related branches found
No related tags found
No related merge requests found
Changes
1
Show whitespace changes
Inline
Side-by-side
Showing
1 changed file
src/Vehicle/MAVLinkLogManager.cc
+31
-26
31 additions, 26 deletions
src/Vehicle/MAVLinkLogManager.cc
with
31 additions
and
26 deletions
src/Vehicle/MAVLinkLogManager.cc
+
31
−
26
View file @
46c9696f
...
@@ -113,13 +113,13 @@ MAVLinkLogFiles::setUploaded(bool uploaded)
...
@@ -113,13 +113,13 @@ MAVLinkLogFiles::setUploaded(bool uploaded)
//-----------------------------------------------------------------------------
//-----------------------------------------------------------------------------
//-----------------------------------------------------------------------------
//-----------------------------------------------------------------------------
MAVLinkLogProcessor
::
MAVLinkLogProcessor
()
MAVLinkLogProcessor
::
MAVLinkLogProcessor
()
:
_fd
(
NULL
)
:
_fd
(
nullptr
)
,
_written
(
0
)
,
_written
(
0
)
,
_sequence
(
-
1
)
,
_sequence
(
-
1
)
,
_numDrops
(
0
)
,
_numDrops
(
0
)
,
_gotHeader
(
false
)
,
_gotHeader
(
false
)
,
_error
(
false
)
,
_error
(
false
)
,
_record
(
NULL
)
,
_record
(
nullptr
)
{
{
}
}
...
@@ -135,7 +135,7 @@ MAVLinkLogProcessor::close()
...
@@ -135,7 +135,7 @@ MAVLinkLogProcessor::close()
{
{
if
(
_fd
)
{
if
(
_fd
)
{
fclose
(
_fd
);
fclose
(
_fd
);
_fd
=
NULL
;
_fd
=
nullptr
;
}
}
}
}
...
@@ -143,7 +143,7 @@ MAVLinkLogProcessor::close()
...
@@ -143,7 +143,7 @@ MAVLinkLogProcessor::close()
bool
bool
MAVLinkLogProcessor
::
valid
()
MAVLinkLogProcessor
::
valid
()
{
{
return
(
_fd
!=
NULL
)
&&
(
_record
!=
NULL
);
return
(
_fd
!=
nullptr
)
&&
(
_record
!=
nullptr
);
}
}
//-----------------------------------------------------------------------------
//-----------------------------------------------------------------------------
...
@@ -300,12 +300,12 @@ MAVLinkLogManager::MAVLinkLogManager(QGCApplication* app, QGCToolbox* toolbox)
...
@@ -300,12 +300,12 @@ MAVLinkLogManager::MAVLinkLogManager(QGCApplication* app, QGCToolbox* toolbox)
:
QGCTool
(
app
,
toolbox
)
:
QGCTool
(
app
,
toolbox
)
,
_enableAutoUpload
(
true
)
,
_enableAutoUpload
(
true
)
,
_enableAutoStart
(
false
)
,
_enableAutoStart
(
false
)
,
_nam
(
NULL
)
,
_nam
(
nullptr
)
,
_currentLogfile
(
NULL
)
,
_currentLogfile
(
nullptr
)
,
_vehicle
(
NULL
)
,
_vehicle
(
nullptr
)
,
_logRunning
(
false
)
,
_logRunning
(
false
)
,
_loggingDisabled
(
false
)
,
_loggingDisabled
(
false
)
,
_logProcessor
(
NULL
)
,
_logProcessor
(
nullptr
)
,
_deleteAfterUpload
(
false
)
,
_deleteAfterUpload
(
false
)
,
_windSpeed
(
-
1
)
,
_windSpeed
(
-
1
)
,
_publicLog
(
false
)
,
_publicLog
(
false
)
...
@@ -487,7 +487,7 @@ MAVLinkLogManager::setPublicLog(bool pub)
...
@@ -487,7 +487,7 @@ MAVLinkLogManager::setPublicLog(bool pub)
bool
bool
MAVLinkLogManager
::
uploading
()
MAVLinkLogManager
::
uploading
()
{
{
return
_currentLogfile
!=
NULL
;
return
_currentLogfile
!=
nullptr
;
}
}
//-----------------------------------------------------------------------------
//-----------------------------------------------------------------------------
...
@@ -515,7 +515,7 @@ MAVLinkLogManager::uploadLog()
...
@@ -515,7 +515,7 @@ MAVLinkLogManager::uploadLog()
qWarning
()
<<
"Internal error"
;
qWarning
()
<<
"Internal error"
;
}
}
}
}
_currentLogfile
=
NULL
;
_currentLogfile
=
nullptr
;
emit
uploadingChanged
();
emit
uploadingChanged
();
}
}
...
@@ -614,6 +614,9 @@ MAVLinkLogManager::cancelUpload()
...
@@ -614,6 +614,9 @@ MAVLinkLogManager::cancelUpload()
void
void
MAVLinkLogManager
::
startLogging
()
MAVLinkLogManager
::
startLogging
()
{
{
//-- If we are allowed to persist data
AppSettings
*
appSettings
=
qgcApp
()
->
toolbox
()
->
settingsManager
()
->
appSettings
();
if
(
!
appSettings
->
disableAllPersistence
()
->
rawValue
().
toBool
())
{
if
(
_vehicle
&&
_vehicle
->
px4Firmware
()
&&
!
_logginDenied
)
{
if
(
_vehicle
&&
_vehicle
->
px4Firmware
()
&&
!
_logginDenied
)
{
if
(
_createNewLog
())
{
if
(
_createNewLog
())
{
_vehicle
->
startMavlinkLog
();
_vehicle
->
startMavlinkLog
();
...
@@ -622,6 +625,7 @@ MAVLinkLogManager::startLogging()
...
@@ -622,6 +625,7 @@ MAVLinkLogManager::startLogging()
}
}
}
}
}
}
}
//-----------------------------------------------------------------------------
//-----------------------------------------------------------------------------
void
void
...
@@ -644,7 +648,7 @@ MAVLinkLogManager::stopLogging()
...
@@ -644,7 +648,7 @@ MAVLinkLogManager::stopLogging()
}
}
}
}
delete
_logProcessor
;
delete
_logProcessor
;
_logProcessor
=
NULL
;
_logProcessor
=
nullptr
;
_logRunning
=
false
;
_logRunning
=
false
;
emit
logRunningChanged
();
emit
logRunningChanged
();
}
}
...
@@ -790,7 +794,7 @@ MAVLinkLogManager::_uploadFinished()
...
@@ -790,7 +794,7 @@ MAVLinkLogManager::_uploadFinished()
if
(
_deleteAfterUpload
)
{
if
(
_deleteAfterUpload
)
{
if
(
_currentLogfile
)
{
if
(
_currentLogfile
)
{
_deleteLog
(
_currentLogfile
);
_deleteLog
(
_currentLogfile
);
_currentLogfile
=
NULL
;
_currentLogfile
=
nullptr
;
}
}
}
else
{
}
else
{
if
(
_currentLogfile
)
{
if
(
_currentLogfile
)
{
...
@@ -818,7 +822,7 @@ void
...
@@ -818,7 +822,7 @@ void
MAVLinkLogManager
::
_uploadProgress
(
qint64
bytesSent
,
qint64
bytesTotal
)
MAVLinkLogManager
::
_uploadProgress
(
qint64
bytesSent
,
qint64
bytesTotal
)
{
{
if
(
bytesTotal
)
{
if
(
bytesTotal
)
{
qreal
progress
=
(
qreal
)
bytesSent
/
(
qreal
)
bytesTotal
;
qreal
progress
=
static_cast
<
qreal
>
(
bytesSent
)
/
static_cast
<
qreal
>
(
bytesTotal
)
;
if
(
_currentLogfile
)
{
if
(
_currentLogfile
)
{
_currentLogfile
->
setProgress
(
progress
);
_currentLogfile
->
setProgress
(
progress
);
}
}
...
@@ -834,13 +838,14 @@ MAVLinkLogManager::_activeVehicleChanged(Vehicle* vehicle)
...
@@ -834,13 +838,14 @@ MAVLinkLogManager::_activeVehicleChanged(Vehicle* vehicle)
// connects/disconnects. In reality, if QGC is connected to multiple vehicles,
// connects/disconnects. In reality, if QGC is connected to multiple vehicles,
// this is called each time the user switches from one vehicle to another. So
// this is called each time the user switches from one vehicle to another. So
// far, I'm working on the assumption that multiple vehicles is a rare exception.
// far, I'm working on the assumption that multiple vehicles is a rare exception.
// For now, we only handle one log download at a time.
// For now, we only handle one log download at a time. The proper way is to have
// each vehicle with their own instance of this "log manager".
// Disconnect the previous one (if any)
// Disconnect the previous one (if any)
if
(
_vehicle
&&
_vehicle
->
px4Firmware
())
{
if
(
_vehicle
&&
_vehicle
->
px4Firmware
())
{
disconnect
(
_vehicle
,
&
Vehicle
::
armedChanged
,
this
,
&
MAVLinkLogManager
::
_armedChanged
);
disconnect
(
_vehicle
,
&
Vehicle
::
armedChanged
,
this
,
&
MAVLinkLogManager
::
_armedChanged
);
disconnect
(
_vehicle
,
&
Vehicle
::
mavlinkLogData
,
this
,
&
MAVLinkLogManager
::
_mavlinkLogData
);
disconnect
(
_vehicle
,
&
Vehicle
::
mavlinkLogData
,
this
,
&
MAVLinkLogManager
::
_mavlinkLogData
);
disconnect
(
_vehicle
,
&
Vehicle
::
mavCommandResult
,
this
,
&
MAVLinkLogManager
::
_mavCommandResult
);
disconnect
(
_vehicle
,
&
Vehicle
::
mavCommandResult
,
this
,
&
MAVLinkLogManager
::
_mavCommandResult
);
_vehicle
=
NULL
;
_vehicle
=
nullptr
;
//-- Stop logging (if that's the case)
//-- Stop logging (if that's the case)
stopLogging
();
stopLogging
();
emit
canStartLogChanged
();
emit
canStartLogChanged
();
...
@@ -865,7 +870,7 @@ MAVLinkLogManager::_mavlinkLogData(Vehicle* /*vehicle*/, uint8_t /*target_system
...
@@ -865,7 +870,7 @@ MAVLinkLogManager::_mavlinkLogData(Vehicle* /*vehicle*/, uint8_t /*target_system
if
(
!
_logProcessor
->
processStreamData
(
sequence
,
first_message
,
data
))
{
if
(
!
_logProcessor
->
processStreamData
(
sequence
,
first_message
,
data
))
{
qCWarning
(
MAVLinkLogManagerLog
)
<<
"Error writing MAVLink log file:"
<<
_logProcessor
->
fileName
();
qCWarning
(
MAVLinkLogManagerLog
)
<<
"Error writing MAVLink log file:"
<<
_logProcessor
->
fileName
();
delete
_logProcessor
;
delete
_logProcessor
;
_logProcessor
=
NULL
;
_logProcessor
=
nullptr
;
_logRunning
=
false
;
_logRunning
=
false
;
_vehicle
->
stopMavlinkLog
();
_vehicle
->
stopMavlinkLog
();
emit
logRunningChanged
();
emit
logRunningChanged
();
...
@@ -914,7 +919,7 @@ MAVLinkLogManager::_discardLog()
...
@@ -914,7 +919,7 @@ MAVLinkLogManager::_discardLog()
_deleteLog
(
_logProcessor
->
record
());
_deleteLog
(
_logProcessor
->
record
());
}
}
delete
_logProcessor
;
delete
_logProcessor
;
_logProcessor
=
NULL
;
_logProcessor
=
nullptr
;
}
}
_logRunning
=
false
;
_logRunning
=
false
;
emit
logRunningChanged
();
emit
logRunningChanged
();
...
@@ -926,18 +931,18 @@ MAVLinkLogManager::_createNewLog()
...
@@ -926,18 +931,18 @@ MAVLinkLogManager::_createNewLog()
{
{
if
(
_logProcessor
)
{
if
(
_logProcessor
)
{
delete
_logProcessor
;
delete
_logProcessor
;
_logProcessor
=
NULL
;
_logProcessor
=
nullptr
;
}
}
_logProcessor
=
new
MAVLinkLogProcessor
;
_logProcessor
=
new
MAVLinkLogProcessor
;
if
(
_logProcessor
->
create
(
this
,
_logPath
,
_vehicle
->
id
()))
{
if
(
_logProcessor
->
create
(
this
,
_logPath
,
static_cast
<
uint8_t
>
(
_vehicle
->
id
()))
)
{
_insertNewLog
(
_logProcessor
->
record
());
_insertNewLog
(
_logProcessor
->
record
());
emit
logFilesChanged
();
emit
logFilesChanged
();
}
else
{
}
else
{
qCWarning
(
MAVLinkLogManagerLog
)
<<
"Could not create MAVLink log file:"
<<
_logProcessor
->
fileName
();
qCWarning
(
MAVLinkLogManagerLog
)
<<
"Could not create MAVLink log file:"
<<
_logProcessor
->
fileName
();
delete
_logProcessor
;
delete
_logProcessor
;
_logProcessor
=
NULL
;
_logProcessor
=
nullptr
;
}
}
return
_logProcessor
!=
NULL
;
return
_logProcessor
!=
nullptr
;
}
}
//-----------------------------------------------------------------------------
//-----------------------------------------------------------------------------
...
...
This diff is collapsed.
Click to expand it.
Preview
0%
Loading
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!
Save comment
Cancel
Please
register
or
sign in
to comment