Commit fe6ee5b3 authored by Lorenz Meier's avatar Lorenz Meier

Unit test fixes

parent 74736dbb
...@@ -36,6 +36,7 @@ along with PIXHAWK. If not, see <http://www.gnu.org/licenses/>. ...@@ -36,6 +36,7 @@ along with PIXHAWK. If not, see <http://www.gnu.org/licenses/>.
#include <QDateTime> #include <QDateTime>
#include <QMutex> #include <QMutex>
#include <QMutexLocker> #include <QMutexLocker>
#include <QMetaType>
/** /**
* The link interface defines the interface for all links used to communicate * The link interface defines the interface for all links used to communicate
...@@ -62,6 +63,7 @@ public: ...@@ -62,6 +63,7 @@ public:
outDataWriteTimes[i] = 0; outDataWriteTimes[i] = 0;
} }
qRegisterMetaType<LinkInterface*>("LinkInterface*");
} }
virtual ~LinkInterface() { virtual ~LinkInterface() {
......
#include "UASUnitTest.h" #include "UASUnitTest.h"
#include <stdio.h> #include <stdio.h>
#include <QObject> #include <QObject>
#include <QThread>
UASUnitTest::UASUnitTest() UASUnitTest::UASUnitTest()
{ {
} }
...@@ -8,7 +10,7 @@ UASUnitTest::UASUnitTest() ...@@ -8,7 +10,7 @@ UASUnitTest::UASUnitTest()
void UASUnitTest::init() void UASUnitTest::init()
{ {
mav = new MAVLinkProtocol(); mav = new MAVLinkProtocol();
uas = new UAS(mav, UASID); uas = new UAS(mav, QThread::currentThread(), UASID);
uas->deleteSettings(); uas->deleteSettings();
} }
//this function is called after every test //this function is called after every test
...@@ -24,7 +26,7 @@ void UASUnitTest::cleanup() ...@@ -24,7 +26,7 @@ void UASUnitTest::cleanup()
void UASUnitTest::getUASID_test() void UASUnitTest::getUASID_test()
{ {
// Test a default ID of zero is assigned // Test a default ID of zero is assigned
UAS* uas2 = new UAS(mav); UAS* uas2 = new UAS(mav, QThread::currentThread());
QCOMPARE(uas2->getUASID(), 0); QCOMPARE(uas2->getUASID(), 0);
delete uas2; delete uas2;
...@@ -49,7 +51,7 @@ void UASUnitTest::getUASName_test() ...@@ -49,7 +51,7 @@ void UASUnitTest::getUASName_test()
void UASUnitTest::getUpTime_test() void UASUnitTest::getUpTime_test()
{ {
UAS* uas2 = new UAS(mav); UAS* uas2 = new UAS(mav, QThread::currentThread());
// Test that the uptime starts at zero to a // Test that the uptime starts at zero to a
// precision of seconds // precision of seconds
QCOMPARE(floor(uas2->getUptime()/1000.0), 0.0); QCOMPARE(floor(uas2->getUptime()/1000.0), 0.0);
...@@ -281,7 +283,7 @@ void UASUnitTest::signalWayPoint_test() ...@@ -281,7 +283,7 @@ void UASUnitTest::signalWayPoint_test()
delete uas;// delete(destroyed) uas for validating delete uas;// delete(destroyed) uas for validating
uas = NULL; uas = NULL;
QCOMPARE(spyDestroyed.count(), 1);// count destroyed uas should are 1 QCOMPARE(spyDestroyed.count(), 1);// count destroyed uas should are 1
uas = new UAS(mav,UASID); uas = new UAS(mav, QThread::currentThread(), UASID);
QSignalSpy spy2(uas->getWaypointManager(), SIGNAL(waypointEditableListChanged())); QSignalSpy spy2(uas->getWaypointManager(), SIGNAL(waypointEditableListChanged()));
QCOMPARE(spy2.count(), 0); QCOMPARE(spy2.count(), 0);
Waypoint* wp2 = new Waypoint(0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,false, false, MAV_FRAME_GLOBAL, MAV_CMD_MISSION_START, "blah"); Waypoint* wp2 = new Waypoint(0,0.0,0.0,0.0,0.0,0.0,0.0,0.0,false, false, MAV_FRAME_GLOBAL, MAV_CMD_MISSION_START, "blah");
......
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