diff --git a/src/ADSB/ADSBVehicle.h b/src/ADSB/ADSBVehicle.h index b51fa157a5d1005713345370e1949cf08443b1dc..c84c4fad81aeded19b774dd39faa3b1bf96cb543 100644 --- a/src/ADSB/ADSBVehicle.h +++ b/src/ADSB/ADSBVehicle.h @@ -67,12 +67,6 @@ signals: void alertChanged (); 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; QString _callsign; QGeoCoordinate _coordinate; @@ -81,6 +75,9 @@ private: bool _alert; 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) diff --git a/src/MissionManager/MissionController.cc b/src/MissionManager/MissionController.cc index 4e06ce00a568a9965a33ed4a8eb4de99704cf174..27182c2cf7669770d5f1bbe0534f538a055dbe26 100644 --- a/src/MissionManager/MissionController.cc +++ b/src/MissionManager/MissionController.cc @@ -1217,8 +1217,7 @@ void MissionController::_recalcWaypointLines(void) bool foundRTL = false; bool homePositionValid = _settingsItem->coordinate().isValid(); bool roiActive = false; - bool setupIncompleteItem = false; - VisualMissionItem* startVIForIncompleteItem = nullptr; + bool previousItemIsIncomplete = false; qCDebug(MissionControllerLog) << "_recalcWaypointLines homePositionValid" << homePositionValid; @@ -1227,6 +1226,10 @@ void MissionController::_recalcWaypointLines(void) _linesTable.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(); _directionArrows.beginReset(); _incompleteComplexItemLines.beginReset(); @@ -1281,22 +1284,17 @@ void MissionController::_recalcWaypointLines(void) 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. - // For example a Survey which has no polygon set for it yet. For these cases we draw incomplete segment lines so that there - // isn't a hole in the flight path lines. + // They may not yet have valid entry/exit coordinates associated with them while in the incomplete state. + // For examples a Survey item which has no polygon set yet. 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 { - 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)) { bool addDirectionArrow = false; if (i != 1) { diff --git a/src/MissionManager/PlanManager.cc b/src/MissionManager/PlanManager.cc index 3ab585b6f5b4a3b37de152490eef289507c572c9..6a08a88228f51b4e5cf13d486d7fd4e9c5d798b1 100644 --- a/src/MissionManager/PlanManager.cc +++ b/src/MissionManager/PlanManager.cc @@ -541,8 +541,10 @@ void PlanManager::_handleMissionRequest(const mavlink_message_t& message, bool m MissionItem* item = _writeMissionItems[missionRequestSeq]; 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; - 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(), qgcApp()->toolbox()->mavlinkProtocol()->getComponentId(), _dedicatedLink->mavlinkChannel(), diff --git a/src/MissionManager/TransectStyleComplexItem.cc b/src/MissionManager/TransectStyleComplexItem.cc index e796d9bb1f4d6ac5c46c840158f73a722bfe8d0e..727d0bc4857cef213c8918a0bc22fd455fb88f9b 100644 --- a/src/MissionManager/TransectStyleComplexItem.cc +++ b/src/MissionManager/TransectStyleComplexItem.cc @@ -748,6 +748,9 @@ int TransectStyleComplexItem::lastSequenceNumber(void) const if (_loadedMissionItems.count()) { // We have stored mission items, just use those 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 { // We have to determine from transects int itemCount = 0;