diff --git a/qgroundcontrol.pro b/qgroundcontrol.pro index b4b5fa03429933e3cf6555d5105e0e9a33b35ef8..c39e90a20a5831a7b4f4c47253d15ead8c3cca7d 100644 --- a/qgroundcontrol.pro +++ b/qgroundcontrol.pro @@ -581,6 +581,7 @@ HEADERS += \ src/qgcunittest/TCPLinkTest.h \ src/qgcunittest/TCPLoopBackServer.h \ src/qgcunittest/UnitTest.h \ + src/ViewWidgets/LogDownloadTest.h \ src/VehicleSetup/SetupViewTest.h \ SOURCES += \ @@ -609,6 +610,7 @@ SOURCES += \ src/qgcunittest/TCPLoopBackServer.cc \ src/qgcunittest/UnitTest.cc \ src/qgcunittest/UnitTestList.cc \ + src/ViewWidgets/LogDownloadTest.cc \ src/VehicleSetup/SetupViewTest.cc \ } # !MobileBuild } # DebugBuild diff --git a/src/FactSystem/FactControls/FactPanelController.cc b/src/FactSystem/FactControls/FactPanelController.cc index 686810562547b86bf39d92bbbc47a7708593120c..83f6b9d990737655f8271dac34fb0e63caaa42e4 100644 --- a/src/FactSystem/FactControls/FactPanelController.cc +++ b/src/FactSystem/FactControls/FactPanelController.cc @@ -20,7 +20,7 @@ QGC_LOGGING_CATEGORY(FactPanelControllerLog, "FactPanelControllerLog") -FactPanelController::FactPanelController(void) +FactPanelController::FactPanelController(bool standaloneUnitTesting) : _vehicle(NULL) , _uas(NULL) , _autopilot(NULL) @@ -33,8 +33,10 @@ FactPanelController::FactPanelController(void) _autopilot = _vehicle->autopilotPlugin(); } - // Do a delayed check for the _factPanel finally being set correctly from Qml - QTimer::singleShot(1000, this, &FactPanelController::_checkForMissingFactPanel); + if (!standaloneUnitTesting) { + // Do a delayed check for the _factPanel finally being set correctly from Qml + QTimer::singleShot(1000, this, &FactPanelController::_checkForMissingFactPanel); + } } QQuickItem* FactPanelController::factPanel(void) diff --git a/src/FactSystem/FactControls/FactPanelController.h b/src/FactSystem/FactControls/FactPanelController.h index ec90b2a3766b0ed9cd05a567e012e650989e75ef..98ca8ff3eb18da0b0f31a9d27991124f70a761be 100644 --- a/src/FactSystem/FactControls/FactPanelController.h +++ b/src/FactSystem/FactControls/FactPanelController.h @@ -30,7 +30,8 @@ class FactPanelController : public QObject Q_OBJECT public: - FactPanelController(void); + /// @param standaloneUnitTesting true: being run without factPanel, false: normal operation, factPanel is required + FactPanelController(bool standaloneUnitTesting = false); Q_PROPERTY(QQuickItem* factPanel READ factPanel WRITE setFactPanel) Q_PROPERTY(Vehicle* vehicle MEMBER _vehicle CONSTANT) diff --git a/src/ViewWidgets/LogDownloadController.cc b/src/ViewWidgets/LogDownloadController.cc index 7f55a5f63c979c6ea49adb265b72dc5aa55c15a5..1a7fb9622cd84bb8a57b7e51a3de9929deb5b9e3 100644 --- a/src/ViewWidgets/LogDownloadController.cc +++ b/src/ViewWidgets/LogDownloadController.cc @@ -103,8 +103,9 @@ QGCLogEntry::sizeStr() const } //---------------------------------------------------------------------------------------- -LogDownloadController::LogDownloadController(void) - : _uas(NULL) +LogDownloadController::LogDownloadController(bool standaloneUnitTesting) + : FactPanelController(standaloneUnitTesting) + , _uas(NULL) , _downloadData(NULL) , _vehicle(NULL) , _requestingLogEntries(false) @@ -501,6 +502,16 @@ LogDownloadController::_requestLogList(uint32_t start, uint32_t end) //---------------------------------------------------------------------------------------- void LogDownloadController::download(void) +{ + QString dir = QGCFileDialog::getExistingDirectory( + MainWindow::instance(), + "Log Download Directory", + QDir::homePath(), + QGCFileDialog::ShowDirsOnly | QGCFileDialog::DontResolveSymlinks); + downloadToDirectory(dir); +} + +void LogDownloadController::downloadToDirectory(const QString& dir) { //-- Stop listing just in case _receivedAllEntries(); @@ -509,12 +520,7 @@ LogDownloadController::download(void) delete _downloadData; _downloadData = 0; } - _downloadPath.clear(); - _downloadPath = QGCFileDialog::getExistingDirectory( - MainWindow::instance(), - "Log Download Directory", - QDir::homePath(), - QGCFileDialog::ShowDirsOnly | QGCFileDialog::DontResolveSymlinks); + _downloadPath = dir; if(!_downloadPath.isEmpty()) { if(!_downloadPath.endsWith(QDir::separator())) _downloadPath += QDir::separator(); @@ -534,6 +540,7 @@ LogDownloadController::download(void) } } + //---------------------------------------------------------------------------------------- QGCLogEntry* LogDownloadController::_getNextSelected() @@ -619,18 +626,22 @@ LogDownloadController::_prepareLogDownload() void LogDownloadController::_setDownloading(bool active) { - _downloadingLogs = active; - _vehicle->setConnectionLostEnabled(!active); - emit downloadingLogsChanged(); + if (_downloadingLogs != active) { + _downloadingLogs = active; + _vehicle->setConnectionLostEnabled(!active); + emit downloadingLogsChanged(); + } } //---------------------------------------------------------------------------------------- void LogDownloadController::_setListing(bool active) { - _requestingLogEntries = active; - _vehicle->setConnectionLostEnabled(!active); - emit requestingListChanged(); + if (_requestingLogEntries != active) { + _requestingLogEntries = active; + _vehicle->setConnectionLostEnabled(!active); + emit requestingListChanged(); + } } //---------------------------------------------------------------------------------------- diff --git a/src/ViewWidgets/LogDownloadController.h b/src/ViewWidgets/LogDownloadController.h index 5956a9923d91b5ff70c90a82f4a435291423629a..a98a9452333a877ca7f54cf120d99716617e38ce 100644 --- a/src/ViewWidgets/LogDownloadController.h +++ b/src/ViewWidgets/LogDownloadController.h @@ -115,7 +115,8 @@ class LogDownloadController : public FactPanelController Q_OBJECT public: - LogDownloadController(); + /// @param standaloneUnitTesting true: being run without factPanel, false: normal operation, factPanel is required + LogDownloadController(bool standaloneUnitTesting = false); Q_PROPERTY(QGCLogModel* model READ model NOTIFY modelChanged) Q_PROPERTY(bool requestingList READ requestingList NOTIFY requestingListChanged) @@ -130,6 +131,8 @@ public: Q_INVOKABLE void eraseAll (); Q_INVOKABLE void cancel (); + void downloadToDirectory(const QString& dir); + signals: void requestingListChanged (); void downloadingLogsChanged (); diff --git a/src/ViewWidgets/LogDownloadTest.cc b/src/ViewWidgets/LogDownloadTest.cc new file mode 100644 index 0000000000000000000000000000000000000000..6637722696b20e2c2e8eef6bca2edb2e163f6a48 --- /dev/null +++ b/src/ViewWidgets/LogDownloadTest.cc @@ -0,0 +1,66 @@ +/**************************************************************************** + * + * (c) 2009-2016 QGROUNDCONTROL PROJECT + * + * QGroundControl is licensed according to the terms in the file + * COPYING.md in the root of the source code directory. + * + ****************************************************************************/ + +#include "LogDownloadTest.h" +#include "LogDownloadController.h" +#include "MockLink.h" + +#include + +LogDownloadTest::LogDownloadTest(void) +{ + +} + +void LogDownloadTest::downloadTest(void) +{ + + _connectMockLink(MAV_AUTOPILOT_PX4); + + LogDownloadController* controller = new LogDownloadController(true); + + _rgLogDownloadControllerSignals[requestingListChangedSignalIndex] = SIGNAL(requestingListChanged()); + _rgLogDownloadControllerSignals[downloadingLogsChangedSignalIndex] = SIGNAL(downloadingLogsChanged()); + _rgLogDownloadControllerSignals[modelChangedSignalIndex] = SIGNAL(modelChanged()); + + _multiSpyLogDownloadController = new MultiSignalSpy(); + QVERIFY(_multiSpyLogDownloadController->init(controller, _rgLogDownloadControllerSignals, _cLogDownloadControllerSignals)); + + controller->refresh(); + QVERIFY(_multiSpyLogDownloadController->waitForSignalByIndex(requestingListChangedSignalIndex, 10000)); + _multiSpyLogDownloadController->clearAllSignals(); + if (controller->requestingList()) { + QVERIFY(_multiSpyLogDownloadController->waitForSignalByIndex(requestingListChangedSignalIndex, 10000)); + QCOMPARE(controller->requestingList(), false); + } + _multiSpyLogDownloadController->clearAllSignals(); + + QGCLogModel* model = controller->model(); + QVERIFY(model); + qDebug() << model->count(); + (*model)[0]->setSelected(true); + + QString downloadTo = QDir::currentPath(); + qDebug() << "download to:" << downloadTo; + controller->downloadToDirectory(downloadTo); + QVERIFY(_multiSpyLogDownloadController->waitForSignalByIndex(downloadingLogsChangedSignalIndex, 10000)); + _multiSpyLogDownloadController->clearAllSignals(); + if (controller->downloadingLogs()) { + QVERIFY(_multiSpyLogDownloadController->waitForSignalByIndex(downloadingLogsChangedSignalIndex, 10000)); + QCOMPARE(controller->downloadingLogs(), false); + } + _multiSpyLogDownloadController->clearAllSignals(); + + QString downloadFile = QDir(downloadTo).filePath("log_0_UnknownDate.px4log"); + QVERIFY(UnitTest::fileCompare(downloadFile, _mockLink->logDownloadFile())); + + QFile::remove(downloadFile); + + delete controller; +} diff --git a/src/ViewWidgets/LogDownloadTest.h b/src/ViewWidgets/LogDownloadTest.h new file mode 100644 index 0000000000000000000000000000000000000000..0b546a75dd6436dfe7704ea987c2224a3b7f9942 --- /dev/null +++ b/src/ViewWidgets/LogDownloadTest.h @@ -0,0 +1,51 @@ +/**************************************************************************** + * + * (c) 2009-2016 QGROUNDCONTROL PROJECT + * + * QGroundControl is licensed according to the terms in the file + * COPYING.md in the root of the source code directory. + * + ****************************************************************************/ + +#ifndef LogDownloadTest_H +#define LogDownloadTest_H + +#include "UnitTest.h" +#include "MultiSignalSpy.h" + +class LogDownloadTest : public UnitTest +{ + Q_OBJECT + +public: + LogDownloadTest(void); + +private slots: + //void init(void); + //void cleanup(void) { _cleanup(); } + + void downloadTest(void); + +private: + // LogDownloadController signals + + enum { + requestingListChangedSignalIndex = 0, + downloadingLogsChangedSignalIndex, + modelChangedSignalIndex, + logDownloadControllerMaxSignalIndex + }; + + enum { + requestingListChangedSignalMask = 1 << requestingListChangedSignalIndex, + downloadingLogsChangedSignalMask = 1 << downloadingLogsChangedSignalIndex, + modelChangedSignalIndexMask = 1 << modelChangedSignalIndex, + }; + + MultiSignalSpy* _multiSpyLogDownloadController; + static const size_t _cLogDownloadControllerSignals = logDownloadControllerMaxSignalIndex; + const char* _rgLogDownloadControllerSignals[_cLogDownloadControllerSignals]; + +}; + +#endif diff --git a/src/comm/MockLink.cc b/src/comm/MockLink.cc index 4b9d185630bc44581c0054d093ea69a65edab16d..cba6807713921fae459f5b2962bedc8288bdb27d 100644 --- a/src/comm/MockLink.cc +++ b/src/comm/MockLink.cc @@ -11,6 +11,7 @@ #include "MockLink.h" #include "QGCLoggingCategory.h" #include "QGCApplication.h" +#include "UnitTest.h" #include #include @@ -59,6 +60,8 @@ MockLink::MockLink(MockConfiguration* config) , _sendGPSPositionDelayCount(100) // No gps lock for 5 seconds , _currentParamRequestListComponentIndex(-1) , _currentParamRequestListParamIndex(-1) + , _logDownloadCurrentOffset(0) + , _logDownloadBytesRemaining(0) { _config = config; if (_config) { @@ -86,6 +89,9 @@ MockLink::MockLink(MockConfiguration* config) MockLink::~MockLink(void) { _disconnect(); + if (!_logDownloadFilename.isEmpty()) { + QFile::remove(_logDownloadFilename); + } } bool MockLink::_connect(void) @@ -170,6 +176,7 @@ void MockLink::_run500HzTasks(void) { if (_mavlinkStarted && _connected) { _paramRequestListWorker(); + _logDownloadWorker(); } } @@ -378,6 +385,14 @@ void MockLink::_handleIncomingMavlinkBytes(const uint8_t* bytes, int cBytes) _handleManualControl(msg); break; + case MAVLINK_MSG_ID_LOG_REQUEST_LIST: + _handleLogRequestList(msg); + break; + + case MAVLINK_MSG_ID_LOG_REQUEST_DATA: + _handleLogRequestData(msg); + break; + default: break; } @@ -1097,3 +1112,86 @@ void MockLink::_handlePreFlightCalibration(const mavlink_command_long_t& request respondWithMavlinkMessage(msg); } +void MockLink::_handleLogRequestList(const mavlink_message_t& msg) +{ + mavlink_log_request_list_t request; + + mavlink_msg_log_request_list_decode(&msg, &request); + + if (request.start != 0 && request.end != 0xffff) { + qWarning() << "MockLink::_handleLogRequestList cannot handle partial requests"; + return; + } + + mavlink_message_t responseMsg; + mavlink_msg_log_entry_pack(_vehicleSystemId, + _vehicleComponentId, + &responseMsg, + _logDownloadLogId, // log id + 1, // num_logs + 1, // last_log_num + 0, // time_utc + _logDownloadFileSize); // size + respondWithMavlinkMessage(responseMsg); +} + +void MockLink::_handleLogRequestData(const mavlink_message_t& msg) +{ + mavlink_log_request_data_t request; + + mavlink_msg_log_request_data_decode(&msg, &request); + + if (_logDownloadFilename.isEmpty()) { + _logDownloadFilename = UnitTest::createRandomFile(_logDownloadFileSize); + } + + if (request.id != 0) { + qWarning() << "MockLink::_handleLogRequestData id must be 0"; + return; + } + + if (request.ofs > _logDownloadFileSize - 1) { + qWarning() << "MockLink::_handleLogRequestData offset past end of file request.ofs:size" << request.ofs << _logDownloadFileSize; + return; + } + + // This will trigger _logDownloadWorker to send data + _logDownloadCurrentOffset = request.ofs; + if (request.ofs + request.count > _logDownloadFileSize) { + request.count = _logDownloadFileSize - request.ofs; + } + _logDownloadBytesRemaining = request.count; +} + +void MockLink::_logDownloadWorker(void) +{ + if (_logDownloadBytesRemaining != 0) { + QFile file(_logDownloadFilename); + if (file.open(QIODevice::ReadOnly)) { + uint8_t buffer[MAVLINK_MSG_LOG_DATA_FIELD_DATA_LEN]; + + qint64 bytesToRead = qMin(_logDownloadBytesRemaining, (uint32_t)MAVLINK_MSG_LOG_DATA_FIELD_DATA_LEN); + Q_ASSERT(file.seek(_logDownloadCurrentOffset)); + Q_ASSERT(file.read((char *)buffer, bytesToRead) == bytesToRead); + + qDebug() << "MockLink::_logDownloadWorker" << _logDownloadCurrentOffset << _logDownloadBytesRemaining; + + mavlink_message_t responseMsg; + mavlink_msg_log_data_pack(_vehicleSystemId, + _vehicleComponentId, + &responseMsg, + _logDownloadLogId, + _logDownloadCurrentOffset, + bytesToRead, + &buffer[0]); + respondWithMavlinkMessage(responseMsg); + + _logDownloadCurrentOffset += bytesToRead; + _logDownloadBytesRemaining -= bytesToRead; + + file.close(); + } else { + qWarning() << "MockLink::_logDownloadWorker open failed" << file.errorString(); + } + } +} diff --git a/src/comm/MockLink.h b/src/comm/MockLink.h index 53ea1e3f49e06fe2bd1ce9ddb4c4ebdc4cc6ada6..cdb25373f8f98e3e4bf340f5437190701c9a4264 100644 --- a/src/comm/MockLink.h +++ b/src/comm/MockLink.h @@ -144,6 +144,9 @@ public: /// Reset the state of the MissionItemHandler to no items, no transactions in progress. void resetMissionItemHandler(void) { _missionItemHandler.reset(); } + /// Returns the filename for the simulated log file. Onyl available after a download is requested. + QString logDownloadFile(void) { return _logDownloadFilename; } + static MockLink* startPX4MockLink (bool sendStatusText, MockConfiguration::FailureMode_t failureMode = MockConfiguration::FailNone); static MockLink* startGenericMockLink (bool sendStatusText, MockConfiguration::FailureMode_t failureMode = MockConfiguration::FailNone); static MockLink* startAPMArduCopterMockLink (bool sendStatusText, MockConfiguration::FailureMode_t failureMode = MockConfiguration::FailNone); @@ -180,6 +183,8 @@ private: void _handleCommandLong(const mavlink_message_t& msg); void _handleManualControl(const mavlink_message_t& msg); void _handlePreFlightCalibration(const mavlink_command_long_t& request); + void _handleLogRequestList(const mavlink_message_t& msg); + void _handleLogRequestData(const mavlink_message_t& msg); float _floatUnionForParam(int componentId, const QString& paramName); void _setParamFloatUnionIntoMap(int componentId, const QString& paramName, float paramFloat); void _sendHomePosition(void); @@ -189,6 +194,7 @@ private: void _respondWithAutopilotVersion(void); void _sendRCChannels(void); void _paramRequestListWorker(void); + void _logDownloadWorker(void); static MockLink* _startMockLink(MockConfiguration* mockConfig); @@ -224,7 +230,14 @@ private: int _sendGPSPositionDelayCount; int _currentParamRequestListComponentIndex; // Current component index for param request list workflow, -1 for no request in progress - int _currentParamRequestListParamIndex; // Current parameter index for param request list workflor + int _currentParamRequestListParamIndex; // Current parameter index for param request list workflow + + static const uint16_t _logDownloadLogId = 0; ///< Id of siumulated log file + static const uint32_t _logDownloadFileSize = 1000; ///< Size of simulated log file + + QString _logDownloadFilename; ///< Filename for log download which is in progress + uint32_t _logDownloadCurrentOffset; ///< Current offset we are sending from + uint32_t _logDownloadBytesRemaining; ///< Number of bytes still to send, 0 = send inactive static float _vehicleLatitude; static float _vehicleLongitude; diff --git a/src/qgcunittest/UnitTest.cc b/src/qgcunittest/UnitTest.cc index d910e26726d32a43810888705c47f657fefb2458..a45ae1b0f6635bda229c3781530e029d3e78cbcd 100644 --- a/src/qgcunittest/UnitTest.cc +++ b/src/qgcunittest/UnitTest.cc @@ -19,6 +19,10 @@ #include "MainWindow.h" #include "Vehicle.h" +#include +#include +#include + bool UnitTest::_messageBoxRespondedTo = false; bool UnitTest::_badResponseButton = false; QMessageBox::StandardButton UnitTest::_messageBoxResponseButton = QMessageBox::NoButton; @@ -433,3 +437,71 @@ void UnitTest::_closeMainWindow(bool cancelExpected) QTest::qWait(1000); } } + +QString UnitTest::createRandomFile(uint32_t byteCount) +{ + QTemporaryFile tempFile; + + QTime time = QTime::currentTime(); + qsrand((uint)time.msec()); + + tempFile.setAutoRemove(false); + if (tempFile.open()) { + for (uint32_t bytesWritten=0; bytesWritten