Commit 8f8d79f7 authored by Don Gagne's avatar Don Gagne Committed by GitHub

Merge pull request #3979 from DonLakeFlyer/LogDownloadTest

Initial implementation of LogDownloadTest
parents f434cda0 83126fc0
......@@ -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
......
......@@ -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)
......
......@@ -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)
......
......@@ -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();
}
}
//----------------------------------------------------------------------------------------
......
......@@ -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 ();
......
/****************************************************************************
*
* (c) 2009-2016 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org>
*
* 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 <QDir>
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;
}
/****************************************************************************
*
* (c) 2009-2016 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org>
*
* 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
......@@ -11,6 +11,7 @@
#include "MockLink.h"
#include "QGCLoggingCategory.h"
#include "QGCApplication.h"
#include "UnitTest.h"
#include <QTimer>
#include <QDebug>
......@@ -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();
}
}
}
......@@ -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;
......
......@@ -19,6 +19,9 @@
#include "MainWindow.h"
#include "Vehicle.h"
#include <QTemporaryFile>
#include <QTime>
bool UnitTest::_messageBoxRespondedTo = false;
bool UnitTest::_badResponseButton = false;
QMessageBox::StandardButton UnitTest::_messageBoxResponseButton = QMessageBox::NoButton;
......@@ -433,3 +436,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<byteCount; bytesWritten++) {
unsigned char byte = (qrand() * 0xFF) / RAND_MAX;
tempFile.write((char *)&byte, 1);
}
tempFile.close();
return tempFile.fileName();
} else {
qWarning() << "UnitTest::createRandomFile open failed" << tempFile.errorString();
return QString();
}
}
bool UnitTest::fileCompare(const QString& file1, const QString& file2)
{
QFile f1(file1);
QFile f2(file2);
if (QFileInfo(file1).size() != QFileInfo(file2).size()) {
qWarning() << "UnitTest::fileCompare file sizes differ size1:size2" << QFileInfo(file1).size() << QFileInfo(file2).size();
return false;
}
if (!f1.open(QIODevice::ReadOnly)) {
qWarning() << "UnitTest::fileCompare unable to open file1:" << f1.errorString();
return false;
}
if (!f2.open(QIODevice::ReadOnly)) {
qWarning() << "UnitTest::fileCompare unable to open file1:" << f1.errorString();
return false;
}
qint64 bytesRemaining = QFileInfo(file1).size();
qint64 offset = 0;
while (bytesRemaining) {
uint8_t b1, b2;
qint64 bytesRead = f1.read((char*)&b1, 1);
if (bytesRead != 1) {
qWarning() << "UnitTest::fileCompare file1 read failed:" << f1.errorString();
return false;
}
bytesRead = f2.read((char*)&b2, 1);
if (bytesRead != 1) {
qWarning() << "UnitTest::fileCompare file2 read failed:" << f2.errorString();
return false;
}
if (b1 != b2) {
qWarning() << "UnitTest::fileCompare mismatch offset:b1:b2" << offset << b1 << b2;
return false;
}
offset++;
bytesRemaining--;
}
return true;
}
......@@ -84,6 +84,14 @@ public:
/// @brief Adds a unit test to the list. Should only be called by UnitTestWrapper.
static void _addTest(QObject* test);
/// Creates a file with random contents of the specified size.
/// @return Fully qualified path to created file
static QString createRandomFile(uint32_t byteCount);
/// Will throw qWarning at location where files differ
/// @return true: files are alike, false: files differ
static bool fileCompare(const QString& file1, const QString& file2);
protected slots:
// These are all pure virtuals to force the derived class to implement each one and in turn
......
......@@ -31,6 +31,7 @@
#include "TCPLinkTest.h"
#include "ParameterLoaderTest.h"
#include "MissionCommandTreeTest.h"
#include "LogDownloadTest.h"
UT_REGISTER_TEST(FactSystemTestGeneric)
UT_REGISTER_TEST(FactSystemTestPX4)
......@@ -50,6 +51,7 @@ UT_REGISTER_TEST(TCPLinkTest)
UT_REGISTER_TEST(FileManagerTest)
UT_REGISTER_TEST(ParameterLoaderTest)
UT_REGISTER_TEST(MissionCommandTreeTest)
UT_REGISTER_TEST(LogDownloadTest)
// List of unit test which are currently disabled.
// If disabling a new test, include reason in comment.
......
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