Unverified Commit 8b96abb5 authored by Don Gagne's avatar Don Gagne Committed by GitHub

Merge pull request #8598 from DonLakeFlyer/StableCherryPick

Stable cherry pick
parents 67f93cee 9e38788a
...@@ -67,12 +67,6 @@ signals: ...@@ -67,12 +67,6 @@ signals:
void alertChanged (); void alertChanged ();
private: private:
/* According with Thomas Voß, we should be using 2 minutes for the time being
static constexpr qint64 expirationTimeoutMs = 5000; ///< timeout with no update in ms after which the vehicle is removed.
///< AirMap sends updates for each vehicle every second.
*/
static constexpr qint64 expirationTimeoutMs = 120000;
uint32_t _icaoAddress; uint32_t _icaoAddress;
QString _callsign; QString _callsign;
QGeoCoordinate _coordinate; QGeoCoordinate _coordinate;
...@@ -81,6 +75,9 @@ private: ...@@ -81,6 +75,9 @@ private:
bool _alert; bool _alert;
QElapsedTimer _lastUpdateTimer; QElapsedTimer _lastUpdateTimer;
static constexpr qint64 expirationTimeoutMs = 120000; ///< timeout with no update in ms after which the vehicle is removed.
///< AirMap sends updates for each vehicle every second.
}; };
Q_DECLARE_METATYPE(ADSBVehicle::VehicleInfo_t) Q_DECLARE_METATYPE(ADSBVehicle::VehicleInfo_t)
......
...@@ -1217,8 +1217,7 @@ void MissionController::_recalcWaypointLines(void) ...@@ -1217,8 +1217,7 @@ void MissionController::_recalcWaypointLines(void)
bool foundRTL = false; bool foundRTL = false;
bool homePositionValid = _settingsItem->coordinate().isValid(); bool homePositionValid = _settingsItem->coordinate().isValid();
bool roiActive = false; bool roiActive = false;
bool setupIncompleteItem = false; bool previousItemIsIncomplete = false;
VisualMissionItem* startVIForIncompleteItem = nullptr;
qCDebug(MissionControllerLog) << "_recalcWaypointLines homePositionValid" << homePositionValid; qCDebug(MissionControllerLog) << "_recalcWaypointLines homePositionValid" << homePositionValid;
...@@ -1227,6 +1226,10 @@ void MissionController::_recalcWaypointLines(void) ...@@ -1227,6 +1226,10 @@ void MissionController::_recalcWaypointLines(void)
_linesTable.clear(); _linesTable.clear();
_waypointPath.clear(); _waypointPath.clear();
// Note: Although visual support _incompleteComplexItemLines is still in the codebase. The support for populating the list is not.
// This is due to the initial implementation being buggy and incomplete with respect to correctly generating the line set.
// So for now we leave the code for displaying them in, but none are ever added until we have time to implement the correct support.
_waypointLines.beginReset(); _waypointLines.beginReset();
_directionArrows.beginReset(); _directionArrows.beginReset();
_incompleteComplexItemLines.beginReset(); _incompleteComplexItemLines.beginReset();
...@@ -1281,22 +1284,17 @@ void MissionController::_recalcWaypointLines(void) ...@@ -1281,22 +1284,17 @@ void MissionController::_recalcWaypointLines(void)
if (visualItem->specifiesCoordinate() && !visualItem->isStandaloneCoordinate()) { if (visualItem->specifiesCoordinate() && !visualItem->isStandaloneCoordinate()) {
// Incomplete items are complex items which are waiting for the user to complete setup before there visuals can become valid. // Incomplete items are complex items which are waiting for the user to complete setup before there visuals can become valid.
// For example a Survey which has no polygon set for it yet. For these cases we draw incomplete segment lines so that there // They may not yet have valid entry/exit coordinates associated with them while in the incomplete state.
// isn't a hole in the flight path lines. // For examples a Survey item which has no polygon set yet.
if (complexItem && complexItem->isIncomplete()) { if (complexItem && complexItem->isIncomplete()) {
setupIncompleteItem = true; // We don't link lines from a valid item to an incomplete item
previousItemIsIncomplete = true;
} else if (previousItemIsIncomplete) {
// We also don't link lines from an incomplete item to a valid item.
previousItemIsIncomplete = false;
firstCoordinateNotFound = false;
lastCoordinateItemBeforeRTL = visualItem;
} else { } else {
if (setupIncompleteItem) {
VisualItemPair viPair(startVIForIncompleteItem, visualItem);
CoordinateVector* coordVector = _createCoordinateVectorWorker(viPair);
_incompleteComplexItemLines.append(coordVector);
startVIForIncompleteItem = nullptr;
setupIncompleteItem = false;
} else {
startVIForIncompleteItem = visualItem;
}
if (lastCoordinateItemBeforeRTL != _settingsItem || (homePositionValid && linkStartToHome)) { if (lastCoordinateItemBeforeRTL != _settingsItem || (homePositionValid && linkStartToHome)) {
bool addDirectionArrow = false; bool addDirectionArrow = false;
if (i != 1) { if (i != 1) {
......
...@@ -541,8 +541,10 @@ void PlanManager::_handleMissionRequest(const mavlink_message_t& message, bool m ...@@ -541,8 +541,10 @@ void PlanManager::_handleMissionRequest(const mavlink_message_t& message, bool m
MissionItem* item = _writeMissionItems[missionRequestSeq]; MissionItem* item = _writeMissionItems[missionRequestSeq];
qCDebug(PlanManagerLog) << QStringLiteral("_handleMissionRequest %1 sequenceNumber:command").arg(_planTypeString()) << missionRequestSeq << item->command(); qCDebug(PlanManagerLog) << QStringLiteral("_handleMissionRequest %1 sequenceNumber:command").arg(_planTypeString()) << missionRequestSeq << item->command();
// ArduPilot always expects to get MISSION_ITEM_INT if possible
bool forceMissionItemInt = (_vehicle->capabilityBits() & MAV_PROTOCOL_CAPABILITY_MISSION_INT) && _vehicle->apmFirmware();
mavlink_message_t messageOut; mavlink_message_t messageOut;
if (missionItemInt || _vehicle->apmFirmware() /* ArduPilot always expects to get MISSION_ITEM_INT no matter what */) { if (missionItemInt || forceMissionItemInt) {
mavlink_msg_mission_item_int_pack_chan(qgcApp()->toolbox()->mavlinkProtocol()->getSystemId(), mavlink_msg_mission_item_int_pack_chan(qgcApp()->toolbox()->mavlinkProtocol()->getSystemId(),
qgcApp()->toolbox()->mavlinkProtocol()->getComponentId(), qgcApp()->toolbox()->mavlinkProtocol()->getComponentId(),
_dedicatedLink->mavlinkChannel(), _dedicatedLink->mavlinkChannel(),
......
...@@ -748,6 +748,9 @@ int TransectStyleComplexItem::lastSequenceNumber(void) const ...@@ -748,6 +748,9 @@ int TransectStyleComplexItem::lastSequenceNumber(void) const
if (_loadedMissionItems.count()) { if (_loadedMissionItems.count()) {
// We have stored mission items, just use those // We have stored mission items, just use those
return _sequenceNumber + _loadedMissionItems.count() - 1; return _sequenceNumber + _loadedMissionItems.count() - 1;
} else if (_transects.count() == 0) {
// Polygon has not yet been set so we just return back a one item complex item for now
return _sequenceNumber;
} else { } else {
// We have to determine from transects // We have to determine from transects
int itemCount = 0; int itemCount = 0;
......
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