Browse Source

Signal waypoint test passes.

QGC4.4
Jessica 13 years ago
parent
commit
16f4c928ad
  1. 17
      qgcunittest/UASUnitTest.cc

17
qgcunittest/UASUnitTest.cc

@ -16,8 +16,10 @@ void UASUnitTest::cleanup()
{ {
delete mav; delete mav;
mav = NULL; mav = NULL;
if(uas != NULL){
delete uas; delete uas;
uas = NULL; uas = NULL;
}
} }
void UASUnitTest::getUASID_test() void UASUnitTest::getUASID_test()
@ -253,32 +255,35 @@ void UASUnitTest::getWaypoint_test()
void UASUnitTest::signalWayPoint_test() void UASUnitTest::signalWayPoint_test()
{ {
QSignalSpy spy(uas->getWaypointManager(), SIGNAL(waypointEditableListChanged(UASID))); QSignalSpy spy(uas->getWaypointManager(), SIGNAL(waypointEditableListChanged()));
Waypoint* wp = 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* wp = new Waypoint(0,1.0,1.0,1.0,0.0,0.0,0.0,0.0,false, false, MAV_FRAME_GLOBAL, MAV_CMD_MISSION_START, "blah");
uas->getWaypointManager()->addWaypointEditable(wp, true); uas->getWaypointManager()->addWaypointEditable(wp, true);
printf("spy.count = %d\n", spy.count());
QCOMPARE(spy.count(), 1); // 1 listChanged for add wayPoint QCOMPARE(spy.count(), 1); // 1 listChanged for add wayPoint
uas->getWaypointManager()->removeWaypoint(0); uas->getWaypointManager()->removeWaypoint(0);
QCOMPARE(spy.count(), 2); // 2 listChanged for remove wayPoint QCOMPARE(spy.count(), 2); // 2 listChanged for remove wayPoint
QSignalSpy spyDestroyed(uas->getWaypointManager(), SIGNAL(destroyed())); QSignalSpy spyDestroyed(uas->getWaypointManager(), SIGNAL(destroyed()));
QVERIFY(spyDestroyed.isValid()); QVERIFY(spyDestroyed.isValid());
QCOMPARE( spyDestroyed.count(), 0 ); QCOMPARE( spyDestroyed.count(), 0 );
delete uas;// delete(destroyed) uas for validating delete uas;// delete(destroyed) uas for validating
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,UASID);
QSignalSpy spy2(uas->getWaypointManager(), SIGNAL(waypointListChanged())); 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");
uas->getWaypointManager()->addWaypointEditable(wp, true); uas->getWaypointManager()->addWaypointEditable(wp2, true);
QCOMPARE(spy2.count(), 1); QCOMPARE(spy2.count(), 1);
uas->getWaypointManager()->clearWaypointList(); uas->getWaypointManager()->clearWaypointList();
QVector<Waypoint*> wpList = uas->getWaypointManager()->getWaypointEditableList(); QVector<Waypoint*> wpList = uas->getWaypointManager()->getWaypointEditableList();
QCOMPARE(wpList.count(), 1); QCOMPARE(wpList.count(), 1);
delete wp2;
} }
void UASUnitTest::signalUASLink_test() void UASUnitTest::signalUASLink_test()

Loading…
Cancel
Save