Commit 3f81112a authored by Don Gagne's avatar Don Gagne

Merge pull request #2094 from DonLakeFlyer/MissionControllerUT

Mission controller Unit Test
parents bf4e313c 4cceba3b
......@@ -453,6 +453,8 @@ HEADERS += \
src/FactSystem/FactSystemTestGeneric.h \
src/FactSystem/FactSystemTestPX4.h \
src/MissionItemTest.h \
src/MissionManager/MissionControllerTest.h \
src/MissionManager/MissionControllerManagerTest.h \
src/MissionManager/MissionManagerTest.h \
src/qgcunittest/FileDialogTest.h \
src/qgcunittest/FileManagerTest.h \
......@@ -473,6 +475,8 @@ SOURCES += \
src/FactSystem/FactSystemTestGeneric.cc \
src/FactSystem/FactSystemTestPX4.cc \
src/MissionItemTest.cc \
src/MissionManager/MissionControllerTest.cc \
src/MissionManager/MissionControllerManagerTest.cc \
src/MissionManager/MissionManagerTest.cc \
src/qgcunittest/FileDialogTest.cc \
src/qgcunittest/FileManagerTest.cc \
......
......@@ -83,10 +83,7 @@ QGCView {
onAutoSyncChanged: QGroundControl.flightMapSettings.saveMapSetting(editorMap.mapName, _autoSyncKey, autoSync)
*/
onMissionItemsChanged: {
updateHomePosition()
itemEditor.clearItem()
}
onMissionItemsChanged: itemEditor.clearItem()
}
QGCPalette { id: qgcPal; colorGroupEnabled: enabled }
......@@ -105,19 +102,6 @@ QGCView {
}
}
function updateHomePosition() {
if (liveHomePositionAvailable) {
homePosition = liveHomePosition
_missionItems.get(0).coordinate = liveHomePosition
_missionItems.get(0).homePositionValid = true
}
}
Component.onCompleted: updateHomePosition()
//onOfflineHomePositionChanged: updateHomePosition()
onLiveHomePositionAvailableChanged: updateHomePosition()
onLiveHomePositionChanged: updateHomePosition()
QGCViewPanel {
id: panel
anchors.fill: parent
......
......@@ -446,6 +446,13 @@ void MissionController::_activeVehicleChanged(Vehicle* activeVehicle)
void MissionController::_activeVehicleHomePositionAvailableChanged(bool homePositionAvailable)
{
MissionItem* homeItem = qobject_cast<MissionItem*>(_missionItems->get(0));
if (homePositionAvailable) {
homeItem->setCoordinate(_liveHomePosition);
}
homeItem->setHomePositionValid(homePositionAvailable);
_liveHomePositionAvailable = homePositionAvailable;
emit liveHomePositionAvailableChanged(_liveHomePositionAvailable);
}
......
/*=====================================================================
QGroundControl Open Source Ground Control Station
(c) 2009 - 2014 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org>
This file is part of the QGROUNDCONTROL project
QGROUNDCONTROL is free software: you can redistribute it and/or modify
it under the terms of the GNU General Public License as published by
the Free Software Foundation, either version 3 of the License, or
(at your option) any later version.
QGROUNDCONTROL is distributed in the hope that it will be useful,
but WITHOUT ANY WARRANTY; without even the implied warranty of
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
GNU General Public License for more details.
You should have received a copy of the GNU General Public License
along with QGROUNDCONTROL. If not, see <http://www.gnu.org/licenses/>.
======================================================================*/
#include "MissionControllerManagerTest.h"
#include "LinkManager.h"
#include "MultiVehicleManager.h"
UT_REGISTER_TEST(MissionControllerManagerTest)
MissionControllerManagerTest::MissionControllerManagerTest(void)
: _mockLink(NULL)
{
}
void MissionControllerManagerTest::cleanup(void)
{
delete _multiSpyMissionManager;
_multiSpyMissionManager = NULL;
LinkManager::instance()->disconnectLink(_mockLink);
_mockLink = NULL;
QTest::qWait(1000); // Need to allow signals to move between threads
UnitTest::cleanup();
}
void MissionControllerManagerTest::_initForFirmwareType(MAV_AUTOPILOT firmwareType)
{
UnitTest::init();
LinkManager* linkMgr = LinkManager::instance();
Q_CHECK_PTR(linkMgr);
_mockLink = new MockLink();
Q_CHECK_PTR(_mockLink);
_mockLink->setFirmwareType(firmwareType);
LinkManager::instance()->_addLink(_mockLink);
linkMgr->connectLink(_mockLink);
// Wait for the Vehicle to work it's way through the various threads
QSignalSpy spyVehicle(MultiVehicleManager::instance(), SIGNAL(activeVehicleChanged(Vehicle*)));
QCOMPARE(spyVehicle.wait(5000), true);
// Wait for the Mission Manager to finish it's initial load
_missionManager = MultiVehicleManager::instance()->activeVehicle()->missionManager();
QVERIFY(_missionManager);
_rgMissionManagerSignals[canEditChangedSignalIndex] = SIGNAL(canEditChanged(bool));
_rgMissionManagerSignals[newMissionItemsAvailableSignalIndex] = SIGNAL(newMissionItemsAvailable(void));
_rgMissionManagerSignals[inProgressChangedSignalIndex] = SIGNAL(inProgressChanged(bool));
_rgMissionManagerSignals[errorSignalIndex] = SIGNAL(error(int, const QString&));
_multiSpyMissionManager = new MultiSignalSpy();
Q_CHECK_PTR(_multiSpyMissionManager);
QCOMPARE(_multiSpyMissionManager->init(_missionManager, _rgMissionManagerSignals, _cMissionManagerSignals), true);
if (_missionManager->inProgress()) {
_multiSpyMissionManager->waitForSignalByIndex(newMissionItemsAvailableSignalIndex, _missionManagerSignalWaitTime);
_multiSpyMissionManager->waitForSignalByIndex(inProgressChangedSignalIndex, _missionManagerSignalWaitTime);
QCOMPARE(_multiSpyMissionManager->checkSignalByMask(newMissionItemsAvailableSignalMask | inProgressChangedSignalMask), true);
QCOMPARE(_multiSpyMissionManager->checkNoSignalByMask(canEditChangedSignalIndex), true);
}
QVERIFY(!_missionManager->inProgress());
QCOMPARE(_missionManager->missionItems()->count(), 0);
_multiSpyMissionManager->clearAllSignals();
}
/// Checks the state of the inProgress value and signal to match the specified value
void MissionControllerManagerTest::_checkInProgressValues(bool inProgress)
{
QCOMPARE(_missionManager->inProgress(), inProgress);
QSignalSpy* spy = _multiSpyMissionManager->getSpyByIndex(inProgressChangedSignalIndex);
QList<QVariant> signalArgs = spy->takeFirst();
QCOMPARE(signalArgs.count(), 1);
QCOMPARE(signalArgs[0].toBool(), inProgress);
}
/*=====================================================================
QGroundControl Open Source Ground Control Station
(c) 2009 - 2015 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org>
This file is part of the QGROUNDCONTROL project
QGROUNDCONTROL is free software: you can redistribute it and/or modify
it under the terms of the GNU General Public License as published by
the Free Software Foundation, either version 3 of the License, or
(at your option) any later version.
QGROUNDCONTROL is distributed in the hope that it will be useful,
but WITHOUT ANY WARRANTY; without even the implied warranty of
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
GNU General Public License for more details.
You should have received a copy of the GNU General Public License
along with QGROUNDCONTROL. If not, see <http://www.gnu.org/licenses/>.
======================================================================*/
#ifndef MissionControllerManagerTest_H
#define MissionControllerManagerTest_H
#include "UnitTest.h"
#include "MockLink.h"
#include "MissionManager.h"
#include "MultiSignalSpy.h"
#include <QGeoCoordinate>
/// This is the base class for the MissionManager and MissionController unit tests.
class MissionControllerManagerTest : public UnitTest
{
Q_OBJECT
public:
MissionControllerManagerTest(void);
protected slots:
void cleanup(void);
protected:
void _initForFirmwareType(MAV_AUTOPILOT firmwareType);
void _checkInProgressValues(bool inProgress);
MockLink* _mockLink;
MissionManager* _missionManager;
typedef struct {
int sequenceNumber;
QGeoCoordinate coordinate;
int command;
double param1;
double param2;
double param3;
double param4;
bool autocontinue;
bool isCurrentItem;
int frame;
} ItemInfo_t;
typedef struct {
const char* itemStream;
const ItemInfo_t expectedItem;
} TestCase_t;
typedef enum {
canEditChangedSignalIndex = 0,
newMissionItemsAvailableSignalIndex,
inProgressChangedSignalIndex,
errorSignalIndex,
maxSignalIndex
} MissionManagerSignalIndex_t;
typedef enum {
canEditChangedSignalMask = 1 << canEditChangedSignalIndex,
newMissionItemsAvailableSignalMask = 1 << newMissionItemsAvailableSignalIndex,
inProgressChangedSignalMask = 1 << inProgressChangedSignalIndex,
errorSignalMask = 1 << errorSignalIndex,
} MissionManagerSignalMask_t;
MultiSignalSpy* _multiSpyMissionManager;
static const size_t _cMissionManagerSignals = maxSignalIndex;
const char* _rgMissionManagerSignals[_cMissionManagerSignals];
static const int _missionManagerSignalWaitTime = MissionManager::_ackTimeoutMilliseconds * MissionManager::_maxRetryCount * 2;
};
#endif
/*=====================================================================
QGroundControl Open Source Ground Control Station
(c) 2009 - 2014 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org>
This file is part of the QGROUNDCONTROL project
QGROUNDCONTROL is free software: you can redistribute it and/or modify
it under the terms of the GNU General Public License as published by
the Free Software Foundation, either version 3 of the License, or
(at your option) any later version.
QGROUNDCONTROL is distributed in the hope that it will be useful,
but WITHOUT ANY WARRANTY; without even the implied warranty of
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
GNU General Public License for more details.
You should have received a copy of the GNU General Public License
along with QGROUNDCONTROL. If not, see <http://www.gnu.org/licenses/>.
======================================================================*/
#include "MissionControllerTest.h"
#include "LinkManager.h"
#include "MultiVehicleManager.h"
UT_REGISTER_TEST(MissionControllerTest)
MissionControllerTest::MissionControllerTest(void)
: _missionController(NULL)
{
}
void MissionControllerTest::cleanup(void)
{
delete _missionController;
MissionControllerManagerTest::cleanup();
}
void MissionControllerTest::_initForFirmwareType(MAV_AUTOPILOT firmwareType)
{
MissionControllerManagerTest::_initForFirmwareType(firmwareType);
_rgSignals[missionItemsChangedSignalIndex] = SIGNAL(missionItemsChanged());
_rgSignals[waypointLinesChangedSignalIndex] = SIGNAL(waypointLinesChanged());
_rgSignals[liveHomePositionAvailableChangedSignalIndex] = SIGNAL(liveHomePositionAvailableChanged(bool));
_rgSignals[liveHomePositionChangedSignalIndex] = SIGNAL(liveHomePositionChanged(const QGeoCoordinate&));
_missionController = new MissionController();
Q_CHECK_PTR(_missionController);
_multiSpy = new MultiSignalSpy();
Q_CHECK_PTR(_multiSpy);
QCOMPARE(_multiSpy->init(_missionController, _rgSignals, _cSignals), true);
_missionController->start(false /* editMode */);
// All signals should some through on start
QCOMPARE(_multiSpy->checkOnlySignalByMask(missionItemsChangedSignalMask | waypointLinesChangedSignalMask | liveHomePositionAvailableChangedSignalMask | liveHomePositionChangedSignalMask), true);
_multiSpy->clearAllSignals();
QmlObjectListModel* missionItems = _missionController->missionItems();
QVERIFY(missionItems);
// Empty vehicle only has home position
QCOMPARE(missionItems->count(), 1);
// Home position should be in first slot
MissionItem* homeItem = qobject_cast<MissionItem*>(missionItems->get(0));
QVERIFY(homeItem);
QCOMPARE(homeItem->homePosition(), true);
// Home should have no children
QCOMPARE(homeItem->childItems()->count(), 0);
// No waypoint lines
QmlObjectListModel* waypointLines = _missionController->waypointLines();
QVERIFY(waypointLines);
QCOMPARE(waypointLines->count(), 0);
// Should not have home position yet
QCOMPARE(_missionController->liveHomePositionAvailable(), false);
// AutoSync should be off by default
QCOMPARE(_missionController->autoSync(), false);
}
void MissionControllerTest::_testEmptyVehicleWorker(MAV_AUTOPILOT firmwareType)
{
_initForFirmwareType(firmwareType);
// FYI: A significant amount of empty vehicle testing is in _initForFirmwareType since that
// sets up an empty vehicle
// APM stack doesn't support HOME_POSITION yet
bool expectedHomePositionValid = firmwareType == MAV_AUTOPILOT_PX4 ? true : false;
QmlObjectListModel* missionItems = _missionController->missionItems();
QVERIFY(missionItems);
MissionItem* homeItem = qobject_cast<MissionItem*>(missionItems->get(0));
QVERIFY(homeItem);
if (expectedHomePositionValid) {
// Wait for the home position to show up
if (!_missionController->liveHomePositionAvailable()) {
QVERIFY(_multiSpy->waitForSignalByIndex(liveHomePositionChangedSignalIndex, 2000));
// Once the home position shows up we get a number of addititional signals
QCOMPARE(_multiSpy->checkOnlySignalsByMask(liveHomePositionChangedSignalMask | liveHomePositionAvailableChangedSignalMask | waypointLinesChangedSignalMask), true);
// These should be signalled once
QCOMPARE(_multiSpy->checkSignalByMask(liveHomePositionChangedSignalMask | liveHomePositionAvailableChangedSignalMask), true);
// Waypoint lines get spit out multiple tiems
QCOMPARE(_multiSpy->checkSignalByMask(waypointLinesChangedSignalMask), false);
_multiSpy->clearAllSignals();
}
}
QCOMPARE(homeItem->homePositionValid(), expectedHomePositionValid);
QCOMPARE(_missionController->liveHomePositionAvailable(), expectedHomePositionValid);
QCOMPARE(_missionController->liveHomePosition().isValid(), expectedHomePositionValid);
}
void MissionControllerTest::_testEmptyVehiclePX4(void)
{
_testEmptyVehicleWorker(MAV_AUTOPILOT_PX4);
}
void MissionControllerTest::_testEmptyVehicleAPM(void)
{
_testEmptyVehicleWorker(MAV_AUTOPILOT_ARDUPILOTMEGA);
}
void MissionControllerTest::_testAddWaypointWorker(MAV_AUTOPILOT firmwareType)
{
_initForFirmwareType(firmwareType);
QGeoCoordinate coordinate(37.803784, -122.462276);
_missionController->addMissionItem(coordinate);
QCOMPARE(_multiSpy->checkOnlySignalsByMask(waypointLinesChangedSignalMask), true);
QmlObjectListModel* missionItems = _missionController->missionItems();
QVERIFY(missionItems);
QCOMPARE(missionItems->count(), 2);
MissionItem* homeItem = qobject_cast<MissionItem*>(missionItems->get(0));
MissionItem* item = qobject_cast<MissionItem*>(missionItems->get(1));
QVERIFY(homeItem);
QVERIFY(item);
QCOMPARE(item->command(), MavlinkQmlSingleton::MAV_CMD_NAV_TAKEOFF);
QCOMPARE(homeItem->childItems()->count(), 0);
QCOMPARE(item->childItems()->count(), 0);
int expectedLineCount;
if (homeItem->homePositionValid()) {
expectedLineCount = 1;
} else {
expectedLineCount = 0;
}
QmlObjectListModel* waypointLines = _missionController->waypointLines();
QVERIFY(waypointLines);
QCOMPARE(waypointLines->count(), expectedLineCount);
}
void MissionControllerTest::_testAddWayppointAPM(void)
{
_testAddWaypointWorker(MAV_AUTOPILOT_ARDUPILOTMEGA);
}
void MissionControllerTest::_testAddWayppointPX4(void)
{
_testAddWaypointWorker(MAV_AUTOPILOT_PX4);
}
/*=====================================================================
QGroundControl Open Source Ground Control Station
(c) 2009 - 2015 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org>
This file is part of the QGROUNDCONTROL project
QGROUNDCONTROL is free software: you can redistribute it and/or modify
it under the terms of the GNU General Public License as published by
the Free Software Foundation, either version 3 of the License, or
(at your option) any later version.
QGROUNDCONTROL is distributed in the hope that it will be useful,
but WITHOUT ANY WARRANTY; without even the implied warranty of
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
GNU General Public License for more details.
You should have received a copy of the GNU General Public License
along with QGROUNDCONTROL. If not, see <http://www.gnu.org/licenses/>.
======================================================================*/
#ifndef MissionControllerTest_H
#define MissionControllerTest_H
#include "UnitTest.h"
#include "MockLink.h"
#include "MissionManager.h"
#include "MultiSignalSpy.h"
#include "MissionControllerManagerTest.h"
#include "MissionController.h"
#include <QGeoCoordinate>
class MissionControllerTest : public MissionControllerManagerTest
{
Q_OBJECT
public:
MissionControllerTest(void);
private slots:
void cleanup(void);
void _testEmptyVehicleAPM(void);
void _testEmptyVehiclePX4(void);
void _testAddWayppointAPM(void);
void _testAddWayppointPX4(void);
private:
void _initForFirmwareType(MAV_AUTOPILOT firmwareType);
void _testEmptyVehicleWorker(MAV_AUTOPILOT firmwareType);
void _testAddWaypointWorker(MAV_AUTOPILOT firmwareType);
enum {
missionItemsChangedSignalIndex = 0,
waypointLinesChangedSignalIndex,
liveHomePositionAvailableChangedSignalIndex,
liveHomePositionChangedSignalIndex,
maxSignalIndex
};
enum {
missionItemsChangedSignalMask = 1 << missionItemsChangedSignalIndex,
waypointLinesChangedSignalMask = 1 << waypointLinesChangedSignalIndex,
liveHomePositionAvailableChangedSignalMask = 1 << liveHomePositionAvailableChangedSignalIndex,
liveHomePositionChangedSignalMask = 1 << liveHomePositionChangedSignalIndex,
};
MultiSignalSpy* _multiSpy;
static const size_t _cSignals = maxSignalIndex;
const char* _rgSignals[_cSignals];
MissionController* _missionController;
};
#endif
This diff is collapsed.
......@@ -28,10 +28,11 @@
#include "MockLink.h"
#include "MissionManager.h"
#include "MultiSignalSpy.h"
#include "MissionControllerManagerTest.h"
#include <QGeoCoordinate>
class MissionManagerTest : public UnitTest
class MissionManagerTest : public MissionControllerManagerTest
{
Q_OBJECT
......@@ -39,67 +40,19 @@ public:
MissionManagerTest(void);
private slots:
void cleanup(void);
void _testEmptyVehicleAPM(void);
void _testEmptyVehiclePX4(void);
void _testWriteFailureHandlingAPM(void);
void _testReadFailureHandlingAPM(void);
void _testWriteFailureHandlingPX4(void);
void _testReadFailureHandlingPX4(void);
private:
void _initForFirmwareType(MAV_AUTOPILOT firmwareType);
void _checkInProgressValues(bool inProgress);
void _roundTripItems(MockLinkMissionItemHandler::FailureMode_t failureMode, MissionManager::ErrorCode_t errorCode, bool failFirstTimeOnly);
void _writeItems(MockLinkMissionItemHandler::FailureMode_t failureMode, MissionManager::ErrorCode_t errorCode, bool failFirstTimeOnly);
void _testWriteFailureHandlingWorker(void);
void _testReadFailureHandlingWorker(void);
void _readEmptyVehicleWorker(void);
MockLink* _mockLink;
MissionManager* _missionManager;
enum {
canEditChangedSignalIndex = 0,
newMissionItemsAvailableSignalIndex,
inProgressChangedSignalIndex,
errorSignalIndex,
maxSignalIndex
};
enum {
canEditChangedSignalMask = 1 << canEditChangedSignalIndex,
newMissionItemsAvailableSignalMask = 1 << newMissionItemsAvailableSignalIndex,
inProgressChangedSignalMask = 1 << inProgressChangedSignalIndex,
errorSignalMask = 1 << errorSignalIndex,
};
MultiSignalSpy* _multiSpy;
static const size_t _cSignals = maxSignalIndex;
const char* _rgSignals[_cSignals];
typedef struct {
int sequenceNumber;
QGeoCoordinate coordinate;
int command;
double param1;
double param2;
double param3;
double param4;
bool autocontinue;
bool isCurrentItem;
int frame;
} ItemInfo_t;
typedef struct {
const char* itemStream;
const ItemInfo_t expectedItem;
} TestCase_t;
static const TestCase_t _rgTestCases[];
static const size_t _cTestCases;
static const int _signalWaitTime = MissionManager::_ackTimeoutMilliseconds * MissionManager::_maxRetryCount * 2;
static const MissionControllerManagerTest::TestCase_t _rgTestCases[];
static const size_t _cTestCases;
};
#endif
......@@ -88,6 +88,7 @@ MockLink::MockLink(MockConfiguration* config)
, _fileServer(NULL)
, _sendStatusText(false)
, _apmSendHomePositionOnEmptyList(false)
, _sendHomePositionDelayCount(2)
{
_config = config;
if (_config) {
......@@ -171,7 +172,12 @@ void MockLink::_run1HzTasks(void)
{
if (_mavlinkStarted && _connected) {
_sendHeartBeat();
_sendHomePosition();
if (_sendHomePositionDelayCount > 0) {
// We delay home position a bit to be more realistic
_sendHomePositionDelayCount--;
} else {
_sendHomePosition();
}
if (_sendStatusText) {
_sendStatusText = false;
_sendStatusTextMessages();
......@@ -715,24 +721,29 @@ void MockLink::setMissionItemFailureMode(MockLinkMissionItemHandler::FailureMode
void MockLink::_sendHomePosition(void)
{
mavlink_message_t msg;
float bogus[4];
bogus[0] = 0.0f;
bogus[1] = 0.0f;
bogus[2] = 0.0f;
bogus[3] = 0.0f;
mavlink_msg_home_position_pack(_vehicleSystemId,
_vehicleComponentId,
&msg,
(int32_t)(_vehicleLatitude * 1E7),
(int32_t)(_vehicleLongitude * 1E7),
(int32_t)(_vehicleAltitude * 1000),
0.0f, 0.0f, 0.0f,
&bogus[0],
0.0f, 0.0f, 0.0f);
respondWithMavlinkMessage(msg);
// APM stack does not yet support HOME_POSITION
if (_firmwareType != MAV_AUTOPILOT_ARDUPILOTMEGA) {
mavlink_message_t msg;
float bogus[4];
bogus[0] = 0.0f;
bogus[1] = 0.0f;
bogus[2] = 0.0f;
bogus[3] = 0.0f;
mavlink_msg_home_position_pack(_vehicleSystemId,
_vehicleComponentId,
&msg,
(int32_t)(_vehicleLatitude * 1E7),
(int32_t)(_vehicleLongitude * 1E7),
(int32_t)(_vehicleAltitude * 1000),
0.0f, 0.0f, 0.0f,
&bogus[0],
0.0f, 0.0f, 0.0f);
respondWithMavlinkMessage(msg);
}
}
void MockLink::_sendGpsRawInt(void)
......
......@@ -191,6 +191,8 @@ private:
bool _sendStatusText;
bool _apmSendHomePositionOnEmptyList;
int _sendHomePositionDelayCount;
static float _vehicleLatitude;
static float _vehicleLongitude;
static float _vehicleAltitude;
......
......@@ -85,17 +85,14 @@ bool MultiSignalSpy::init(
return true;
}
/// @param mask bit mask specifying which signals to check. The lowest order bit represents
/// index 0 into the rgSignals array and so on up the bit mask.
/// @return true if signal count = 1 for the specified signals
bool MultiSignalSpy::checkSignalByMask(quint16 mask)
bool MultiSignalSpy::_checkSignalByMaskWorker(quint16 mask, bool multipleSignalsAllowed)
{
for (size_t i=0; i<_cSignals; i++) {
if ((1 << i) & mask) {
QSignalSpy* spy = _rgSpys[i];
Q_ASSERT(spy != NULL);
if (spy->count() != 1) {
if ((multipleSignalsAllowed && spy->count() == 0) || spy->count() != 1) {
_printSignalState();
return false;
}
......@@ -105,16 +102,14 @@ bool MultiSignalSpy::checkSignalByMask(quint16 mask)
return true;
}
/// @return true if signal count = 1 for specified signals and signal count of 0
/// for all other signals
bool MultiSignalSpy::checkOnlySignalByMask(quint16 mask)
bool MultiSignalSpy::_checkOnlySignalByMaskWorker(quint16 mask, bool multipleSignalsAllowed)
{
for (size_t i=0; i<_cSignals; i++) {
QSignalSpy* spy = _rgSpys[i];
Q_ASSERT(spy != NULL);
if ((1 << i) & mask) {
if (spy->count() != 1) {
if ((multipleSignalsAllowed && spy->count() == 0) || (!multipleSignalsAllowed && spy->count() != 1)) {
_printSignalState();
return false;
}
......@@ -129,6 +124,26 @@ bool MultiSignalSpy::checkOnlySignalByMask(quint16 mask)
return true;
}
bool MultiSignalSpy::checkSignalByMask(quint16 mask)
{
return _checkSignalByMaskWorker(mask, false /* multipleSignalsAllowed */);
}
bool MultiSignalSpy::checkOnlySignalByMask(quint16 mask)
{
return _checkOnlySignalByMaskWorker(mask, false /* multipleSignalsAllowed */);
}
bool MultiSignalSpy::checkSignalsByMask(quint16 mask)
{
return _checkSignalByMaskWorker(mask, true /* multipleSignalsAllowed */);
}
bool MultiSignalSpy::checkOnlySignalsByMask(quint16 mask)
{
return _checkOnlySignalByMaskWorker(mask, true /* multipleSignalsAllowed */);
}
/// @return true if signal count = 0 for specified signals
bool MultiSignalSpy::checkNoSignalByMask(quint16 mask)
{
......
......@@ -43,8 +43,24 @@ public:
bool init(QObject* signalEmitter, const char** rgSignals, size_t cSignals);
/// @param mask bit mask specifying which signals to check. The lowest order bit represents
/// index 0 into the rgSignals array and so on up the bit mask.
/// @return true if signal count = 1 for the specified signals
bool checkSignalByMask(quint16 mask);
/// @return true if signal count = 1 for specified signals and signal count of 0
/// for all other signals
bool checkOnlySignalByMask(quint16 mask);
/// @param mask bit mask specifying which signals to check. The lowest order bit represents
/// index 0 into the rgSignals array and so on up the bit mask.
/// @return true if signal count >= 1 for the specified signals
bool checkSignalsByMask(quint16 mask);
/// @return true if signal count >= 1 for specified signals and signal count of 0
/// for all other signals
bool checkOnlySignalsByMask(quint16 mask);
bool checkNoSignalByMask(quint16 mask);
bool checkNoSignals(void);
......@@ -61,6 +77,8 @@ private:
void timerEvent(QTimerEvent * event);
void _printSignalState(void);
bool _checkSignalByMaskWorker(quint16 mask, bool multipleSignalsAllowed);
bool _checkOnlySignalByMaskWorker(quint16 mask, bool multipleSignalsAllowed);
QObject* _signalEmitter;
const char** _rgSignals;
......
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