Newer
Older
Mariano Lizarraga
committed
#include "UASUnitTest.h"
UASUnitTest::UASUnitTest()
{
}
void UASUnitTest::initTestCase()
{
mav= new MAVLinkProtocol();
link = new SerialLink();
uas=new UAS(mav,UASID);
Mariano Lizarraga
committed
}
void UASUnitTest::cleanupTestCase()
{
Mariano Lizarraga
committed
delete uas;
delete mav;
Mariano Lizarraga
committed
}
void UASUnitTest::getUASID_test()
{
// Test a default ID of zero is assigned
UAS* uas2 = new UAS(mav);
QCOMPARE(uas2->getUASID(), 0);
delete uas2;
// Test that the chosen ID was assigned at construction
QCOMPARE(uas->getUASID(), UASID);
// Make sure that no other ID was sert
QEXPECT_FAIL("", "When you set an ID it does not use the default ID of 0", Continue);
QCOMPARE(uas->getUASID(), 0);
Mariano Lizarraga
committed
// Make sure that ID >= 0
QCOMPARE(uas->getUASID(), 100);
Mariano Lizarraga
committed
}
void UASUnitTest::getUASName_test()
{
Mariano Lizarraga
committed
// Test that the name is build as MAV + ID
QCOMPARE(uas->getUASName(), "MAV " + QString::number(UASID));
Mariano Lizarraga
committed
}
void UASUnitTest::getUpTime_test()
{
UAS* uas2 = new UAS(mav);
// Test that the uptime starts at zero to a
// precision of seconds
QCOMPARE(floor(uas2->getUptime()/1000.0), 0.0);
Mariano Lizarraga
committed
// Sleep for three seconds
QTest::qSleep(3000);
Mariano Lizarraga
committed
// Test that the up time is computed correctly to a
// precision of seconds
QCOMPARE(floor(uas2->getUptime()/1000.0), 3.0);
Mariano Lizarraga
committed
delete uas2;
Mariano Lizarraga
committed
}
void UASUnitTest::getCommunicationStatus_test()
{
// Verify that upon construction the Comm status is disconnected
QCOMPARE(uas->getCommunicationStatus(), static_cast<int>(UASInterface::COMM_DISCONNECTED));
Mariano Lizarraga
committed
}
void UASUnitTest::filterVoltage_test()
{
float verificar=uas->filterVoltage(0.4f);
// Verify that upon construction the Comm status is disconnected
QCOMPARE(verificar, 8.52f);
Mariano Lizarraga
committed
}
void UASUnitTest:: getAutopilotType_test()
{
int type = uas->getAutopilotType();
// Verify that upon construction the autopilot is set to -1
QCOMPARE(type, -1);
Mariano Lizarraga
committed
}
void UASUnitTest::setAutopilotType_test()
{
uas->setAutopilotType(2);
// Verify that the autopilot is set
QCOMPARE(uas->getAutopilotType(), 2);
Mariano Lizarraga
committed
}
void UASUnitTest::getStatusForCode_test()
{
QString state, desc;
state = "";
desc = "";
Mariano Lizarraga
committed
uas->getStatusForCode(MAV_STATE_UNINIT, state, desc);
QVERIFY(state == "UNINIT");
Mariano Lizarraga
committed
uas->getStatusForCode(MAV_STATE_UNINIT, state, desc);
QVERIFY(state == "UNINIT");
Mariano Lizarraga
committed
uas->getStatusForCode(MAV_STATE_BOOT, state, desc);
QVERIFY(state == "BOOT");
Mariano Lizarraga
committed
uas->getStatusForCode(MAV_STATE_CALIBRATING, state, desc);
QVERIFY(state == "CALIBRATING");
Mariano Lizarraga
committed
uas->getStatusForCode(MAV_STATE_ACTIVE, state, desc);
QVERIFY(state == "ACTIVE");
Mariano Lizarraga
committed
uas->getStatusForCode(MAV_STATE_STANDBY, state, desc);
QVERIFY(state == "STANDBY");
Mariano Lizarraga
committed
uas->getStatusForCode(MAV_STATE_CRITICAL, state, desc);
QVERIFY(state == "CRITICAL");
Mariano Lizarraga
committed
uas->getStatusForCode(MAV_STATE_EMERGENCY, state, desc);
QVERIFY(state == "EMERGENCY");
Mariano Lizarraga
committed
uas->getStatusForCode(MAV_STATE_POWEROFF, state, desc);
QVERIFY(state == "SHUTDOWN");
Mariano Lizarraga
committed
uas->getStatusForCode(5325, state, desc);
QVERIFY(state == "UNKNOWN");
Mariano Lizarraga
committed
}
void UASUnitTest::getLocalX_test()
{
QCOMPARE(uas->getLocalX(), 0.0);
Mariano Lizarraga
committed
}
void UASUnitTest::getLocalY_test()
{
QCOMPARE(uas->getLocalY(), 0.0);
Mariano Lizarraga
committed
}
void UASUnitTest::getLocalZ_test()
{
QCOMPARE(uas->getLocalZ(), 0.0);
Mariano Lizarraga
committed
}
void UASUnitTest::getLatitude_test()
{ QCOMPARE(uas->getLatitude(), 0.0);
}
void UASUnitTest::getLongitude_test()
{
QCOMPARE(uas->getLongitude(), 0.0);
Mariano Lizarraga
committed
}
void UASUnitTest::getAltitude_test()
{
QCOMPARE(uas->getAltitude(), 0.0);
Mariano Lizarraga
committed
}
void UASUnitTest::getRoll_test()
{
QCOMPARE(uas->getRoll(), 0.0);
Mariano Lizarraga
committed
}
void UASUnitTest::getPitch_test()
{
QCOMPARE(uas->getPitch(), 0.0);
Mariano Lizarraga
committed
}
void UASUnitTest::getYaw_test()
{
QCOMPARE(uas->getYaw(), 0.0);
}
Mariano Lizarraga
committed
void UASUnitTest::getSelected_test()
{
Mariano Lizarraga
committed
QCOMPARE(uas->getSelected(), false);
}
Mariano Lizarraga
committed
void UASUnitTest::getSystemType_test()
{
Mariano Lizarraga
committed
QCOMPARE(uas->getSystemType(), 13);
}
Mariano Lizarraga
committed
void UASUnitTest::getAirframe_test()
{
Mariano Lizarraga
committed
QCOMPARE(uas->getAirframe(), 0);
uas->setAirframe(25);
QVERIFY(uas->getAirframe() == 25);
}
Mariano Lizarraga
committed
void UASUnitTest::getWaypointList_test()
{
Mariano Lizarraga
committed
180
181
182
183
184
185
186
187
188
189
190
191
192
193
194
195
196
197
198
199
200
201
202
203
204
205
206
207
208
209
210
211
212
213
214
215
216
217
218
219
220
221
222
223
QVector<Waypoint*> kk = uas->getWaypointManager()->getWaypointList();
QCOMPARE(kk.count(), 0);
Waypoint* wp = new Waypoint(0,0,0,0,0,false, false, 0,0, MAV_FRAME_GLOBAL, MAV_ACTION_NAVIGATE);
uas->getWaypointManager()->addWaypoint(wp, true);
kk = uas->getWaypointManager()->getWaypointList();
QCOMPARE(kk.count(), 1);
wp = new Waypoint();
uas->getWaypointManager()->addWaypoint(wp, false);
kk = uas->getWaypointManager()->getWaypointList();
QCOMPARE(kk.count(), 2);
uas->getWaypointManager()->removeWaypoint(1);
kk = uas->getWaypointManager()->getWaypointList();
QCOMPARE(kk.count(), 1);
uas->getWaypointManager()->removeWaypoint(0);
kk = uas->getWaypointManager()->getWaypointList();
QCOMPARE(kk.count(), 0);
qDebug()<<"disconnect SIGNAL waypointListChanged";
}
void UASUnitTest::getWaypoint_test()
{
Waypoint* wp = new Waypoint(0,5.6,0,0,0,false, false, 0,0, MAV_FRAME_GLOBAL, MAV_ACTION_NAVIGATE);
uas->getWaypointManager()->addWaypoint(wp, true);
QVector<Waypoint*> wpList = uas->getWaypointManager()->getWaypointList();
QCOMPARE(wpList.count(), 1);
QCOMPARE(static_cast<quint16>(0), static_cast<Waypoint*>(wpList.at(0))->getId());
wp = new Waypoint(0, 5.6, 2, 3);
uas->getWaypointManager()->addWaypoint(wp, true);
Waypoint* wp2 = static_cast<Waypoint*>(wpList.at(0));
QCOMPARE(wp->getX(), wp2->getX());
QCOMPARE(wp->getFrame(), MAV_FRAME_GLOBAL);
QCOMPARE(wp->getFrame(), wp2->getFrame());
}
Mariano Lizarraga
committed
void UASUnitTest::signalWayPoint_test()
{
Mariano Lizarraga
committed
228
229
230
231
232
233
234
235
236
237
238
239
240
241
242
243
244
245
246
247
248
249
250
251
252
253
QSignalSpy spy(uas->getWaypointManager(), SIGNAL(waypointListChanged()));
Waypoint* wp = new Waypoint(0,5.6,0,0,0,false, false, 0,0, MAV_FRAME_GLOBAL, MAV_ACTION_NAVIGATE);
uas->getWaypointManager()->addWaypoint(wp, true);
QCOMPARE(spy.count(), 1); // 1 listChanged for add wayPoint
uas->getWaypointManager()->removeWaypoint(0);
QCOMPARE(spy.count(), 2); // 2 listChanged for remove wayPoint
QSignalSpy spyDestroyed(uas->getWaypointManager(), SIGNAL(destroyed()));
QVERIFY(spyDestroyed.isValid());
QCOMPARE( spyDestroyed.count(), 0 );
delete uas;// delete(destroyed) uas for validating
QCOMPARE(spyDestroyed.count(), 1);// count destroyed uas should are 1
uas = new UAS(mav,UASID);
QSignalSpy spy2(uas->getWaypointManager(), SIGNAL(waypointListChanged()));
QCOMPARE(spy2.count(), 0);
uas->getWaypointManager()->addWaypoint(wp, true);
QCOMPARE(spy2.count(), 1);
uas->getWaypointManager()->clearWaypointList();
QVector<Waypoint*> wpList = uas->getWaypointManager()->getWaypointList();
QCOMPARE(wpList.count(), 1);
}
Mariano Lizarraga
committed
void UASUnitTest::signalUASLink_test()
{
Mariano Lizarraga
committed
258
259
260
261
262
263
264
265
266
267
268
269
270
271
272
273
274
275
276
277
278
279
280
281
282
283
284
285
286
287
288
289
290
291
292
293
294
295
296
297
298
299
300
301
302
303
304
305
306
307
308
309
310
311
QSignalSpy spy(uas, SIGNAL(modeChanged(int,QString,QString)));
uas->setMode(2);
QCOMPARE(spy.count(), 0);// not solve for UAS not receiving message from UAS
QSignalSpy spyS(LinkManager::instance(), SIGNAL(newLink(LinkInterface*)));
SerialLink* link = new SerialLink();
LinkManager::instance()->add(link);
LinkManager::instance()->addProtocol(link, mav);
QCOMPARE(spyS.count(), 1);
LinkManager::instance()->add(link);
LinkManager::instance()->addProtocol(link, mav);
QCOMPARE(spyS.count(), 1);// not add SerialLink, exist in list
SerialLink* link2 = new SerialLink();
LinkManager::instance()->add(link2);
LinkManager::instance()->addProtocol(link2, mav);
QCOMPARE(spyS.count(), 2);// add SerialLink, not exist in list
QList<LinkInterface*> links = LinkManager::instance()->getLinks();
foreach(LinkInterface* link, links)
{
qDebug()<< link->getName();
qDebug()<< QString::number(link->getId());
qDebug()<< QString::number(link->getNominalDataRate());
QVERIFY(link != NULL);
uas->addLink(link);
}
SerialLink* ff = static_cast<SerialLink*>(uas->getLinks()->at(0));
QCOMPARE(ff->isConnected(), false);
QCOMPARE(ff->isRunning(), false);
QCOMPARE(ff->isFinished(), false);
QCOMPARE(links.count(), uas->getLinks()->count());
QCOMPARE(uas->getLinks()->count(), 2);
LinkInterface* ff99 = static_cast<LinkInterface*>(links.at(1));
LinkManager::instance()->removeLink(ff99);
QCOMPARE(LinkManager::instance()->getLinks().count(), 1);
QCOMPARE(uas->getLinks()->count(), 2);
QCOMPARE(static_cast<LinkInterface*>(LinkManager::instance()->getLinks().at(0))->getId(),
static_cast<LinkInterface*>(uas->getLinks()->at(0))->getId());
link = new SerialLink();
LinkManager::instance()->add(link);
LinkManager::instance()->addProtocol(link, mav);
QCOMPARE(spyS.count(), 3);
}
Mariano Lizarraga
committed
void UASUnitTest::signalIdUASLink_test()
{
Mariano Lizarraga
committed
SerialLink* myLink = new SerialLink();
myLink->setPortName("COM 17");
LinkManager::instance()->add(myLink);
LinkManager::instance()->addProtocol(myLink, mav);
myLink = new SerialLink();
myLink->setPortName("COM 18");
LinkManager::instance()->add(myLink);
LinkManager::instance()->addProtocol(myLink, mav);
QCOMPARE(LinkManager::instance()->getLinks().count(), 4);
QList<LinkInterface*> links = LinkManager::instance()->getLinks();
LinkInterface* a = static_cast<LinkInterface*>(links.at(2));
LinkInterface* b = static_cast<LinkInterface*>(links.at(3));
QCOMPARE(a->getName(), QString("serial port COM 17"));
QCOMPARE(b->getName(), QString("serial port COM 18"));