Commit 7c89c4ac authored by acfloria's avatar acfloria

Multi link support clean up

- Improve function names
- For notifications of an active link change only show the priority keyword if multiple links are connected
- Use QMap instead of QList for the HeartbeatTimers
- Style improvements
- Simplify sending the MAV_CMD_CONTROL_HIGH_LATENCY command
parent a09fcba9
......@@ -1611,9 +1611,9 @@ void Vehicle::_addLink(LinkInterface* link)
qCDebug(VehicleLog) << "_addLink:" << QString("%1").arg((ulong)link, 0, 16);
_links += link;
if (_links.count() <= 1) {
_updatePriorityLink(true, false);
_updatePriorityLink(true /* updateActive */, false /* sendCommand */);
} else {
_updatePriorityLink(true, true);
_updatePriorityLink(true /* updateActive */, true /* sendCommand */);
}
connect(_toolbox->linkManager(), &LinkManager::linkInactive, this, &Vehicle::_linkInactiveOrDeleted);
......@@ -1633,7 +1633,7 @@ void Vehicle::_linkInactiveOrDeleted(LinkInterface* link)
_priorityLink.clear();
}
_updatePriorityLink(true, true);
_updatePriorityLink(true /* updateActive */, true /* sendCommand */);
if (_links.count() == 0 && !_allLinksInactiveSent) {
qCDebug(VehicleLog) << "All links inactive";
......@@ -2480,7 +2480,7 @@ void Vehicle::_linkActiveChanged(LinkInterface *link, bool active, int vehicleID
// communication to priority link regained
_connectionLost = false;
emit connectionLostChanged(false);
qgcApp()->showMessage((tr("%1 communication to priority link %2 regained")).arg(_vehicleIdSpeech()).arg(link->getName()));
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);
......@@ -2494,9 +2494,9 @@ void Vehicle::_linkActiveChanged(LinkInterface *link, bool active, int vehicleID
} else if (!active && !_connectionLost) {
// communication to priority link lost
qgcApp()->showMessage((tr("%1 communication to priority link %2 lost")).arg(_vehicleIdSpeech()).arg(link->getName()));
qgcApp()->showMessage((tr("%1 communication to %2 link %3 lost")).arg(_vehicleIdSpeech()).arg((_links.count() > 1) ? "priority" : "").arg(link->getName()));
_updatePriorityLink(false, true);
_updatePriorityLink(false /* updateActive */, true /* sendCommand */);
if (link == _priorityLink) {
_say(QString(tr("%1 communication lost")).arg(_vehicleIdSpeech()));
......@@ -2520,7 +2520,7 @@ 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, true);
_updatePriorityLink(false /* updateActive */, true /* sendCommand */);
}
}
......@@ -3408,17 +3408,10 @@ void Vehicle::_updateHighLatencyLink(bool sendCommand)
emit highLatencyLinkChanged(_highLatencyLink);
if (sendCommand) {
if (_highLatencyLink) {
sendMavCommand(defaultComponentId(),
MAV_CMD_CONTROL_HIGH_LATENCY,
true,
1.0f); // request start transmitting over high latency telemetry
} else {
sendMavCommand(defaultComponentId(),
MAV_CMD_CONTROL_HIGH_LATENCY,
true,
0.0f); // request stop transmitting over high latency telemetry
}
sendMavCommand(defaultComponentId(),
MAV_CMD_CONTROL_HIGH_LATENCY,
true,
_highLatencyLink ? 1.0f : 0.0f); // request start/stop transmitting over high latency telemetry
}
}
}
......
......@@ -12,8 +12,10 @@
bool LinkInterface::active() const
{
for( int i=0; i<_heartbeatTimerList.count(); ++i ) {
if (_heartbeatTimerList[i]->getActive()) {
QMapIterator<int /* vehicle id */, HeartbeatTimer*> iter(_heartbeatTimers);
while (iter.hasNext()) {
iter.next();
if (iter.value()->getActive()) {
return true;
}
}
......@@ -23,13 +25,11 @@ bool LinkInterface::active() const
bool LinkInterface::active(int vehicle_id) const
{
for( int i=0; i<_heartbeatTimerList.count(); ++i ) {
if (_heartbeatTimerList[i]->getVehicleID() == vehicle_id) {
return _heartbeatTimerList[i]->getActive();
}
if (_heartbeatTimers.contains(vehicle_id)) {
return _heartbeatTimers.value(vehicle_id)->getActive();
} else {
return false;
}
return false;
}
/// mavlink channel to use for this link, as used by mavlink_parse_char. The mavlink channel is only
......@@ -186,29 +186,23 @@ void LinkInterface::_activeChanged(bool active, int vehicle_id)
emit activeChanged(this, active, vehicle_id);
}
void LinkInterface::timerStart(int vehicle_id) {
int timer_index{-1};
for( int i=0; i<_heartbeatTimerList.count(); ++i ) {
if (_heartbeatTimerList[i]->getVehicleID() == vehicle_id) {
timer_index = i;
break;
}
}
if (timer_index != -1) {
_heartbeatTimerList[timer_index]->restartTimer();
void LinkInterface::startHeartbeatTimer(int vehicle_id) {
if (_heartbeatTimers.contains(vehicle_id)) {
_heartbeatTimers.value(vehicle_id)->restartTimer();
} else {
_heartbeatTimerList.append(new HeartbeatTimer(vehicle_id, _highLatency));
QObject::connect(_heartbeatTimerList.last(), &HeartbeatTimer::activeChanged, this, &LinkInterface::_activeChanged);
_heartbeatTimers.insert(vehicle_id, new HeartbeatTimer(vehicle_id, _highLatency));
QObject::connect(_heartbeatTimers.value(vehicle_id), &HeartbeatTimer::activeChanged, this, &LinkInterface::_activeChanged);
}
}
void LinkInterface::timerStop() {
for(int i=0; i<_heartbeatTimerList.count(); ++i ) {
QObject::disconnect(_heartbeatTimerList[i], &HeartbeatTimer::activeChanged, this, &LinkInterface::_activeChanged);
delete _heartbeatTimerList[i];
_heartbeatTimerList[i] = nullptr;
void LinkInterface::stopHeartbeatTimer() {
QMapIterator<int /* vehicle id */, HeartbeatTimer*> iter(_heartbeatTimers);
while (iter.hasNext()) {
iter.next();
QObject::disconnect(iter.value(), &HeartbeatTimer::activeChanged, this, &LinkInterface::_activeChanged);
delete _heartbeatTimers[iter.key()];
_heartbeatTimers[iter.key()] = nullptr;
}
_heartbeatTimerList.clear();
_heartbeatTimers.clear();
}
......@@ -39,7 +39,7 @@ class LinkInterface : public QThread
public:
virtual ~LinkInterface() {
timerStop();
stopHeartbeatTimer();
_config->setLink(NULL);
}
......@@ -260,18 +260,19 @@ private:
void _setMavlinkChannel(uint8_t channel);
/**
* @brief timerStart
* @brief startHeartbeatTimer
*
* Allocate the timer if it does not exist yet and start it.
* Start/restart the heartbeat timer for the specific vehicle.
* If no timer exists an instance is allocated.
*/
void timerStart(int vehicle_id);
void startHeartbeatTimer(int vehicle_id);
/**
* @brief timerStop
* @brief stopHeartbeatTimer
*
* Stop and deallocate the timer if it exists.
* Stop and deallocate the heartbeat timers for all vehicles if any exists.
*/
void timerStop();
void stopHeartbeatTimer();
bool _mavlinkChannelSet; ///< true: _mavlinkChannel has been set
uint8_t _mavlinkChannel; ///< mavlink channel to use for this link, as used by mavlink_parse_char
......@@ -297,7 +298,7 @@ private:
bool _enableRateCollection;
bool _decodedFirstMavlinkPacket; ///< true: link has correctly decoded it's first mavlink packet
QList<HeartbeatTimer*> _heartbeatTimerList;
QMap<int /* vehicle id */, HeartbeatTimer*> _heartbeatTimers;
};
typedef QSharedPointer<LinkInterface> SharedLinkInterfacePointer;
......
......@@ -1011,5 +1011,5 @@ void LinkManager::_heartbeatReceived(LinkInterface* link, int vehicleId, int com
Q_UNUSED(vehicleFirmwareType);
Q_UNUSED(vehicleType);
link->timerStart(vehicleId);
link->startHeartbeatTimer(vehicleId);
}
......@@ -59,10 +59,12 @@ Item {
}
}
Component.onCompleted: priorityLinkSelector.updatelinkSelectionMenu()
Connections {
target: QGroundControl.multiVehicleManager
onActiveVehicleChanged: priorityLinkSelector.updatelinkSelectionMenu()
}
Connections {
target: _activeVehicle
onLinkNamesChanged: priorityLinkSelector.updatelinkSelectionMenu()
......
Markdown is supported
0% or
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment