Browse Source

Merge pull request #6360 from DonLakeFlyer/UpstreamStableMerge

Upstream stable merge
QGC4.4
Don Gagne 7 years ago committed by GitHub
parent
commit
33480f6295
No known key found for this signature in database
GPG Key ID: 4AEE18F83AFDEB23
  1. 31
      src/AnalyzeView/GeoTagController.cc
  2. 1
      src/AnalyzeView/GeoTagController.h
  3. 1
      src/AnalyzeView/GeoTagPage.qml
  4. 2
      src/AnalyzeView/LogDownloadController.cc
  5. 2
      src/AnalyzeView/LogDownloadPage.qml
  6. 8
      src/AnalyzeView/ULogParser.cc
  7. 7
      src/AnalyzeView/ULogParser.h
  8. 35
      src/VideoStreaming/VideoReceiver.cc
  9. 1
      src/VideoStreaming/VideoReceiver.h
  10. 17
      src/comm/BluetoothLink.cc
  11. 15
      src/comm/SerialLink.cc
  12. 8
      src/comm/TCPLink.cc
  13. 6
      src/comm/UDPLink.cc

31
src/AnalyzeView/GeoTagController.cc

@ -70,8 +70,7 @@ void GeoTagController::startTagging(void)
QDir imageDirectory = QDir(_worker.imageDirectory()); QDir imageDirectory = QDir(_worker.imageDirectory());
if(!imageDirectory.exists()) { if(!imageDirectory.exists()) {
_errorMessage = tr("Cannot find the image directory"); _setErrorMessage(tr("Cannot find the image directory"));
emit errorMessageChanged(_errorMessage);
return; return;
} }
if(_worker.saveDirectory() == "") { if(_worker.saveDirectory() == "") {
@ -83,23 +82,20 @@ void GeoTagController::startTagging(void)
msgBox.setWindowModality(Qt::ApplicationModal); msgBox.setWindowModality(Qt::ApplicationModal);
msgBox.addButton(tr("Replace"), QMessageBox::ActionRole); msgBox.addButton(tr("Replace"), QMessageBox::ActionRole);
if (msgBox.exec() == QMessageBox::Cancel) { if (msgBox.exec() == QMessageBox::Cancel) {
_errorMessage = tr("Images have already been tagged"); _setErrorMessage(tr("Images have already been tagged"));
emit errorMessageChanged(_errorMessage);
return; return;
} }
QDir oldTaggedFolder = QDir(_worker.imageDirectory() + "/TAGGED"); QDir oldTaggedFolder = QDir(_worker.imageDirectory() + "/TAGGED");
oldTaggedFolder.removeRecursively(); oldTaggedFolder.removeRecursively();
if(!imageDirectory.mkdir(_worker.imageDirectory() + "/TAGGED")) { if(!imageDirectory.mkdir(_worker.imageDirectory() + "/TAGGED")) {
_errorMessage = tr("Couldn't replace the previously tagged images"); _setErrorMessage(tr("Couldn't replace the previously tagged images"));
emit errorMessageChanged(_errorMessage);
return; return;
} }
} }
} else { } else {
QDir saveDirectory = QDir(_worker.saveDirectory()); QDir saveDirectory = QDir(_worker.saveDirectory());
if(!saveDirectory.exists()) { if(!saveDirectory.exists()) {
_errorMessage = tr("Cannot find the save directory"); _setErrorMessage(tr("Cannot find the save directory"));
emit errorMessageChanged(_errorMessage);
return; return;
} }
saveDirectory.setFilter(QDir::Files | QDir::Readable | QDir::NoSymLinks | QDir::Writable); saveDirectory.setFilter(QDir::Files | QDir::Readable | QDir::NoSymLinks | QDir::Writable);
@ -115,15 +111,13 @@ void GeoTagController::startTagging(void)
msgBox.setWindowModality(Qt::ApplicationModal); msgBox.setWindowModality(Qt::ApplicationModal);
msgBox.addButton(tr("Replace"), QMessageBox::ActionRole); msgBox.addButton(tr("Replace"), QMessageBox::ActionRole);
if (msgBox.exec() == QMessageBox::Cancel) { if (msgBox.exec() == QMessageBox::Cancel) {
_errorMessage = tr("Save folder not empty"); _setErrorMessage(tr("Save folder not empty"));
emit errorMessageChanged(_errorMessage);
return; return;
} }
foreach(QString dirFile, imageList) foreach(QString dirFile, imageList)
{ {
if(!saveDirectory.remove(dirFile)) { if(!saveDirectory.remove(dirFile)) {
_errorMessage = tr("Couldn't replace the existing images"); _setErrorMessage(tr("Couldn't replace the existing images"));
emit errorMessageChanged(_errorMessage);
return; return;
} }
} }
@ -144,6 +138,13 @@ void GeoTagController::_workerError(QString errorMessage)
emit errorMessageChanged(errorMessage); emit errorMessageChanged(errorMessage);
} }
void GeoTagController::_setErrorMessage(const QString& error)
{
_errorMessage = error;
emit errorMessageChanged(error);
}
GeoTagWorker::GeoTagWorker(void) GeoTagWorker::GeoTagWorker(void)
: _cancel(false) : _cancel(false)
, _logFile("") , _logFile("")
@ -210,9 +211,10 @@ void GeoTagWorker::run(void)
// Instantiate appropriate parser // Instantiate appropriate parser
_triggerList.clear(); _triggerList.clear();
bool parseComplete = false; bool parseComplete = false;
QString errorString;
if (isULog) { if (isULog) {
ULogParser parser; ULogParser parser;
parseComplete = parser.getTagsFromLog(log, _triggerList); parseComplete = parser.getTagsFromLog(log, _triggerList, errorString);
} else { } else {
PX4LogParser parser; PX4LogParser parser;
@ -227,7 +229,8 @@ void GeoTagWorker::run(void)
return; return;
} else { } else {
qCDebug(GeotaggingLog) << "Log parsing failed"; 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; return;
} }
} }

1
src/AnalyzeView/GeoTagController.h

@ -119,6 +119,7 @@ signals:
private slots: private slots:
void _workerProgressChanged (double progress); void _workerProgressChanged (double progress);
void _workerError (QString errorMsg); void _workerError (QString errorMsg);
void _setErrorMessage (const QString& error);
private: private:
QString _errorMessage; QString _errorMessage;

1
src/AnalyzeView/GeoTagPage.qml

@ -126,6 +126,7 @@ AnalyzePage {
QGCButton { QGCButton {
text: geoController.inProgress ? qsTr("Cancel Tagging") : qsTr("Start Tagging") text: geoController.inProgress ? qsTr("Cancel Tagging") : qsTr("Start Tagging")
width: ScreenTools.defaultFontPixelWidth * 30 width: ScreenTools.defaultFontPixelWidth * 30
onClicked: { onClicked: {
if (geoController.inProgress) { if (geoController.inProgress) {
geoController.cancelTagging() geoController.cancelTagging()

2
src/AnalyzeView/LogDownloadController.cc

@ -321,7 +321,7 @@ LogDownloadController::_logData(UASInterface* uas, uint32_t ofs, uint16_t id, ui
if(ofs <= _downloadData->entry->size()) { if(ofs <= _downloadData->entry->size()) {
const uint32_t chunk = ofs / kChunkSize; const uint32_t chunk = ofs / kChunkSize;
if (chunk != _downloadData->current_chunk) { 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; return;
} }
const uint16_t bin = (ofs - chunk*kChunkSize) / MAVLINK_MSG_LOG_DATA_FIELD_DATA_LEN; const uint16_t bin = (ofs - chunk*kChunkSize) / MAVLINK_MSG_LOG_DATA_FIELD_DATA_LEN;

2
src/AnalyzeView/LogDownloadPage.qml

@ -155,7 +155,7 @@ AnalyzePage {
fileDialog.qgcView = logDownloadPage fileDialog.qgcView = logDownloadPage
fileDialog.title = qsTr("Select save directory") fileDialog.title = qsTr("Select save directory")
fileDialog.selectExisting = true fileDialog.selectExisting = true
fileDialog.folder = QGroundControl.settingsManager.appSettings.telemetrySavePath fileDialog.folder = QGroundControl.settingsManager.appSettings.logSavePath
fileDialog.selectFolder = true fileDialog.selectFolder = true
fileDialog.openForLoad() fileDialog.openForLoad()
} }

8
src/AnalyzeView/ULogParser.cc

@ -86,11 +86,13 @@ bool ULogParser::parseFieldFormat(QString& fields)
return false; 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 //verify it's an ULog file
if(!log.contains(_ULogMagic)) { if(!log.contains(_ULogMagic)) {
qWarning() << "Could not detect ULog file header magic"; errorMessage = tr("Could not detect ULog file header magic");
return false; return false;
} }
@ -175,7 +177,7 @@ bool ULogParser::getTagsFromLog(QByteArray& log, QList<GeoTagWorker::cameraFeedb
} }
if (cameraFeedback.count() == 0) { 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; return false;
} }

7
src/AnalyzeView/ULogParser.h

@ -3,6 +3,7 @@
#include <QGeoCoordinate> #include <QGeoCoordinate>
#include <QDebug> #include <QDebug>
#include <QCoreApplication>
#include "GeoTagController.h" #include "GeoTagController.h"
@ -10,10 +11,14 @@
class ULogParser class ULogParser
{ {
Q_DECLARE_TR_FUNCTIONS(ULogParser)
public: public:
ULogParser(); ULogParser();
~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: private:

35
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->mux);
gst_element_sync_state_with_parent(_sink->filesink); 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"); GstPad* sinkpad = gst_element_get_static_pad(_sink->queue, "sink");
gst_pad_link(_sink->teepad, sinkpad); gst_pad_link(_sink->teepad, sinkpad);
gst_object_unref(sinkpad); gst_object_unref(sinkpad);
@ -803,6 +811,33 @@ VideoReceiver::_unlinkCallBack(GstPad* pad, GstPadProbeInfo* info, gpointer user
#endif #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 void
VideoReceiver::_updateTimer() VideoReceiver::_updateTimer()
{ {

1
src/VideoStreaming/VideoReceiver.h

@ -119,6 +119,7 @@ private:
static gboolean _onBusMessage (GstBus* bus, GstMessage* message, gpointer user_data); static gboolean _onBusMessage (GstBus* bus, GstMessage* message, gpointer user_data);
static GstPadProbeReturn _unlinkCallBack (GstPad* pad, GstPadProbeInfo* info, 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 _detachRecordingBranch (GstPadProbeInfo* info);
void _shutdownRecordingBranch(); void _shutdownRecordingBranch();
void _shutdownPipeline (); void _shutdownPipeline ();

17
src/comm/BluetoothLink.cc

@ -75,25 +75,19 @@ QString BluetoothLink::getName() const
void BluetoothLink::_writeBytes(const QByteArray bytes) void BluetoothLink::_writeBytes(const QByteArray bytes)
{ {
if(_targetSocket) if (_targetSocket) {
{
if(_targetSocket->isWritable())
{
if(_targetSocket->write(bytes) > 0) { if(_targetSocket->write(bytes) > 0) {
_logOutputDataRate(bytes.size(), QDateTime::currentMSecsSinceEpoch()); _logOutputDataRate(bytes.size(), QDateTime::currentMSecsSinceEpoch());
} } else {
else
qWarning() << "Bluetooth write error"; qWarning() << "Bluetooth write error";
} }
else
qWarning() << "Bluetooth not writable error";
} }
} }
void BluetoothLink::readBytes() void BluetoothLink::readBytes()
{ {
while (_targetSocket->bytesAvailable() > 0) if (_targetSocket) {
{ while (_targetSocket->bytesAvailable() > 0) {
QByteArray datagram; QByteArray datagram;
datagram.resize(_targetSocket->bytesAvailable()); datagram.resize(_targetSocket->bytesAvailable());
_targetSocket->read(datagram.data(), datagram.size()); _targetSocket->read(datagram.data(), datagram.size());
@ -101,6 +95,7 @@ void BluetoothLink::readBytes()
_logInputDataRate(datagram.length(), QDateTime::currentMSecsSinceEpoch()); _logInputDataRate(datagram.length(), QDateTime::currentMSecsSinceEpoch());
} }
} }
}
void BluetoothLink::_disconnect(void) void BluetoothLink::_disconnect(void)
{ {
@ -114,7 +109,7 @@ void BluetoothLink::_disconnect(void)
#endif #endif
if(_targetSocket) if(_targetSocket)
{ {
delete _targetSocket; _targetSocket->deleteLater();
_targetSocket = NULL; _targetSocket = NULL;
emit disconnected(); emit disconnected();
} }

15
src/comm/SerialLink.cc

@ -57,10 +57,6 @@ void SerialLink::requestReset()
SerialLink::~SerialLink() SerialLink::~SerialLink()
{ {
_disconnect(); _disconnect();
if (_port) {
delete _port;
}
_port = NULL;
} }
bool SerialLink::_isBootloader() bool SerialLink::_isBootloader()
@ -92,6 +88,7 @@ void SerialLink::_writeBytes(const QByteArray data)
_port->write(data); _port->write(data);
} else { } else {
// Error occurred // Error occurred
qWarning() << "Serial port not writeable";
_emitLinkError(tr("Could not send data - link %1 is disconnected!").arg(getName())); _emitLinkError(tr("Could not send data - link %1 is disconnected!").arg(getName()));
} }
} }
@ -105,7 +102,7 @@ void SerialLink::_disconnect(void)
{ {
if (_port) { if (_port) {
_port->close(); _port->close();
delete _port; _port->deleteLater();
_port = NULL; _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), QObject::connect(_port, static_cast<void (QSerialPort::*)(QSerialPort::SerialPortError)>(&QSerialPort::error),
this, &SerialLink::linkError); this, &SerialLink::linkError);
@ -261,6 +258,7 @@ bool SerialLink::_hardwareConnect(QSerialPort::SerialPortError& error, QString&
void SerialLink::_readBytes(void) void SerialLink::_readBytes(void)
{ {
if (_port && _port->isOpen()) {
qint64 byteCount = _port->bytesAvailable(); qint64 byteCount = _port->bytesAvailable();
if (byteCount) { if (byteCount) {
QByteArray buffer; QByteArray buffer;
@ -268,6 +266,11 @@ void SerialLink::_readBytes(void)
_port->read(buffer.data(), buffer.size()); _port->read(buffer.data(), buffer.size());
emit bytesReceived(this, buffer); emit bytesReceived(this, buffer);
} }
} else {
// Error occurred
qWarning() << "Serial port not readable";
_emitLinkError(tr("Could not read data - link %1 is disconnected!").arg(getName()));
}
} }
void SerialLink::linkError(QSerialPort::SerialPortError error) void SerialLink::linkError(QSerialPort::SerialPortError error)

8
src/comm/TCPLink.cc

@ -78,12 +78,12 @@ void TCPLink::_writeBytes(const QByteArray data)
#ifdef TCPLINK_READWRITE_DEBUG #ifdef TCPLINK_READWRITE_DEBUG
_writeDebugBytes(data); _writeDebugBytes(data);
#endif #endif
if (!_socket)
return;
if (_socket) {
_socket->write(data); _socket->write(data);
_logOutputDataRate(data.size(), QDateTime::currentMSecsSinceEpoch()); _logOutputDataRate(data.size(), QDateTime::currentMSecsSinceEpoch());
} }
}
/** /**
* @brief Read a number of bytes from the interface. * @brief Read a number of bytes from the interface.
@ -93,6 +93,7 @@ void TCPLink::_writeBytes(const QByteArray data)
**/ **/
void TCPLink::readBytes() void TCPLink::readBytes()
{ {
if (_socket) {
qint64 byteCount = _socket->bytesAvailable(); qint64 byteCount = _socket->bytesAvailable();
if (byteCount) if (byteCount)
{ {
@ -106,6 +107,7 @@ void TCPLink::readBytes()
#endif #endif
} }
} }
}
/** /**
* @brief Disconnect the connection. * @brief Disconnect the connection.
@ -118,9 +120,9 @@ void TCPLink::_disconnect(void)
wait(); wait();
if (_socket) { if (_socket) {
_socketIsConnected = false; _socketIsConnected = false;
_socket->deleteLater(); // Make sure delete happens on correct thread
_socket->disconnectFromHost(); // Disconnect tcp _socket->disconnectFromHost(); // Disconnect tcp
_socket->waitForDisconnected(); _socket->waitForDisconnected();
_socket->deleteLater(); // Make sure delete happens on correct thread
_socket = NULL; _socket = NULL;
emit disconnected(); emit disconnected();
} }

6
src/comm/UDPLink.cc

@ -193,6 +193,10 @@ void UDPLink::_writeDataGram(const QByteArray data, const UDPCLient* target)
**/ **/
void UDPLink::readBytes() void UDPLink::readBytes()
{ {
if (_socket) {
return;
}
QByteArray databuffer; QByteArray databuffer;
while (_socket->hasPendingDatagrams()) while (_socket->hasPendingDatagrams())
{ {
@ -272,7 +276,7 @@ bool UDPLink::_hardwareConnect()
_socket = NULL; _socket = NULL;
} }
QHostAddress host = QHostAddress::AnyIPv4; QHostAddress host = QHostAddress::AnyIPv4;
_socket = new QUdpSocket(); _socket = new QUdpSocket(this);
_socket->setProxy(QNetworkProxy::NoProxy); _socket->setProxy(QNetworkProxy::NoProxy);
_connectState = _socket->bind(host, _udpConfig->localPort(), QAbstractSocket::ReuseAddressHint | QUdpSocket::ShareAddress); _connectState = _socket->bind(host, _udpConfig->localPort(), QAbstractSocket::ReuseAddressHint | QUdpSocket::ShareAddress);
if (_connectState) { if (_connectState) {

Loading…
Cancel
Save