Browse Source

Better comm lost/regained text/speech

QGC4.4
DonLakeFlyer 7 years ago
parent
commit
39fc2fbcb6
  1. 90
      src/Vehicle/Vehicle.cc

90
src/Vehicle/Vehicle.cc

@ -2135,7 +2135,7 @@ void Vehicle::setFlightMode(const QString& flightMode)
QString Vehicle::priorityLinkName(void) const QString Vehicle::priorityLinkName(void) const
{ {
if (_priorityLink) { if (_priorityLink) {
return _priorityLink->getName(); return _priorityLink->getName();
} }
return "none"; return "none";
@ -2411,10 +2411,10 @@ void Vehicle::_sendQGCTimeToVehicle(void)
// Timestamp of the component clock since boot time in milliseconds (Not necessary). // Timestamp of the component clock since boot time in milliseconds (Not necessary).
cmd.time_boot_ms = 0; cmd.time_boot_ms = 0;
mavlink_msg_system_time_encode_chan(_mavlink->getSystemId(), mavlink_msg_system_time_encode_chan(_mavlink->getSystemId(),
_mavlink->getComponentId(), _mavlink->getComponentId(),
priorityLink()->mavlinkChannel(), priorityLink()->mavlinkChannel(),
&msg, &msg,
&cmd); &cmd);
sendMessageOnLink(priorityLink(), msg); sendMessageOnLink(priorityLink(), msg);
} }
@ -2488,12 +2488,15 @@ void Vehicle::_linkActiveChanged(LinkInterface *link, bool active, int vehicleID
emit linksPropertiesChanged(); emit linksPropertiesChanged();
bool communicationLost = false;
bool communicationRegained = false;
if (link == _priorityLink) { if (link == _priorityLink) {
if (active && _connectionLost) { if (active && _connectionLost) {
// communication to priority link regained // communication to priority link regained
_connectionLost = false; _connectionLost = false;
communicationRegained = true;
emit connectionLostChanged(false); 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()) { if (_priorityLink->highLatency()) {
_setMaxProtoVersion(100); _setMaxProtoVersion(100);
@ -2504,31 +2507,21 @@ void Vehicle::_linkActiveChanged(LinkInterface *link, bool active, int vehicleID
false, // No error shown if fails false, // No error shown if fails
1); // Request protocol version 1); // Request protocol version
} }
} else if (!active && !_connectionLost) { } else if (!active && !_connectionLost) {
// communication to priority link lost if (_connectionLostEnabled) {
qgcApp()->showMessage((tr("%1 communication to %2 link %3 lost")).arg(_vehicleIdSpeech()).arg((_links.count() > 1) ? "priority" : "").arg(link->getName())); _connectionLost = true;
communicationLost = true;
_updatePriorityLink(false /* updateActive */, true /* sendCommand */); _heardFrom = false;
_maxProtoVersion = 0;
if (link == _priorityLink) { emit connectionLostChanged(true);
_say(QString(tr("%1 communication lost")).arg(_vehicleIdSpeech()));
qgcApp()->showMessage((tr("%1 communication lost")).arg(_vehicleIdSpeech())); if (_autoDisconnect) {
// Reset link state
if (_connectionLostEnabled) { for (int i = 0; i < _links.length(); i++) {
_connectionLost = true; _mavlink->resetMetadataForLink(_links.at(i));
_heardFrom = false;
_maxProtoVersion = 0;
emit connectionLostChanged(true);
if (_autoDisconnect) {
// Reset link state
for (int i = 0; i < _links.length(); i++) {
_mavlink->resetMetadataForLink(_links.at(i));
}
disconnectInactiveVehicle();
} }
disconnectInactiveVehicle();
} }
} }
} }
@ -2536,6 +2529,31 @@ void Vehicle::_linkActiveChanged(LinkInterface *link, bool active, int vehicleID
qgcApp()->showMessage((tr("%1 communication to auxiliary link %2 %3")).arg(_vehicleIdSpeech()).arg(link->getName()).arg(active ? "regained" : "lost")); qgcApp()->showMessage((tr("%1 communication to auxiliary link %2 %3")).arg(_vehicleIdSpeech()).arg(link->getName()).arg(active ? "regained" : "lost"));
_updatePriorityLink(false /* updateActive */, true /* sendCommand */); _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) void Vehicle::_say(const QString& text)
@ -2780,13 +2798,13 @@ void Vehicle::guidedModeOrbit(const QGeoCoordinate& centerCoord, double radius,
lat, lon, alt); lat, lon, alt);
} else { } else {
sendMavCommand(defaultComponentId(), sendMavCommand(defaultComponentId(),
MAV_CMD_DO_ORBIT, MAV_CMD_DO_ORBIT,
true, // show error if fails true, // show error if fails
radius, radius,
qQNaN(), // Use default velocity qQNaN(), // Use default velocity
0, // Vehicle points to center 0, // Vehicle points to center
qQNaN(), // reserved qQNaN(), // reserved
lat, lon, alt); lat, lon, alt);
} }
} }

Loading…
Cancel
Save