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
1e77e295
Commit
1e77e295
authored
Apr 06, 2018
by
acfloria
Browse files
Options
Browse Files
Download
Email Patches
Plain Diff
Use again the heartbeat instead of bytes received to determine if a link is active
parent
dd28d2a3
Changes
5
Hide whitespace changes
Inline
Side-by-side
Showing
5 changed files
with
25 additions
and
21 deletions
+25
-21
Vehicle.cc
src/Vehicle/Vehicle.cc
+1
-0
LinkInterface.cc
src/comm/LinkInterface.cc
+13
-14
LinkInterface.h
src/comm/LinkInterface.h
+3
-3
LinkManager.cc
src/comm/LinkManager.cc
+7
-3
LinkManager.h
src/comm/LinkManager.h
+1
-1
No files found.
src/Vehicle/Vehicle.cc
View file @
1e77e295
...
...
@@ -2490,6 +2490,7 @@ void Vehicle::_linkActiveChanged(LinkInterface *link, bool active)
}
}
else
{
qgcApp
()
->
showMessage
((
tr
(
"communication to auxiliary link %2 %3"
)).
arg
(
link
->
getName
()).
arg
(
active
?
"regained"
:
"lost"
));
_updatePriorityLink
(
false
,
true
);
}
}
...
...
src/comm/LinkInterface.cc
View file @
1e77e295
...
...
@@ -28,7 +28,7 @@ LinkInterface::LinkInterface(SharedLinkConfigurationPointer& config)
,
_active
(
false
)
,
_enableRateCollection
(
false
)
,
_decodedFirstMavlinkPacket
(
false
)
,
_
bytes
ReceivedTimer
(
NULL
)
,
_
heartbeat
ReceivedTimer
(
NULL
)
{
_config
->
setLink
(
this
);
...
...
@@ -161,8 +161,7 @@ void LinkInterface::_setMavlinkChannel(uint8_t channel)
_mavlinkChannel
=
channel
;
}
void
LinkInterface
::
_bytesReceivedTimeout
()
void
LinkInterface
::
_heartbeatReceivedTimeout
()
{
if
(
_active
&&
!
_highLatency
)
{
setActive
(
false
);
...
...
@@ -170,21 +169,21 @@ void LinkInterface::_bytesReceivedTimeout()
}
void
LinkInterface
::
timerStart
()
{
if
(
_
bytes
ReceivedTimer
)
{
_
bytes
ReceivedTimer
->
start
();
if
(
_
heartbeat
ReceivedTimer
)
{
_
heartbeat
ReceivedTimer
->
start
();
}
else
{
_
bytes
ReceivedTimer
=
new
QTimer
();
_
bytesReceivedTimer
->
setInterval
(
_bytes
ReceivedTimeoutMSecs
);
_
bytes
ReceivedTimer
->
setSingleShot
(
true
);
_
bytes
ReceivedTimer
->
start
();
QObject
::
connect
(
_
bytesReceivedTimer
,
&
QTimer
::
timeout
,
this
,
&
LinkInterface
::
_bytes
ReceivedTimeout
);
_
heartbeat
ReceivedTimer
=
new
QTimer
();
_
heartbeatReceivedTimer
->
setInterval
(
_heartbeat
ReceivedTimeoutMSecs
);
_
heartbeat
ReceivedTimer
->
setSingleShot
(
true
);
_
heartbeat
ReceivedTimer
->
start
();
QObject
::
connect
(
_
heartbeatReceivedTimer
,
&
QTimer
::
timeout
,
this
,
&
LinkInterface
::
_heartbeat
ReceivedTimeout
);
}
}
void
LinkInterface
::
timerStop
()
{
if
(
_
bytes
ReceivedTimer
)
{
_
bytes
ReceivedTimer
->
stop
();
QObject
::
disconnect
(
_
bytesReceivedTimer
,
&
QTimer
::
timeout
,
this
,
&
LinkInterface
::
_bytes
ReceivedTimeout
);
delete
_
bytes
ReceivedTimer
;
if
(
_
heartbeat
ReceivedTimer
)
{
_
heartbeat
ReceivedTimer
->
stop
();
QObject
::
disconnect
(
_
heartbeatReceivedTimer
,
&
QTimer
::
timeout
,
this
,
&
LinkInterface
::
_heartbeat
ReceivedTimeout
);
delete
_
heartbeat
ReceivedTimer
;
}
}
src/comm/LinkInterface.h
View file @
1e77e295
...
...
@@ -154,7 +154,7 @@ public slots:
private
slots
:
virtual
void
_writeBytes
(
const
QByteArray
)
=
0
;
void
_
bytes
ReceivedTimeout
(
void
);
void
_
heartbeat
ReceivedTimeout
(
void
);
signals:
...
...
@@ -298,8 +298,8 @@ private:
bool
_enableRateCollection
;
bool
_decodedFirstMavlinkPacket
;
///< true: link has correctly decoded it's first mavlink packet
static
const
int
_
bytes
ReceivedTimeoutMSecs
=
3500
;
// Signal connection lost after 3.5 seconds of no messages
QTimer
*
_
bytes
ReceivedTimer
;
static
const
int
_
heartbeat
ReceivedTimeoutMSecs
=
3500
;
// Signal connection lost after 3.5 seconds of no messages
QTimer
*
_
heartbeat
ReceivedTimer
;
};
typedef
QSharedPointer
<
LinkInterface
>
SharedLinkInterfacePointer
;
...
...
src/comm/LinkManager.cc
View file @
1e77e295
...
...
@@ -80,6 +80,8 @@ void LinkManager::setToolbox(QGCToolbox *toolbox)
_autoConnectSettings
=
toolbox
->
settingsManager
()
->
autoConnectSettings
();
_mavlinkProtocol
=
_toolbox
->
mavlinkProtocol
();
connect
(
_mavlinkProtocol
,
&
MAVLinkProtocol
::
vehicleHeartbeatInfo
,
this
,
&
LinkManager
::
_heartbeatReceived
);
connect
(
&
_portListTimer
,
&
QTimer
::
timeout
,
this
,
&
LinkManager
::
_updateAutoConnectLinks
);
_portListTimer
.
start
(
_autoconnectUpdateTimerMSecs
);
// timeout must be long enough to get past bootloader on second pass
...
...
@@ -195,7 +197,6 @@ void LinkManager::_addLink(LinkInterface* link)
connect
(
link
,
&
LinkInterface
::
communicationError
,
_app
,
&
QGCApplication
::
criticalMessageBoxOnMainThread
);
connect
(
link
,
&
LinkInterface
::
bytesReceived
,
_mavlinkProtocol
,
&
MAVLinkProtocol
::
receiveBytes
);
connect
(
link
,
&
LinkInterface
::
bytesReceived
,
this
,
&
LinkManager
::
_bytesReceived
);
_mavlinkProtocol
->
resetMetadataForLink
(
link
);
_mavlinkProtocol
->
setVersion
(
_mavlinkProtocol
->
getCurrentVersion
());
...
...
@@ -1005,8 +1006,11 @@ void LinkManager::_freeMavlinkChannel(int channel)
_mavlinkChannelsUsedBitMask
&=
~
(
1
<<
channel
);
}
void
LinkManager
::
_bytesReceived
(
LinkInterface
*
link
,
QByteArray
bytes
)
{
Q_UNUSED
(
bytes
);
void
LinkManager
::
_heartbeatReceived
(
LinkInterface
*
link
,
int
vehicleId
,
int
componentId
,
int
vehicleFirmwareType
,
int
vehicleType
)
{
Q_UNUSED
(
vehicleId
);
Q_UNUSED
(
componentId
);
Q_UNUSED
(
vehicleFirmwareType
);
Q_UNUSED
(
vehicleType
);
link
->
timerStart
();
...
...
src/comm/LinkManager.h
View file @
1e77e295
...
...
@@ -204,7 +204,7 @@ private:
SerialConfiguration
*
_autoconnectConfigurationsContainsPort
(
const
QString
&
portName
);
#endif
void
_
bytesReceived
(
LinkInterface
*
link
,
QByteArray
bytes
);
void
_
heartbeatReceived
(
LinkInterface
*
link
,
int
vehicleId
,
int
componentId
,
int
vehicleFirmwareType
,
int
vehicleType
);
bool
_configUpdateSuspended
;
///< true: stop updating configuration list
bool
_configurationsLoaded
;
///< true: Link configurations have been loaded
...
...
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