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
2440526f
Commit
2440526f
authored
Oct 14, 2015
by
Don Gagne
Browse files
Options
Browse Files
Download
Email Patches
Plain Diff
No telemetry logs in mobile
parent
aa9f5591
Changes
4
Show whitespace changes
Inline
Side-by-side
Showing
4 changed files
with
32 additions
and
7 deletions
+32
-7
QGCApplication.cc
src/QGCApplication.cc
+2
-0
LogReplayLink.cc
src/comm/LogReplayLink.cc
+4
-0
MAVLinkProtocol.cc
src/comm/MAVLinkProtocol.cc
+14
-0
MAVLinkProtocol.h
src/comm/MAVLinkProtocol.h
+12
-7
No files found.
src/QGCApplication.cc
View file @
2440526f
...
...
@@ -448,9 +448,11 @@ bool QGCApplication::_initForNormalAppBoot(void)
splashScreen
->
finish
(
mainWindow
);
mainWindow
->
splashScreenFinished
();
#ifndef __mobile__
// Now that main window is up check for lost log files
connect
(
this
,
&
QGCApplication
::
checkForLostLogFiles
,
MAVLinkProtocol
::
instance
(),
&
MAVLinkProtocol
::
checkForLostLogFiles
);
emit
checkForLostLogFiles
();
#endif
// Load known link configurations
LinkManager
::
instance
()
->
loadLinkConfigurationList
();
...
...
src/comm/LogReplayLink.cc
View file @
2440526f
...
...
@@ -367,7 +367,9 @@ void LogReplayLink::_play(void)
{
// FIXME: With move to link I don't think this is needed any more? Except for the replay widget handling multi-uas?
LinkManager
::
instance
()
->
setConnectionsSuspended
(
tr
(
"Connect not allowed during Flight Data replay."
));
#ifndef __mobile__
MAVLinkProtocol
::
instance
()
->
suspendLogForReplay
(
true
);
#endif
// Make sure we aren't at the end of the file, if we are, reset to the beginning and play from there.
if
(
_logFile
.
atEnd
())
{
...
...
@@ -397,7 +399,9 @@ void LogReplayLink::_play(void)
void
LogReplayLink
::
_pause
(
void
)
{
LinkManager
::
instance
()
->
setConnectionsAllowed
();
#ifndef __mobile__
MAVLinkProtocol
::
instance
()
->
suspendLogForReplay
(
false
);
#endif
_readTickTimer
.
stop
();
...
...
src/comm/MAVLinkProtocol.cc
View file @
2440526f
...
...
@@ -33,8 +33,10 @@ Q_DECLARE_METATYPE(mavlink_message_t)
IMPLEMENT_QGC_SINGLETON
(
MAVLinkProtocol
,
MAVLinkProtocol
)
QGC_LOGGING_CATEGORY
(
MAVLinkProtocolLog
,
"MAVLinkProtocolLog"
)
#ifndef __mobile__
const
char
*
MAVLinkProtocol
::
_tempLogFileTemplate
=
"FlightDataXXXXXX"
;
///< Template for temporary log file
const
char
*
MAVLinkProtocol
::
_logFileExtension
=
"mavlink"
;
///< Extension for log files
#endif
/**
* The default constructor will create a new MAVLink object sending heartbeats at
...
...
@@ -52,10 +54,12 @@ MAVLinkProtocol::MAVLinkProtocol(QObject* parent) :
m_actionRetransmissionTimeout
(
100
),
versionMismatchIgnore
(
false
),
systemId
(
QGC
::
defaultSystemId
),
#ifndef __mobile__
_logSuspendError
(
false
),
_logSuspendReplay
(
false
),
_logWasArmed
(
false
),
_tempLogFile
(
QString
(
"%2.%3"
).
arg
(
_tempLogFileTemplate
).
arg
(
_logFileExtension
)),
#endif
_linkMgr
(
LinkManager
::
instance
()),
_heartbeatRate
(
MAVLINK_HEARTBEAT_DEFAULT_RATE
),
_heartbeatsEnabled
(
true
)
...
...
@@ -91,7 +95,9 @@ MAVLinkProtocol::~MAVLinkProtocol()
{
storeSettings
();
#ifndef __mobile__
_closeLogFile
();
#endif
}
void
MAVLinkProtocol
::
loadSettings
()
...
...
@@ -181,10 +187,12 @@ void MAVLinkProtocol::_linkStatusChanged(LinkInterface* link, bool connected)
// Use the same shared pointer as LinkManager
_connectedLinks
.
append
(
LinkManager
::
instance
()
->
sharedPointerForLink
(
link
));
#ifndef __mobile__
if
(
_connectedLinks
.
count
()
==
1
)
{
// This is the first link, we need to start logging
_startLogging
();
}
#endif
// Send command to start MAVLink
// XXX hacky but safe
...
...
@@ -206,10 +214,12 @@ void MAVLinkProtocol::_linkStatusChanged(LinkInterface* link, bool connected)
Q_UNUSED
(
found
);
Q_ASSERT
(
found
);
#ifndef __mobile__
if
(
_connectedLinks
.
count
()
==
0
)
{
// Last link is gone, close out logging
_stopLogging
();
}
#endif
}
}
...
...
@@ -303,6 +313,7 @@ void MAVLinkProtocol::receiveBytes(LinkInterface* link, QByteArray b)
rstatus
.
txbuf
,
rstatus
.
noise
,
rstatus
.
remnoise
);
}
#ifndef __mobile__
// Log data
if
(
!
_logSuspendError
&&
!
_logSuspendReplay
&&
_tempLogFile
.
isOpen
())
{
...
...
@@ -339,6 +350,7 @@ void MAVLinkProtocol::receiveBytes(LinkInterface* link, QByteArray b)
}
}
}
#endif
if
(
message
.
msgid
==
MAVLINK_MSG_ID_HEARTBEAT
)
{
// Notify the vehicle manager of the heartbeat. This will create/update vehicles as needed.
...
...
@@ -613,6 +625,7 @@ int MAVLinkProtocol::getHeartbeatRate()
return
_heartbeatRate
;
}
#ifndef __mobile__
/// @brief Closes the log file if it is open
bool
MAVLinkProtocol
::
_closeLogFile
(
void
)
{
...
...
@@ -707,3 +720,4 @@ void MAVLinkProtocol::deleteTempLogFiles(void)
QFile
::
remove
(
fileInfo
.
filePath
());
}
}
#endif
src/comm/MAVLinkProtocol.h
View file @
2440526f
...
...
@@ -203,11 +203,13 @@ public slots:
/** @brief Store protocol settings */
void
storeSettings
();
#ifndef __mobile__
/// @brief Deletes any log files which are in the temp directory
static
void
deleteTempLogFiles
(
void
);
/// Checks for lost log files
void
checkForLostLogFiles
(
void
);
#endif
protected:
bool
m_multiplexingEnabled
;
///< Enable/disable packet multiplexing
...
...
@@ -281,15 +283,12 @@ private:
~
MAVLinkProtocol
();
void
_linkStatusChanged
(
LinkInterface
*
link
,
bool
connected
);
#ifndef __mobile__
bool
_closeLogFile
(
void
);
void
_startLogging
(
void
);
void
_stopLogging
(
void
);
/// List of all links connected to protocol. We keep SharedLinkInterface objects
/// which are QSharedPointer's in order to maintain reference counts across threads.
/// This way Link deletion works correctly.
QList
<
SharedLinkInterface
>
_connectedLinks
;
bool
_logSuspendError
;
///< true: Logging suspended due to error
bool
_logSuspendReplay
;
///< true: Logging suspended due to replay
bool
_logWasArmed
;
///< true: vehicle was armed during logging
...
...
@@ -297,6 +296,12 @@ private:
QGCTemporaryFile
_tempLogFile
;
///< File to log to
static
const
char
*
_tempLogFileTemplate
;
///< Template for temporary log file
static
const
char
*
_logFileExtension
;
///< Extension for log files
#endif
/// List of all links connected to protocol. We keep SharedLinkInterface objects
/// which are QSharedPointer's in order to maintain reference counts across threads.
/// This way Link deletion works correctly.
QList
<
SharedLinkInterface
>
_connectedLinks
;
LinkManager
*
_linkMgr
;
...
...
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