@ -2488,12 +2488,15 @@ void Vehicle::_linkActiveChanged(LinkInterface *link, bool active, int vehicleID
@@ -2488,12 +2488,15 @@ void Vehicle::_linkActiveChanged(LinkInterface *link, bool active, int vehicleID
emit linksPropertiesChanged ( ) ;
bool communicationLost = false ;
bool communicationRegained = false ;
if ( link = = _priorityLink ) {
if ( active & & _connectionLost ) {
// communication to priority link regained
_connectionLost = false ;
communicationRegained = true ;
emit connectionLostChanged ( false ) ;
qgcApp ( ) - > showMessage ( ( tr ( " %1 communication to %2 link %3 regained " ) ) . arg ( _vehicleIdSpeech ( ) ) . arg ( ( _links . count ( ) > 1 ) ? " priority " : " " ) . arg ( link - > getName ( ) ) ) ;
if ( _priorityLink - > highLatency ( ) ) {
_setMaxProtoVersion ( 100 ) ;
@ -2504,19 +2507,10 @@ void Vehicle::_linkActiveChanged(LinkInterface *link, bool active, int vehicleID
@@ -2504,19 +2507,10 @@ void Vehicle::_linkActiveChanged(LinkInterface *link, bool active, int vehicleID
false , // No error shown if fails
1 ) ; // Request protocol version
}
} else if ( ! active & & ! _connectionLost ) {
// communication to priority link lost
qgcApp ( ) - > showMessage ( ( tr ( " %1 communication to %2 link %3 lost " ) ) . arg ( _vehicleIdSpeech ( ) ) . arg ( ( _links . count ( ) > 1 ) ? " priority " : " " ) . arg ( link - > getName ( ) ) ) ;
_updatePriorityLink ( false /* updateActive */ , true /* sendCommand */ ) ;
if ( link = = _priorityLink ) {
_say ( QString ( tr ( " %1 communication lost " ) ) . arg ( _vehicleIdSpeech ( ) ) ) ;
qgcApp ( ) - > showMessage ( ( tr ( " %1 communication lost " ) ) . arg ( _vehicleIdSpeech ( ) ) ) ;
if ( _connectionLostEnabled ) {
_connectionLost = true ;
communicationLost = true ;
_heardFrom = false ;
_maxProtoVersion = 0 ;
emit connectionLostChanged ( true ) ;
@ -2531,11 +2525,35 @@ void Vehicle::_linkActiveChanged(LinkInterface *link, bool active, int vehicleID
@@ -2531,11 +2525,35 @@ void Vehicle::_linkActiveChanged(LinkInterface *link, bool active, int vehicleID
}
}
}
}
} else {
qgcApp ( ) - > showMessage ( ( tr ( " %1 communication to auxiliary link %2 %3 " ) ) . arg ( _vehicleIdSpeech ( ) ) . arg ( link - > getName ( ) ) . arg ( active ? " regained " : " lost " ) ) ;
_updatePriorityLink ( false /* updateActive */ , true /* sendCommand */ ) ;
}
QString commSpeech ;
bool multiVehicle = _toolbox - > multiVehicleManager ( ) - > vehicles ( ) - > count ( ) > 1 ;
if ( communicationRegained ) {
commSpeech = tr ( " Communication regained " ) ;
if ( _links . count ( ) > 1 ) {
qgcApp ( ) - > showMessage ( tr ( " Communication regained to vehicle %1 on %2 link %3 " ) . arg ( _id ) . arg ( _links . count ( ) > 1 ? tr ( " priority " ) : tr ( " auxiliary " ) ) . arg ( link - > getName ( ) ) ) ;
} else if ( multiVehicle ) {
qgcApp ( ) - > showMessage ( tr ( " Communication regained to vehicle %1 " ) . arg ( _id ) ) ;
}
}
if ( communicationLost ) {
commSpeech = tr ( " Communication lost " ) ;
if ( _links . count ( ) > 1 ) {
qgcApp ( ) - > showMessage ( tr ( " Communication lost to vehicle %1 on %2 link %3 " ) . arg ( _id ) . arg ( _links . count ( ) > 1 ? tr ( " priority " ) : tr ( " auxiliary " ) ) . arg ( link - > getName ( ) ) ) ;
} else if ( multiVehicle ) {
qgcApp ( ) - > showMessage ( tr ( " Communication lost to vehicle %1 " ) . arg ( _id ) ) ;
}
}
if ( multiVehicle & & ( communicationLost | | communicationRegained ) ) {
commSpeech . append ( tr ( " to vehicle %1 " ) . arg ( _id ) ) ;
}
if ( ! commSpeech . isEmpty ( ) ) {
_say ( commSpeech ) ;
}
}
void Vehicle : : _say ( const QString & text )