Unverified Commit 33480f62 authored by Don Gagne's avatar Don Gagne Committed by GitHub

Merge pull request #6360 from DonLakeFlyer/UpstreamStableMerge

Upstream stable merge
parents 08d6ac3a a76dd63b
......@@ -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:
......
......@@ -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 ();
......
......@@ -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);
}
} else {
// Error occurred
qWarning() << "Serial port not readable";
_emitLinkError(tr("Could not read data - link %1 is disconnected!").arg(getName()));
}
}
......
......@@ -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();
}
......
......@@ -193,6 +193,10 @@ void UDPLink::_writeDataGram(const QByteArray data, const UDPCLient* target)
**/
void UDPLink::readBytes()
{
if (_socket) {
return;
}
QByteArray databuffer;
while (_socket->hasPendingDatagrams())
{
......@@ -272,7 +276,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) {
......
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