diff --git a/QGCSetup.pri b/QGCSetup.pri index b4d7dbafca4f2ef2e9f3a5a775f4c796e3586a74..753613ff12bcffc77b1ae1666dae6bb517faf553 100644 --- a/QGCSetup.pri +++ b/QGCSetup.pri @@ -63,7 +63,9 @@ WindowsBuild { ReleaseBuild: DLL_QT_DEBUGCHAR = "" COPY_FILE_LIST = \ $$BASEDIR\\libs\\lib\\sdl2\\msvc\\lib\\x86\\SDL2.dll \ - $$BASEDIR\\deploy\\libeay32.dll + $$BASEDIR\\deploy\\libeay32.dll \ + $$BASEDIR_WIN\\deploy\\libssl32.dll \ + $$BASEDIR_WIN\\deploy\\ssleay32.dll for(COPY_FILE, COPY_FILE_LIST) { QMAKE_POST_LINK += $$escape_expand(\\n) $$QMAKE_COPY \"$$COPY_FILE\" \"$$DESTDIR_WIN\" diff --git a/deploy/libeay32.dll b/deploy/libeay32.dll index fadf8b2d519836e7e03bfdbdadbba9d391829b62..ffd92b884dc051c9bf4cd398e1c8db6abe845ce0 100644 Binary files a/deploy/libeay32.dll and b/deploy/libeay32.dll differ diff --git a/deploy/libssl32.dll b/deploy/libssl32.dll new file mode 100644 index 0000000000000000000000000000000000000000..0592244daa24a2c67e8ad4fb8077c2c0b56b1eb5 Binary files /dev/null and b/deploy/libssl32.dll differ diff --git a/deploy/ssleay32.dll b/deploy/ssleay32.dll new file mode 100644 index 0000000000000000000000000000000000000000..0592244daa24a2c67e8ad4fb8077c2c0b56b1eb5 Binary files /dev/null and b/deploy/ssleay32.dll differ diff --git a/src/AnalyzeView/GeoTagController.cc b/src/AnalyzeView/GeoTagController.cc index 2db65e718c9c80b439a229d00c54ddf80666e5ee..3f0627deb204b1ce6f5e775e6b62cf435131e488 100644 --- a/src/AnalyzeView/GeoTagController.cc +++ b/src/AnalyzeView/GeoTagController.cc @@ -70,8 +70,7 @@ void GeoTagController::startTagging(void) QDir imageDirectory = QDir(_worker.imageDirectory()); if(!imageDirectory.exists()) { - _errorMessage = tr("Cannot find the image directory"); - emit errorMessageChanged(_errorMessage); + _setErrorMessage(tr("Cannot find the image directory")); return; } if(_worker.saveDirectory() == "") { @@ -83,23 +82,20 @@ void GeoTagController::startTagging(void) msgBox.setWindowModality(Qt::ApplicationModal); msgBox.addButton(tr("Replace"), QMessageBox::ActionRole); if (msgBox.exec() == QMessageBox::Cancel) { - _errorMessage = tr("Images have already been tagged"); - emit errorMessageChanged(_errorMessage); + _setErrorMessage(tr("Images have already been tagged")); return; } QDir oldTaggedFolder = QDir(_worker.imageDirectory() + "/TAGGED"); oldTaggedFolder.removeRecursively(); if(!imageDirectory.mkdir(_worker.imageDirectory() + "/TAGGED")) { - _errorMessage = tr("Couldn't replace the previously tagged images"); - emit errorMessageChanged(_errorMessage); + _setErrorMessage(tr("Couldn't replace the previously tagged images")); return; } } } else { QDir saveDirectory = QDir(_worker.saveDirectory()); if(!saveDirectory.exists()) { - _errorMessage = tr("Cannot find the save directory"); - emit errorMessageChanged(_errorMessage); + _setErrorMessage(tr("Cannot find the save directory")); return; } saveDirectory.setFilter(QDir::Files | QDir::Readable | QDir::NoSymLinks | QDir::Writable); @@ -115,15 +111,13 @@ void GeoTagController::startTagging(void) msgBox.setWindowModality(Qt::ApplicationModal); msgBox.addButton(tr("Replace"), QMessageBox::ActionRole); if (msgBox.exec() == QMessageBox::Cancel) { - _errorMessage = tr("Save folder not empty"); - emit errorMessageChanged(_errorMessage); + _setErrorMessage(tr("Save folder not empty")); return; } foreach(QString dirFile, imageList) { if(!saveDirectory.remove(dirFile)) { - _errorMessage = tr("Couldn't replace the existing images"); - emit errorMessageChanged(_errorMessage); + _setErrorMessage(tr("Couldn't replace the existing images")); return; } } @@ -144,6 +138,13 @@ void GeoTagController::_workerError(QString errorMessage) emit errorMessageChanged(errorMessage); } + +void GeoTagController::_setErrorMessage(const QString& error) +{ + _errorMessage = error; + emit errorMessageChanged(error); +} + GeoTagWorker::GeoTagWorker(void) : _cancel(false) , _logFile("") @@ -210,9 +211,10 @@ void GeoTagWorker::run(void) // Instantiate appropriate parser _triggerList.clear(); bool parseComplete = false; - if(isULog) { + QString errorString; + if (isULog) { ULogParser parser; - parseComplete = parser.getTagsFromLog(log, _triggerList); + parseComplete = parser.getTagsFromLog(log, _triggerList, errorString); } else { PX4LogParser parser; @@ -227,7 +229,8 @@ void GeoTagWorker::run(void) return; } else { qCDebug(GeotaggingLog) << "Log parsing failed"; - emit error(tr("Log parsing failed - tagging cancelled")); + errorString = tr("%1 - tagging cancelled").arg(errorString.isEmpty() ? tr("Log parsing failed") : errorString); + emit error(errorString); return; } } diff --git a/src/AnalyzeView/GeoTagController.h b/src/AnalyzeView/GeoTagController.h index aee58f6dd68063514c8744bd6aa82f9ab2b4b2ad..f3955d2712351a8501e72116b5a3bd2728030438 100644 --- a/src/AnalyzeView/GeoTagController.h +++ b/src/AnalyzeView/GeoTagController.h @@ -117,8 +117,9 @@ signals: void errorMessageChanged (QString errorMessage); private slots: - void _workerProgressChanged(double progress); - void _workerError(QString errorMsg); + void _workerProgressChanged (double progress); + void _workerError (QString errorMsg); + void _setErrorMessage (const QString& error); private: QString _errorMessage; diff --git a/src/AnalyzeView/GeoTagPage.qml b/src/AnalyzeView/GeoTagPage.qml index d4f4386f074ddfd71c5a2526bf3c3349e73b7bff..c64147e401dc9178f2ab4024ee27cda29f3365d9 100644 --- a/src/AnalyzeView/GeoTagPage.qml +++ b/src/AnalyzeView/GeoTagPage.qml @@ -124,8 +124,9 @@ AnalyzePage { } QGCButton { - text: geoController.inProgress ? qsTr("Cancel Tagging") : qsTr("Start Tagging") - width: ScreenTools.defaultFontPixelWidth * 30 + text: geoController.inProgress ? qsTr("Cancel Tagging") : qsTr("Start Tagging") + width: ScreenTools.defaultFontPixelWidth * 30 + onClicked: { if (geoController.inProgress) { geoController.cancelTagging() diff --git a/src/AnalyzeView/LogDownloadController.cc b/src/AnalyzeView/LogDownloadController.cc index 133a55671663451192a5d4ad5481485970413585..3eeb02ada316fda8682e1480f84485757fdff64d 100644 --- a/src/AnalyzeView/LogDownloadController.cc +++ b/src/AnalyzeView/LogDownloadController.cc @@ -321,7 +321,7 @@ LogDownloadController::_logData(UASInterface* uas, uint32_t ofs, uint16_t id, ui if(ofs <= _downloadData->entry->size()) { const uint32_t chunk = ofs / kChunkSize; if (chunk != _downloadData->current_chunk) { - qWarning() << "Ignored packet for out of order chunk" << chunk; + qWarning() << "Ignored packet for out of order chunk actual:expected" << chunk << _downloadData->current_chunk; return; } const uint16_t bin = (ofs - chunk*kChunkSize) / MAVLINK_MSG_LOG_DATA_FIELD_DATA_LEN; diff --git a/src/AnalyzeView/LogDownloadPage.qml b/src/AnalyzeView/LogDownloadPage.qml index f2b684d630b7da0669ef8367c57394ded5fc4bff..4b3d35ad594043f02f96a9e81c1a22c46480347e 100644 --- a/src/AnalyzeView/LogDownloadPage.qml +++ b/src/AnalyzeView/LogDownloadPage.qml @@ -155,7 +155,7 @@ AnalyzePage { fileDialog.qgcView = logDownloadPage fileDialog.title = qsTr("Select save directory") fileDialog.selectExisting = true - fileDialog.folder = QGroundControl.settingsManager.appSettings.telemetrySavePath + fileDialog.folder = QGroundControl.settingsManager.appSettings.logSavePath fileDialog.selectFolder = true fileDialog.openForLoad() } diff --git a/src/AnalyzeView/ULogParser.cc b/src/AnalyzeView/ULogParser.cc index 806dfd052e1733babdd6f4b7cc6c60c56f4233ca..d6b7f365eefee50535fe47c5b8938ee920c77cc4 100644 --- a/src/AnalyzeView/ULogParser.cc +++ b/src/AnalyzeView/ULogParser.cc @@ -86,11 +86,13 @@ bool ULogParser::parseFieldFormat(QString& fields) return false; } -bool ULogParser::getTagsFromLog(QByteArray& log, QList& cameraFeedback) +bool ULogParser::getTagsFromLog(QByteArray& log, QList& cameraFeedback, QString& errorMessage) { + errorMessage.clear(); + //verify it's an ULog file if(!log.contains(_ULogMagic)) { - qWarning() << "Could not detect ULog file header magic"; + errorMessage = tr("Could not detect ULog file header magic"); return false; } @@ -175,7 +177,7 @@ bool ULogParser::getTagsFromLog(QByteArray& log, QList #include +#include #include "GeoTagController.h" @@ -10,10 +11,14 @@ class ULogParser { + Q_DECLARE_TR_FUNCTIONS(ULogParser) + public: ULogParser(); ~ULogParser(); - bool getTagsFromLog(QByteArray& log, QList& cameraFeedback); + + /// @return true: failed, errorMessage set + bool getTagsFromLog(QByteArray& log, QList& cameraFeedback, QString& errorMessage); private: diff --git a/src/QtLocationPlugin/QGeoMapReplyQGC.cpp b/src/QtLocationPlugin/QGeoMapReplyQGC.cpp index 44ed968849ae6b0348810f69a3d9fa451ce9d63d..eaee21fc02da06db6a80ccc0cab858ffc2b27257 100644 --- a/src/QtLocationPlugin/QGeoMapReplyQGC.cpp +++ b/src/QtLocationPlugin/QGeoMapReplyQGC.cpp @@ -123,23 +123,23 @@ QGeoTiledMapReplyQGC::networkReplyFinished() } QByteArray a = _reply->readAll(); QString format = getQGCMapEngine()->urlFactory()->getImageFormat((UrlFactory::MapType)tileSpec().mapId(), a); - - // convert "a" to binary in case we have elevation data + //-- Test for a specialized, elevation data (not map tile) if ((UrlFactory::MapType)tileSpec().mapId() == UrlFactory::MapType::AirmapElevation) { - a = TerrainTile::serialize(a); - if (a.isEmpty()) { - emit aborted(); - return; + //-- Cache it if valid + if(!a.isEmpty()) { + getQGCMapEngine()->cacheTile(UrlFactory::MapType::AirmapElevation, tileSpec().x(), tileSpec().y(), tileSpec().zoom(), a, format); } - - } - setMapImageData(a); - if(!format.isEmpty()) { - setMapImageFormat(format); - getQGCMapEngine()->cacheTile((UrlFactory::MapType)tileSpec().mapId(), tileSpec().x(), tileSpec().y(), tileSpec().zoom(), a, format); + emit terrainDone(a, QNetworkReply::NoError); + } else { + //-- This is a map tile. Process and cache it if valid. + setMapImageData(a); + if(!format.isEmpty()) { + setMapImageFormat(format); + getQGCMapEngine()->cacheTile((UrlFactory::MapType)tileSpec().mapId(), tileSpec().x(), tileSpec().y(), tileSpec().zoom(), a, format); + } + setFinished(true); } - setFinished(true); _clearReply(); } @@ -151,11 +151,17 @@ QGeoTiledMapReplyQGC::networkReplyError(QNetworkReply::NetworkError error) if (!_reply) { return; } - if (error != QNetworkReply::OperationCanceledError) { - qWarning() << "Fetch tile error:" << _reply->errorString(); - setError(QGeoTiledMapReply::CommunicationError, _reply->errorString()); + //-- Test for a specialized, elevation data (not map tile) + if ((UrlFactory::MapType)tileSpec().mapId() == UrlFactory::MapType::AirmapElevation) { + emit terrainDone(QByteArray(), error); + } else { + //-- Regular map tile + if (error != QNetworkReply::OperationCanceledError) { + qWarning() << "Fetch tile error:" << _reply->errorString(); + setError(QGeoTiledMapReply::CommunicationError, _reply->errorString()); + } + setFinished(true); } - setFinished(true); _clearReply(); } @@ -164,8 +170,12 @@ void QGeoTiledMapReplyQGC::cacheError(QGCMapTask::TaskType type, QString /*errorString*/) { if(!getQGCMapEngine()->isInternetActive()) { - setError(QGeoTiledMapReply::CommunicationError, "Network not available"); - setFinished(true); + if ((UrlFactory::MapType)tileSpec().mapId() == UrlFactory::MapType::AirmapElevation) { + emit terrainDone(QByteArray(), QNetworkReply::NetworkSessionFailedError); + } else { + setError(QGeoTiledMapReply::CommunicationError, "Network not available"); + setFinished(true); + } } else { if(type != QGCMapTask::taskFetchTile) { qWarning() << "QGeoTiledMapReplyQGC::cacheError() for wrong task"; @@ -196,10 +206,16 @@ QGeoTiledMapReplyQGC::cacheError(QGCMapTask::TaskType type, QString /*errorStrin void QGeoTiledMapReplyQGC::cacheReply(QGCCacheTile* tile) { - setMapImageData(tile->img()); - setMapImageFormat(tile->format()); - setFinished(true); - setCached(true); + //-- Test for a specialized, elevation data (not map tile) + if ((UrlFactory::MapType)tileSpec().mapId() == UrlFactory::MapType::AirmapElevation) { + emit terrainDone(tile->img(), QNetworkReply::NoError); + } else { + //-- Regular map tile + setMapImageData(tile->img()); + setMapImageFormat(tile->format()); + setFinished(true); + setCached(true); + } tile->deleteLater(); } diff --git a/src/QtLocationPlugin/QGeoMapReplyQGC.h b/src/QtLocationPlugin/QGeoMapReplyQGC.h index dcde1f0b3b7fe8984b820038aa9fb898d129b6ff..9f5e812f62e7ed3062da4ce1cc82de0b96bd8803 100644 --- a/src/QtLocationPlugin/QGeoMapReplyQGC.h +++ b/src/QtLocationPlugin/QGeoMapReplyQGC.h @@ -61,6 +61,9 @@ public: ~QGeoTiledMapReplyQGC(); void abort(); +signals: + void terrainDone (QByteArray responseBytes, QNetworkReply::NetworkError error); + private slots: void networkReplyFinished (); void networkReplyError (QNetworkReply::NetworkError error); diff --git a/src/Terrain/TerrainQuery.cc b/src/Terrain/TerrainQuery.cc index b1d7030b0fe72e5965414f5b46cf422423b2fa5c..662501cf41bc79f64babdd1bee086eb2137d2104 100644 --- a/src/Terrain/TerrainQuery.cc +++ b/src/Terrain/TerrainQuery.cc @@ -374,8 +374,7 @@ bool TerrainTileManager::_getAltitudesForCoordinates(const QList spec.setZoom(1); spec.setMapId(UrlFactory::AirmapElevation); QGeoTiledMapReplyQGC* reply = new QGeoTiledMapReplyQGC(&_networkManager, request, spec); - connect(reply, &QGeoTiledMapReplyQGC::finished, this, &TerrainTileManager::_fetchedTile); - connect(reply, &QGeoTiledMapReplyQGC::aborted, this, &TerrainTileManager::_fetchedTile); + connect(reply, &QGeoTiledMapReplyQGC::terrainDone, this, &TerrainTileManager::_terrainDone); _state = State::Downloading; } _tilesMutex.unlock(); @@ -406,7 +405,7 @@ void TerrainTileManager::_tileFailed(void) _requestQueue.clear(); } -void TerrainTileManager::_fetchedTile() +void TerrainTileManager::_terrainDone(QByteArray responseBytes, QNetworkReply::NetworkError error) { QGeoTiledMapReplyQGC* reply = qobject_cast(QObject::sender()); _state = State::Idle; @@ -421,26 +420,19 @@ void TerrainTileManager::_fetchedTile() QString hash = QGCMapEngine::getTileHash(UrlFactory::AirmapElevation, spec.x(), spec.y(), spec.zoom()); // handle potential errors - if (reply->error() != QGeoTiledMapReply::NoError) { - if (reply->error() == QGeoTiledMapReply::CommunicationError) { - qCDebug(TerrainQueryLog) << "Elevation tile fetching returned communication error. " << reply->errorString(); - } else { - qCDebug(TerrainQueryLog) << "Elevation tile fetching returned error. " << reply->errorString(); - } + if (error != QNetworkReply::NoError) { + qCDebug(TerrainQueryLog) << "Elevation tile fetching returned error (" << error << ")"; _tileFailed(); reply->deleteLater(); return; } - if (!reply->isFinished()) { - qCDebug(TerrainQueryLog) << "Error in fetching elevation tile. Not finished. " << reply->errorString(); + if (responseBytes.isEmpty()) { + qCDebug(TerrainQueryLog) << "Error in fetching elevation tile. Empty response."; _tileFailed(); reply->deleteLater(); return; } - // parse received data and insert into hash table - QByteArray responseBytes = reply->mapImageData(); - qWarning() << "Received some bytes of terrain data: " << responseBytes.size(); TerrainTile* terrainTile = new TerrainTile(responseBytes); diff --git a/src/Terrain/TerrainQuery.h b/src/Terrain/TerrainQuery.h index 438a79179f54a72732300a8ba25dd708084fb088..01c7592c070b4bda50076980b48df3ed195ab527 100644 --- a/src/Terrain/TerrainQuery.h +++ b/src/Terrain/TerrainQuery.h @@ -62,20 +62,20 @@ public: TerrainAirMapQuery(QObject* parent = NULL); // Overrides from TerrainQueryInterface - void requestCoordinateHeights(const QList& coordinates) final; - void requestPathHeights(const QGeoCoordinate& fromCoord, const QGeoCoordinate& toCoord) final; - void requestCarpetHeights(const QGeoCoordinate& swCoord, const QGeoCoordinate& neCoord, bool statsOnly) final; + void requestCoordinateHeights (const QList& coordinates) final; + void requestPathHeights (const QGeoCoordinate& fromCoord, const QGeoCoordinate& toCoord) final; + void requestCarpetHeights (const QGeoCoordinate& swCoord, const QGeoCoordinate& neCoord, bool statsOnly) final; private slots: - void _requestError(QNetworkReply::NetworkError code); - void _requestFinished(void); + void _requestError (QNetworkReply::NetworkError code); + void _requestFinished (); private: - void _sendQuery (const QString& path, const QUrlQuery& urlQuery); - void _requestFailed (void); - void _parseCoordinateData (const QJsonValue& coordinateJson); - void _parsePathData (const QJsonValue& pathJson); - void _parseCarpetData (const QJsonValue& carpetJson); + void _sendQuery (const QString& path, const QUrlQuery& urlQuery); + void _requestFailed (void); + void _parseCoordinateData (const QJsonValue& coordinateJson); + void _parsePathData (const QJsonValue& pathJson); + void _parseCarpetData (const QJsonValue& carpetJson); enum QueryMode { QueryModeCoordinates, @@ -117,7 +117,7 @@ public: void addPathQuery (TerrainOfflineAirMapQuery* terrainQueryInterface, const QGeoCoordinate& startPoint, const QGeoCoordinate& endPoint); private slots: - void _fetchedTile (void); /// slot to handle fetched elevation tiles + void _terrainDone (QByteArray responseBytes, QNetworkReply::NetworkError error); private: enum class State { diff --git a/src/TerrainTile.cc b/src/TerrainTile.cc index e4b06b05ea643ab65a5d041a8a61807061d3b7ec..9c17ed24a231adff25d8c780acd537d72cf2e715 100644 --- a/src/TerrainTile.cc +++ b/src/TerrainTile.cc @@ -56,21 +56,57 @@ TerrainTile::TerrainTile(QByteArray byteArray) QDataStream stream(byteArray); float lat,lon; - stream >> lat - >> lon; + if (stream.atEnd()) { + qWarning() << "Terrain tile binary data does not contain all data"; + return; + } + stream >> lat; + if (stream.atEnd()) { + qWarning() << "Terrain tile binary data does not contain all data"; + return; + } + stream >> lon; _southWest.setLatitude(lat); _southWest.setLongitude(lon); - stream >> lat - >> lon; + + if (stream.atEnd()) { + qWarning() << "Terrain tile binary data does not contain all data"; + return; + } + stream >> lat; + if (stream.atEnd()) { + qWarning() << "Terrain tile binary data does not contain all data"; + return; + } + stream >> lon; _northEast.setLatitude(lat); _northEast.setLongitude(lon); - - stream >> _minElevation - >> _maxElevation - >> _avgElevation - >> _gridSizeLat - >> _gridSizeLon; + if (stream.atEnd()) { + qWarning() << "Terrain tile binary data does not contain all data"; + return; + } + stream >> _minElevation; + if (stream.atEnd()) { + qWarning() << "Terrain tile binary data does not contain all data"; + return; + } + stream >> _maxElevation; + if (stream.atEnd()) { + qWarning() << "Terrain tile binary data does not contain all data"; + return; + } + stream >> _avgElevation; + if (stream.atEnd()) { + qWarning() << "Terrain tile binary data does not contain all data"; + return; + } + stream >> _gridSizeLat; + if (stream.atEnd()) { + qWarning() << "Terrain tile binary data does not contain all data"; + return; + } + stream >> _gridSizeLon; qCDebug(TerrainTileLog) << "Loading terrain tile: " << _southWest << " - " << _northEast; qCDebug(TerrainTileLog) << "min:max:avg:sizeLat:sizeLon" << _minElevation << _maxElevation << _avgElevation << _gridSizeLat << _gridSizeLon; diff --git a/src/Vehicle/Vehicle.cc b/src/Vehicle/Vehicle.cc index ac98acd514e90635bb4dc8a301f79b10b71e6243..cf9f341b0464a79479836650c93af91494bd31cf 100644 --- a/src/Vehicle/Vehicle.cc +++ b/src/Vehicle/Vehicle.cc @@ -870,11 +870,11 @@ void Vehicle::_handleGpsRawInt(mavlink_message_t& message) if (gpsRawInt.fix_type >= GPS_FIX_TYPE_3D_FIX) { if (!_globalPositionIntMessageAvailable) { - //-- Set these here and emit a single signal instead of 3 for the same variable (_coordinate) - _coordinate.setLatitude(gpsRawInt.lat / (double)1E7); - _coordinate.setLongitude(gpsRawInt.lon / (double)1E7); - _coordinate.setAltitude(gpsRawInt.alt / 1000.0); - emit coordinateChanged(_coordinate); + QGeoCoordinate newPosition(gpsRawInt.lat / (double)1E7, gpsRawInt.lon / (double)1E7, gpsRawInt.alt / 1000.0); + if (newPosition != _coordinate) { + _coordinate = newPosition; + emit coordinateChanged(_coordinate); + } _altitudeAMSLFact.setRawValue(gpsRawInt.alt / 1000.0); } } @@ -903,11 +903,11 @@ void Vehicle::_handleGlobalPositionInt(mavlink_message_t& message) } _globalPositionIntMessageAvailable = true; - //-- Set these here and emit a single signal instead of 3 for the same variable (_coordinate) - _coordinate.setLatitude(globalPositionInt.lat / (double)1E7); - _coordinate.setLongitude(globalPositionInt.lon / (double)1E7); - _coordinate.setAltitude(globalPositionInt.alt / 1000.0); - emit coordinateChanged(_coordinate); + QGeoCoordinate newPosition(globalPositionInt.lat / (double)1E7, globalPositionInt.lon / (double)1E7, globalPositionInt.alt / 1000.0); + if (newPosition != _coordinate) { + _coordinate = newPosition; + emit coordinateChanged(_coordinate); + } } void Vehicle::_handleHighLatency2(mavlink_message_t& message) diff --git a/src/VideoStreaming/VideoReceiver.cc b/src/VideoStreaming/VideoReceiver.cc index 7f46d85650258331bfd533f0c89ed9d4e2d68e2c..633688e8eca898516feb206ea08e69601cb1bf22 100644 --- a/src/VideoStreaming/VideoReceiver.cc +++ b/src/VideoStreaming/VideoReceiver.cc @@ -674,6 +674,14 @@ VideoReceiver::startRecording(const QString &videoFile) gst_element_sync_state_with_parent(_sink->mux); gst_element_sync_state_with_parent(_sink->filesink); + // Install a probe on the recording branch to drop buffers until we hit our first keyframe + // When we hit our first keyframe, we can offset the timestamps appropriately according to the first keyframe time + // This will ensure the first frame is a keyframe at t=0, and decoding can begin immediately on playback + GstPad* probepad = gst_element_get_static_pad(_sink->queue, "src"); + gst_pad_add_probe(probepad, (GstPadProbeType)(GST_PAD_PROBE_TYPE_BUFFER /* | GST_PAD_PROBE_TYPE_BLOCK */), _keyframeWatch, this, NULL); // to drop the buffer or to block the buffer? + gst_object_unref(probepad); + + // Link the recording branch to the pipeline GstPad* sinkpad = gst_element_get_static_pad(_sink->queue, "sink"); gst_pad_link(_sink->teepad, sinkpad); gst_object_unref(sinkpad); @@ -802,6 +810,33 @@ VideoReceiver::_unlinkCallBack(GstPad* pad, GstPadProbeInfo* info, gpointer user } #endif +//----------------------------------------------------------------------------- +#if defined(QGC_GST_STREAMING) +GstPadProbeReturn +VideoReceiver::_keyframeWatch(GstPad* pad, GstPadProbeInfo* info, gpointer user_data) +{ + Q_UNUSED(pad); + if(info != NULL && user_data != NULL) { + GstBuffer* buf = gst_pad_probe_info_get_buffer(info); + if(GST_BUFFER_FLAG_IS_SET(buf, GST_BUFFER_FLAG_DELTA_UNIT)) { // wait for a keyframe + return GST_PAD_PROBE_DROP; + } else { + VideoReceiver* pThis = (VideoReceiver*)user_data; + // reset the clock + GstClock* clock = gst_pipeline_get_clock(GST_PIPELINE(pThis->_pipeline)); + GstClockTime time = gst_clock_get_time(clock); + gst_object_unref(clock); + gst_element_set_base_time(pThis->_pipeline, time); // offset pipeline timestamps to start at zero again + buf->dts = 0; // The offset will not apply to this current buffer, our first frame, timestamp is zero + buf->pts = 0; + qCDebug(VideoReceiverLog) << "Got keyframe, stop dropping buffers"; + } + } + + return GST_PAD_PROBE_REMOVE; +} +#endif + //----------------------------------------------------------------------------- void VideoReceiver::_updateTimer() diff --git a/src/VideoStreaming/VideoReceiver.h b/src/VideoStreaming/VideoReceiver.h index 843abdf144ea6b0d3e18529ea9abfbd06df653cb..76aa3044cf17f4f47399703e6b2f79cd3f2fddc4 100644 --- a/src/VideoStreaming/VideoReceiver.h +++ b/src/VideoStreaming/VideoReceiver.h @@ -119,6 +119,7 @@ private: static gboolean _onBusMessage (GstBus* bus, GstMessage* message, gpointer user_data); static GstPadProbeReturn _unlinkCallBack (GstPad* pad, GstPadProbeInfo* info, gpointer user_data); + static GstPadProbeReturn _keyframeWatch (GstPad* pad, GstPadProbeInfo* info, gpointer user_data); void _detachRecordingBranch (GstPadProbeInfo* info); void _shutdownRecordingBranch(); void _shutdownPipeline (); diff --git a/src/ViewWidgets/CustomCommandWidget.qml b/src/ViewWidgets/CustomCommandWidget.qml index e937aef5ee105664e42899e091a72c9a8ce64c83..4d4ee60d7688183ba315e772a6f0d9792cafd4d4 100644 --- a/src/ViewWidgets/CustomCommandWidget.qml +++ b/src/ViewWidgets/CustomCommandWidget.qml @@ -34,7 +34,7 @@ QGCView { "So make sure to test your changes thoroughly before using them in flight.

" + "

Click 'Load Custom Qml file' to provide your custom qml file.

" + "

Click 'Reset' to reset to none.

" + - "

Example usage: http://https://dev.qgroundcontrol.com/en/tools/custom_command_widget.html

" + "

Example usage: https://dev.qgroundcontrol.com/en/tools/custom_command_widget.html

" QGCPalette { id: qgcPal; colorGroupEnabled: enabled } @@ -87,15 +87,20 @@ QGCView { } } } - - QGCLabel { - id: textOutput + QGCFlickable { + id: container anchors.fill: loader - wrapMode: Text.WordWrap - textFormat: Text.RichText + contentHeight: textOutput.height + flickableDirection: QGCFlickable.VerticalFlick visible: !loader.visible + QGCLabel { + id: textOutput + width: container.width + wrapMode: Text.WordWrap + textFormat: Text.RichText + onLinkActivated: Qt.openUrlExternally(link) + } } - Row { id: buttonRow spacing: ScreenTools.defaultFontPixelWidth @@ -115,6 +120,7 @@ QGCView { onClicked: controller.clearQmlFile() } } + } - } + } } diff --git a/src/comm/BluetoothLink.cc b/src/comm/BluetoothLink.cc index f1b9cc46e83232564f1cadcd8185f37cd88aad13..b6e2009e59eb73bc1e3016b1ae687715f8d68ea0 100644 --- a/src/comm/BluetoothLink.cc +++ b/src/comm/BluetoothLink.cc @@ -75,30 +75,25 @@ QString BluetoothLink::getName() const void BluetoothLink::_writeBytes(const QByteArray bytes) { - if(_targetSocket) - { - if(_targetSocket->isWritable()) - { - if(_targetSocket->write(bytes) > 0) { - _logOutputDataRate(bytes.size(), QDateTime::currentMSecsSinceEpoch()); - } - else - qWarning() << "Bluetooth write error"; + if (_targetSocket) { + if(_targetSocket->write(bytes) > 0) { + _logOutputDataRate(bytes.size(), QDateTime::currentMSecsSinceEpoch()); + } else { + qWarning() << "Bluetooth write error"; } - else - qWarning() << "Bluetooth not writable error"; } } void BluetoothLink::readBytes() { - while (_targetSocket->bytesAvailable() > 0) - { - QByteArray datagram; - datagram.resize(_targetSocket->bytesAvailable()); - _targetSocket->read(datagram.data(), datagram.size()); - emit bytesReceived(this, datagram); - _logInputDataRate(datagram.length(), QDateTime::currentMSecsSinceEpoch()); + if (_targetSocket) { + while (_targetSocket->bytesAvailable() > 0) { + QByteArray datagram; + datagram.resize(_targetSocket->bytesAvailable()); + _targetSocket->read(datagram.data(), datagram.size()); + emit bytesReceived(this, datagram); + _logInputDataRate(datagram.length(), QDateTime::currentMSecsSinceEpoch()); + } } } @@ -114,7 +109,7 @@ void BluetoothLink::_disconnect(void) #endif if(_targetSocket) { - delete _targetSocket; + _targetSocket->deleteLater(); _targetSocket = NULL; emit disconnected(); } diff --git a/src/comm/SerialLink.cc b/src/comm/SerialLink.cc index 3ae34a3e99ed37f21fe33b9801644f2d8ec85f12..be016aca4b61fd1eec05f4fb7ffed38c2156e18f 100644 --- a/src/comm/SerialLink.cc +++ b/src/comm/SerialLink.cc @@ -57,10 +57,6 @@ void SerialLink::requestReset() SerialLink::~SerialLink() { _disconnect(); - if (_port) { - delete _port; - } - _port = NULL; } bool SerialLink::_isBootloader() @@ -92,6 +88,7 @@ void SerialLink::_writeBytes(const QByteArray data) _port->write(data); } else { // Error occurred + qWarning() << "Serial port not writeable"; _emitLinkError(tr("Could not send data - link %1 is disconnected!").arg(getName())); } } @@ -105,7 +102,7 @@ void SerialLink::_disconnect(void) { if (_port) { _port->close(); - delete _port; + _port->deleteLater(); _port = NULL; } @@ -199,7 +196,7 @@ bool SerialLink::_hardwareConnect(QSerialPort::SerialPortError& error, QString& } } - _port = new QSerialPort(_serialConfig->portName()); + _port = new QSerialPort(_serialConfig->portName(), this); QObject::connect(_port, static_cast(&QSerialPort::error), this, &SerialLink::linkError); @@ -261,12 +258,18 @@ bool SerialLink::_hardwareConnect(QSerialPort::SerialPortError& error, QString& void SerialLink::_readBytes(void) { - qint64 byteCount = _port->bytesAvailable(); - if (byteCount) { - QByteArray buffer; - buffer.resize(byteCount); - _port->read(buffer.data(), buffer.size()); - emit bytesReceived(this, buffer); + if (_port && _port->isOpen()) { + qint64 byteCount = _port->bytesAvailable(); + if (byteCount) { + QByteArray buffer; + buffer.resize(byteCount); + _port->read(buffer.data(), buffer.size()); + emit bytesReceived(this, buffer); + } + } else { + // Error occurred + qWarning() << "Serial port not readable"; + _emitLinkError(tr("Could not read data - link %1 is disconnected!").arg(getName())); } } diff --git a/src/comm/TCPLink.cc b/src/comm/TCPLink.cc index 5760fb755f6d0050e9a1a8a405d60660d83dd26e..d91cdb145d5b4ed9ff79092a22145264f46505d2 100644 --- a/src/comm/TCPLink.cc +++ b/src/comm/TCPLink.cc @@ -78,11 +78,11 @@ void TCPLink::_writeBytes(const QByteArray data) #ifdef TCPLINK_READWRITE_DEBUG _writeDebugBytes(data); #endif - if (!_socket) - return; - _socket->write(data); - _logOutputDataRate(data.size(), QDateTime::currentMSecsSinceEpoch()); + if (_socket) { + _socket->write(data); + _logOutputDataRate(data.size(), QDateTime::currentMSecsSinceEpoch()); + } } /** @@ -93,17 +93,19 @@ void TCPLink::_writeBytes(const QByteArray data) **/ void TCPLink::readBytes() { - qint64 byteCount = _socket->bytesAvailable(); - if (byteCount) - { - QByteArray buffer; - buffer.resize(byteCount); - _socket->read(buffer.data(), buffer.size()); - emit bytesReceived(this, buffer); - _logInputDataRate(byteCount, QDateTime::currentMSecsSinceEpoch()); + if (_socket) { + qint64 byteCount = _socket->bytesAvailable(); + if (byteCount) + { + QByteArray buffer; + buffer.resize(byteCount); + _socket->read(buffer.data(), buffer.size()); + emit bytesReceived(this, buffer); + _logInputDataRate(byteCount, QDateTime::currentMSecsSinceEpoch()); #ifdef TCPLINK_READWRITE_DEBUG - writeDebugBytes(buffer.data(), buffer.size()); + writeDebugBytes(buffer.data(), buffer.size()); #endif + } } } @@ -118,9 +120,9 @@ void TCPLink::_disconnect(void) wait(); if (_socket) { _socketIsConnected = false; - _socket->deleteLater(); // Make sure delete happens on correct thread _socket->disconnectFromHost(); // Disconnect tcp _socket->waitForDisconnected(); + _socket->deleteLater(); // Make sure delete happens on correct thread _socket = NULL; emit disconnected(); } diff --git a/src/comm/UDPLink.cc b/src/comm/UDPLink.cc index ea80e3edb9e3cee95712775d40536a87ea5cf11d..58c32faf338fc2805931db2e5339d4d76281779e 100644 --- a/src/comm/UDPLink.cc +++ b/src/comm/UDPLink.cc @@ -68,27 +68,6 @@ static QString get_ip_address(const QString& address) return QString(""); } -static bool is_ip_local(const QHostAddress& add) -{ - // In simulation and testing setups the vehicle and the GCS can be - // running on the same host. This leads to packets arriving through - // the local network or the loopback adapter, which makes it look - // like the vehicle is connected through two different links, - // complicating routing. - // - // We detect this case and force all traffic to a simulated instance - // onto the local loopback interface. - // Run through all IPv4 interfaces and check if their canonical - // IP address in string representation matches the source IP address - foreach (const QHostAddress &address, QNetworkInterface::allAddresses()) { - if (address == add) { - // This is a local address of the same host - return true; - } - } - return false; -} - static bool contains_target(const QList list, const QHostAddress& address, quint16 port) { foreach(UDPCLient* target, list) { @@ -112,6 +91,9 @@ UDPLink::UDPLink(SharedLinkConfigurationPointer& config) if (!_udpConfig) { qWarning() << "Internal error"; } + foreach (const QHostAddress &address, QNetworkInterface::allAddresses()) { + _localAddress.append(QHostAddress(address)); + } moveToThread(this); } @@ -158,10 +140,36 @@ QString UDPLink::getName() const return _udpConfig->name(); } +bool UDPLink::_isIpLocal(const QHostAddress& add) +{ + // In simulation and testing setups the vehicle and the GCS can be + // running on the same host. This leads to packets arriving through + // the local network or the loopback adapter, which makes it look + // like the vehicle is connected through two different links, + // complicating routing. + // + // We detect this case and force all traffic to a simulated instance + // onto the local loopback interface. + // Run through all IPv4 interfaces and check if their canonical + // IP address in string representation matches the source IP address + // + // On Windows, this is a very expensive call only Redmond would know + // why. As such, we make it once and keep the list locally. If a new + // interface shows up after we start, it won't be on this list. + foreach (const QHostAddress &address, _localAddress) { + if (address == add) { + // This is a local address of the same host + return true; + } + } + return false; +} + void UDPLink::_writeBytes(const QByteArray data) { - if (!_socket) + if (!_socket) { return; + } // Send to all manually targeted systems foreach(UDPCLient* target, _udpConfig->targetHosts()) { // Skip it if it's part of the session clients below @@ -177,6 +185,7 @@ void UDPLink::_writeBytes(const QByteArray data) void UDPLink::_writeDataGram(const QByteArray data, const UDPCLient* target) { + //qDebug() << "UDP Out" << target->address << target->port; if(_socket->writeDatagram(data, target->address, target->port) < 0) { qWarning() << "Error writing to" << target->address << target->port; } else { @@ -193,6 +202,9 @@ void UDPLink::_writeDataGram(const QByteArray data, const UDPCLient* target) **/ void UDPLink::readBytes() { + if (!_socket) { + return; + } QByteArray databuffer; while (_socket->hasPendingDatagrams()) { @@ -200,6 +212,7 @@ void UDPLink::readBytes() datagram.resize(_socket->pendingDatagramSize()); QHostAddress sender; quint16 senderPort; + //-- Note: This call is broken in Qt 5.9.3 on Windows. It always returns a blank sender and 0 for the port. _socket->readDatagram(datagram.data(), datagram.size(), &sender, &senderPort); databuffer.append(datagram); //-- Wait a bit before sending it over @@ -213,7 +226,7 @@ void UDPLink::readBytes() // would trigger this. // Add host to broadcast list if not yet present, or update its port QHostAddress asender = sender; - if(is_ip_local(sender)) { + if(_isIpLocal(sender)) { asender = QHostAddress(QString("127.0.0.1")); } if(!contains_target(_sessionTargets, asender, senderPort)) { @@ -272,7 +285,7 @@ bool UDPLink::_hardwareConnect() _socket = NULL; } QHostAddress host = QHostAddress::AnyIPv4; - _socket = new QUdpSocket(); + _socket = new QUdpSocket(this); _socket->setProxy(QNetworkProxy::NoProxy); _connectState = _socket->bind(host, _udpConfig->localPort(), QAbstractSocket::ReuseAddressHint | QUdpSocket::ShareAddress); if (_connectState) { diff --git a/src/comm/UDPLink.h b/src/comm/UDPLink.h index 6e12c6af7bdef0ad4b2a951cc1ee2f5d1ef94e4e..e88782e04c884fcca9c2746bad1972f2b7eb4da8 100644 --- a/src/comm/UDPLink.h +++ b/src/comm/UDPLink.h @@ -184,6 +184,7 @@ private: bool _connect (void) override; void _disconnect (void) override; + bool _isIpLocal (const QHostAddress& add); bool _hardwareConnect (); void _restartConnection (); void _registerZeroconf (uint16_t port, const std::string& regType); @@ -194,11 +195,12 @@ private: DNSServiceRef _dnssServiceRef; #endif - bool _running; - QUdpSocket* _socket; - UDPConfiguration* _udpConfig; - bool _connectState; - QList _sessionTargets; + bool _running; + QUdpSocket* _socket; + UDPConfiguration* _udpConfig; + bool _connectState; + QList _sessionTargets; + QList _localAddress; };