Commit 453de983 authored by Gus Grubba's avatar Gus Grubba

Merge branch 'master' of https://github.com/mavlink/qgroundcontrol into androidSkipLookup

parents 585e71d9 6d13ae3a
......@@ -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\"
......
No preview for this file type
......@@ -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;
}
}
......
......@@ -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;
......
......@@ -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()
......
......@@ -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;
......
......@@ -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()
}
......
......@@ -86,11 +86,13 @@ bool ULogParser::parseFieldFormat(QString& fields)
return false;
}
bool ULogParser::getTagsFromLog(QByteArray& log, QList<GeoTagWorker::cameraFeedbackPacket>& cameraFeedback)
bool ULogParser::getTagsFromLog(QByteArray& log, QList<GeoTagWorker::cameraFeedbackPacket>& 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<GeoTagWorker::cameraFeedb
}
if (cameraFeedback.count() == 0) {
qWarning() << "Could not detect camera_capture packets in ULog";
errorMessage = tr("Could not detect camera_capture packets in ULog");
return false;
}
......
......@@ -3,6 +3,7 @@
#include <QGeoCoordinate>
#include <QDebug>
#include <QCoreApplication>
#include "GeoTagController.h"
......@@ -10,10 +11,14 @@
class ULogParser
{
Q_DECLARE_TR_FUNCTIONS(ULogParser)
public:
ULogParser();
~ULogParser();
bool getTagsFromLog(QByteArray& log, QList<GeoTagWorker::cameraFeedbackPacket>& cameraFeedback);
/// @return true: failed, errorMessage set
bool getTagsFromLog(QByteArray& log, QList<GeoTagWorker::cameraFeedbackPacket>& cameraFeedback, QString& errorMessage);
private:
......
......@@ -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();
}
......
......@@ -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);
......
......@@ -374,8 +374,7 @@ bool TerrainTileManager::_getAltitudesForCoordinates(const QList<QGeoCoordinate>
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<QGeoTiledMapReplyQGC*>(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);
......
......@@ -62,20 +62,20 @@ public:
TerrainAirMapQuery(QObject* parent = NULL);
// Overrides from TerrainQueryInterface
void requestCoordinateHeights(const QList<QGeoCoordinate>& 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<QGeoCoordinate>& 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 {
......
......@@ -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;
......
......@@ -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)
......
......@@ -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()
......
......@@ -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 ();
......
......@@ -34,7 +34,7 @@ QGCView {
"So make sure to test your changes thoroughly before using them in flight.</p>" +
"<p>Click 'Load Custom Qml file' to provide your custom qml file.</p>" +
"<p>Click 'Reset' to reset to none.</p>" +
"<p>Example usage: http://https://dev.qgroundcontrol.com/en/tools/custom_command_widget.html</p>"
"<p>Example usage: <a href='https://dev.qgroundcontrol.com/en/tools/custom_command_widget.html'>https://dev.qgroundcontrol.com/en/tools/custom_command_widget.html</a></p>"
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()
}
}
}
}
}
}
......@@ -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();
}
......
......@@ -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<void (QSerialPort::*)(QSerialPort::SerialPortError)>(&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);
}