UASUnitTest.cc 12.4 KB
Newer Older
1
#include "UASUnitTest.h"
2
#include <stdio.h>
3
#include <QObject>
4 5 6
UASUnitTest::UASUnitTest()
{
}
7 8
//This function is called after every test
void UASUnitTest::init()
9
{
10
    mav = new MAVLinkProtocol();
11 12
    uas = new UAS(mav, UASID);
    uas->deleteSettings();
13
}
14 15
//this function is called after every test
void UASUnitTest::cleanup()
16
{
17 18 19 20 21
    delete uas;
    uas = NULL;

    delete mav;
    mav = NULL;
22 23 24 25 26 27 28 29 30 31 32 33
}

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);

34
    // Make sure that no other ID was set
35 36
    QEXPECT_FAIL("", "When you set an ID it does not use the default ID of 0", Continue);
    QCOMPARE(uas->getUASID(), 0);
37 38 39

    // Make sure that ID >= 0
    QCOMPARE(uas->getUASID(), 100);
40

41 42 43 44
}

void UASUnitTest::getUASName_test()
{
45 46
  // Test that the name is build as MAV + ID
  QCOMPARE(uas->getUASName(), "MAV " + QString::number(UASID));
47 48 49 50 51

}

void UASUnitTest::getUpTime_test()
{
52 53 54 55
    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);
56

57 58
    // Sleep for three seconds
    QTest::qSleep(3000);
59

60 61 62
    // Test that the up time is computed correctly to a
    // precision of seconds
    QCOMPARE(floor(uas2->getUptime()/1000.0), 3.0);
63

64
    delete uas2;
65 66 67 68
}

void UASUnitTest::getCommunicationStatus_test()
{
69 70
    // Verify that upon construction the Comm status is disconnected
    QCOMPARE(uas->getCommunicationStatus(), static_cast<int>(UASInterface::COMM_DISCONNECTED));
71 72 73 74 75
}

void UASUnitTest::filterVoltage_test()
{
    float verificar=uas->filterVoltage(0.4f);
76 77
    // Verify that upon construction the Comm status is disconnected
    QCOMPARE(verificar, 8.52f);
78 79 80
}
void UASUnitTest:: getAutopilotType_test()
{
81 82 83
    int type = uas->getAutopilotType();
    // Verify that upon construction the autopilot is set to -1
    QCOMPARE(type, -1);
84 85 86
}
void UASUnitTest::setAutopilotType_test()
{
87 88 89
    uas->setAutopilotType(2);
    // Verify that the autopilot is set
    QCOMPARE(uas->getAutopilotType(), 2);
90 91
}

92
//verify that the correct status is returned if a certain statue is given to uas
93 94
void UASUnitTest::getStatusForCode_test()
{
95 96 97
    QString state, desc;
    state = "";
    desc = "";
98

99 100
    uas->getStatusForCode(MAV_STATE_UNINIT, state, desc);
    QVERIFY(state == "UNINIT");
101

102 103
    uas->getStatusForCode(MAV_STATE_UNINIT, state, desc);
    QVERIFY(state == "UNINIT");
104

105 106
    uas->getStatusForCode(MAV_STATE_BOOT, state, desc);
    QVERIFY(state == "BOOT");
107

108 109
    uas->getStatusForCode(MAV_STATE_CALIBRATING, state, desc);
    QVERIFY(state == "CALIBRATING");
110

111 112
    uas->getStatusForCode(MAV_STATE_ACTIVE, state, desc);
    QVERIFY(state == "ACTIVE");
113

114 115
    uas->getStatusForCode(MAV_STATE_STANDBY, state, desc);
    QVERIFY(state == "STANDBY");
116

117 118
    uas->getStatusForCode(MAV_STATE_CRITICAL, state, desc);
    QVERIFY(state == "CRITICAL");
119

120 121
    uas->getStatusForCode(MAV_STATE_EMERGENCY, state, desc);
    QVERIFY(state == "EMERGENCY");
122

123 124
    uas->getStatusForCode(MAV_STATE_POWEROFF, state, desc);
    QVERIFY(state == "SHUTDOWN");
125

126 127
    uas->getStatusForCode(5325, state, desc);
    QVERIFY(state == "UNKNOWN");
128 129 130 131
}

void UASUnitTest::getLocalX_test()
{
132
   QCOMPARE(uas->getLocalX(), 0.0);
133 134 135
}
void UASUnitTest::getLocalY_test()
{
136
    QCOMPARE(uas->getLocalY(), 0.0);
137 138 139
}
void UASUnitTest::getLocalZ_test()
{
140
    QCOMPARE(uas->getLocalZ(), 0.0);
141 142
}
void UASUnitTest::getLatitude_test()
Jessica's avatar
Jessica committed
143 144
{
    QCOMPARE(uas->getLatitude(), 0.0);
145 146 147
}
void UASUnitTest::getLongitude_test()
{
148
    QCOMPARE(uas->getLongitude(), 0.0);
149
}
Don Gagne's avatar
Don Gagne committed
150
void UASUnitTest::getAltitudeAMSL_test()
151
{
Don Gagne's avatar
Don Gagne committed
152 153 154 155 156
    QCOMPARE(uas->getAltitudeAMSL(), 0.0);
}
void UASUnitTest::getAltitudeRelative_test()
{
    QCOMPARE(uas->getAltitudeRelative(), 0.0);
157 158 159
}
void UASUnitTest::getRoll_test()
{
160
    QCOMPARE(uas->getRoll(), 0.0);
161 162 163
}
void UASUnitTest::getPitch_test()
{
164
    QCOMPARE(uas->getPitch(), 0.0);
165 166 167
}
void UASUnitTest::getYaw_test()
{
168 169
    QCOMPARE(uas->getYaw(), 0.0);
}
170 171

void UASUnitTest::getSelected_test()
172
{
173
    QCOMPARE(uas->getSelected(), false);
174 175
}

176
void UASUnitTest::getSystemType_test()
177 178 179
{    //check that system type is set to MAV_TYPE_GENERIC when initialized
    QCOMPARE(uas->getSystemType(), 0);
    uas->setSystemType(13);
180
    QCOMPARE(uas->getSystemType(), 13);
181 182
}

183
void UASUnitTest::getAirframe_test()
184
{
185 186
    //when uas is constructed, airframe is set to QGC_AIRFRAME_GENERIC
    QVERIFY(uas->getAirframe() == UASInterface::QGC_AIRFRAME_GENERIC);
187
}
188

189 190
void UASUnitTest::setAirframe_test()
{
191
    //check at construction, that airframe=0 (GENERIC)
192
    QVERIFY(uas->getAirframe() == UASInterface::QGC_AIRFRAME_GENERIC);
193 194

    //check that set airframe works
195 196
    uas->setAirframe(UASInterface::QGC_AIRFRAME_HEXCOPTER);
    QVERIFY(uas->getAirframe() == UASInterface::QGC_AIRFRAME_HEXCOPTER);
197 198 199

    //check that setAirframe will not assign a number to airframe, that is 
    //not defined in the enum 
200 201
    uas->setAirframe(UASInterface::QGC_AIRFRAME_END_OF_ENUM);
    QVERIFY(uas->getAirframe() == UASInterface::QGC_AIRFRAME_HEXCOPTER);
202
}
203

204
void UASUnitTest::getWaypointList_test()
205
{
Don Gagne's avatar
Don Gagne committed
206
    QList<Waypoint*> kk = uas->getWaypointManager()->getWaypointEditableList();
207 208
    QCOMPARE(kk.count(), 0);

209 210
    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");
    uas->getWaypointManager()->addWaypointEditable(wp, true);
211

212
    kk = uas->getWaypointManager()->getWaypointEditableList();
213 214 215
    QCOMPARE(kk.count(), 1);

    wp = new Waypoint();
216
    uas->getWaypointManager()->addWaypointEditable(wp, false);
217

218
    kk = uas->getWaypointManager()->getWaypointEditableList();
219 220 221
    QCOMPARE(kk.count(), 2);

    uas->getWaypointManager()->removeWaypoint(1);
222
    kk = uas->getWaypointManager()->getWaypointEditableList();
223 224 225
    QCOMPARE(kk.count(), 1);

    uas->getWaypointManager()->removeWaypoint(0);
226
    kk = uas->getWaypointManager()->getWaypointEditableList();
227 228 229
    QCOMPARE(kk.count(), 0);

    qDebug()<<"disconnect SIGNAL waypointListChanged";
230

231 232 233 234
}

void UASUnitTest::getWaypoint_test()
{
Jessica's avatar
Jessica committed
235
    Waypoint* wp = new Waypoint(0,5.6,2.0,3.0,0.0,0.0,0.0,0.0,false, false, MAV_FRAME_GLOBAL, MAV_CMD_MISSION_START, "blah");
236

237
    uas->getWaypointManager()->addWaypointEditable(wp, true);
238

Don Gagne's avatar
Don Gagne committed
239
    QList<Waypoint*> wpList = uas->getWaypointManager()->getWaypointEditableList();
240 241 242 243

    QCOMPARE(wpList.count(), 1);
    QCOMPARE(static_cast<quint16>(0), static_cast<Waypoint*>(wpList.at(0))->getId());

Jessica's avatar
Jessica committed
244
    Waypoint*  wp3 = new Waypoint(1, 5.6, 2.0, 3.0);
Jessica's avatar
Jessica committed
245
    uas->getWaypointManager()->addWaypointEditable(wp3, true);
Jessica's avatar
Jessica committed
246
    wpList = uas->getWaypointManager()->getWaypointEditableList();
247 248
    Waypoint* wp2 = static_cast<Waypoint*>(wpList.at(0));

Jessica's avatar
Jessica committed
249
    QCOMPARE(wpList.count(), 2);
Jessica's avatar
Jessica committed
250 251 252
    QCOMPARE(wp3->getX(), wp2->getX());
    QCOMPARE(wp3->getY(), wp2->getY());
    QCOMPARE(wp3->getZ(), wp2->getZ());
Jessica's avatar
Jessica committed
253
    QCOMPARE(wpList.at(1)->getId(), static_cast<quint16>(1));
Jessica's avatar
Jessica committed
254 255
    QCOMPARE(wp3->getFrame(), MAV_FRAME_GLOBAL);
    QCOMPARE(wp3->getFrame(), wp2->getFrame());
Jessica's avatar
Jessica committed
256

Jessica's avatar
Jessica committed
257 258
    delete wp3;
    delete wp;
259 260
}

261
void UASUnitTest::signalWayPoint_test()
262
{
Jessica's avatar
Jessica committed
263 264
    QSignalSpy spy(uas->getWaypointManager(), SIGNAL(waypointEditableListChanged()));

Jessica's avatar
Jessica committed
265
    Waypoint* wp = new Waypoint(0,1.0,0.0,0.0,0.0,0.0,0.0,0.0,false, false, MAV_FRAME_GLOBAL, MAV_CMD_MISSION_START, "blah");
266
    uas->getWaypointManager()->addWaypointEditable(wp, true);
267

268
    QCOMPARE(spy.count(), 1); // 1 listChanged for add wayPoint
269 270
    uas->getWaypointManager()->removeWaypoint(0);
    QCOMPARE(spy.count(), 2); // 2 listChanged for remove wayPoint
Jessica's avatar
Jessica committed
271

272 273 274 275 276
    QSignalSpy spyDestroyed(uas->getWaypointManager(), SIGNAL(destroyed()));
    QVERIFY(spyDestroyed.isValid());
    QCOMPARE( spyDestroyed.count(), 0 );

    delete uas;// delete(destroyed) uas for validating
Jessica's avatar
Jessica committed
277
    uas = NULL;
278 279
    QCOMPARE(spyDestroyed.count(), 1);// count destroyed uas should are 1
    uas = new UAS(mav,UASID);
Jessica's avatar
Jessica committed
280
    QSignalSpy spy2(uas->getWaypointManager(), SIGNAL(waypointEditableListChanged()));
281
    QCOMPARE(spy2.count(), 0);
Jessica's avatar
Jessica committed
282
    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");
283

Jessica's avatar
Jessica committed
284
    uas->getWaypointManager()->addWaypointEditable(wp2, true);
285 286 287
    QCOMPARE(spy2.count(), 1);

    uas->getWaypointManager()->clearWaypointList();
Don Gagne's avatar
Don Gagne committed
288
    QList<Waypoint*> wpList = uas->getWaypointManager()->getWaypointEditableList();
289
    QCOMPARE(wpList.count(), 1);
290 291
    delete uas;
    uas = NULL;
Jessica's avatar
Jessica committed
292
    delete wp2;
293 294
}

295
void UASUnitTest::signalUASLink_test()
296
{
297

298
    QSignalSpy spy(uas, SIGNAL(modeChanged(int,QString,QString)));
Don Gagne's avatar
Don Gagne committed
299
    uas->setMode(2, 0);
300 301 302 303
    QCOMPARE(spy.count(), 0);// not solve for UAS not receiving message from UAS

    QSignalSpy spyS(LinkManager::instance(), SIGNAL(newLink(LinkInterface*)));
    SerialLink* link = new SerialLink();
304

305 306 307 308 309 310 311 312 313 314 315 316 317 318 319 320 321 322 323 324 325 326 327 328 329 330 331 332 333 334 335 336 337 338 339
    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());
        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);
340
    delete link2;
341 342 343 344 345 346 347

    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());

348 349 350
    SerialLink* link3 = new SerialLink();
    LinkManager::instance()->add(link3);
    LinkManager::instance()->addProtocol(link3, mav);
351
    QCOMPARE(spyS.count(), 3);
352 353
    QCOMPARE(LinkManager::instance()->getLinks().count(), 2);

354 355
    //all the links in LinkManager must be deleted because LinkManager::instance
    //is static. 
356 357 358 359 360
    LinkManager::instance()->removeLink(link3);
    delete link3;
    QCOMPARE(LinkManager::instance()->getLinks().count(), 1);
    LinkManager::instance()->removeLink(link);
    delete link;
361

362
    QCOMPARE(LinkManager::instance()->getLinks().count(), 0);
363 364
}

365
void UASUnitTest::signalIdUASLink_test()
366
{
367 368

    QCOMPARE(LinkManager::instance()->getLinks().count(), 0);
369 370 371 372 373
    SerialLink* myLink = new SerialLink();
    myLink->setPortName("COM 17");
    LinkManager::instance()->add(myLink);
    LinkManager::instance()->addProtocol(myLink, mav);

374 375 376 377 378 379 380 381 382 383 384 385 386 387
    SerialLink* myLink2 = new SerialLink();
    myLink2->setPortName("COM 18");
    LinkManager::instance()->add(myLink2);
    LinkManager::instance()->addProtocol(myLink2, mav);

    SerialLink* myLink3 = new SerialLink();
    myLink3->setPortName("COM 19");
    LinkManager::instance()->add(myLink3);
    LinkManager::instance()->addProtocol(myLink3, mav);

    SerialLink* myLink4 = new SerialLink();
    myLink4->setPortName("COM 20");
    LinkManager::instance()->add(myLink4);
    LinkManager::instance()->addProtocol(myLink4, mav);
388 389 390 391 392

    QCOMPARE(LinkManager::instance()->getLinks().count(), 4);

    QList<LinkInterface*> links = LinkManager::instance()->getLinks();

393 394 395 396
    LinkInterface* a = static_cast<LinkInterface*>(links.at(0));
    LinkInterface* b = static_cast<LinkInterface*>(links.at(1));
    LinkInterface* c = static_cast<LinkInterface*>(links.at(2));
    LinkInterface* d = static_cast<LinkInterface*>(links.at(3));
397 398 399 400
    QCOMPARE(a->getName(), QString("COM 17"));
    QCOMPARE(b->getName(), QString("COM 18"));
    QCOMPARE(c->getName(), QString("COM 19"));
    QCOMPARE(d->getName(), QString("COM 20"));
401 402 403 404 405 406 407 408 409 410 411

    LinkManager::instance()->removeLink(myLink4);
    delete myLink4;
    LinkManager::instance()->removeLink(myLink3);
    delete myLink3;
    LinkManager::instance()->removeLink(myLink2);
    delete myLink2;
    LinkManager::instance()->removeLink(myLink);
    delete myLink;

    QCOMPARE(LinkManager::instance()->getLinks().count(), 0);
412
}