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

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

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

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

39 40 41 42
}

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

}

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

55 56
    // Sleep for three seconds
    QTest::qSleep(3000);
57

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

62
    delete uas2;
63 64 65 66
}

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

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

void UASUnitTest::getStatusForCode_test()
{
92 93 94
    QString state, desc;
    state = "";
    desc = "";
95

96 97
    uas->getStatusForCode(MAV_STATE_UNINIT, state, desc);
    QVERIFY(state == "UNINIT");
98

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

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

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

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

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

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

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

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

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

126 127 128 129
}

void UASUnitTest::getLocalX_test()
{
130
   QCOMPARE(uas->getLocalX(), 0.0);
131 132 133
}
void UASUnitTest::getLocalY_test()
{
134
    QCOMPARE(uas->getLocalY(), 0.0);
135 136 137
}
void UASUnitTest::getLocalZ_test()
{
138
    QCOMPARE(uas->getLocalZ(), 0.0);
139 140 141 142 143 144
}
void UASUnitTest::getLatitude_test()
{  QCOMPARE(uas->getLatitude(), 0.0);
}
void UASUnitTest::getLongitude_test()
{
145
    QCOMPARE(uas->getLongitude(), 0.0);
146 147 148
}
void UASUnitTest::getAltitude_test()
{
149
    QCOMPARE(uas->getAltitude(), 0.0);
150 151 152
}
void UASUnitTest::getRoll_test()
{
153
    QCOMPARE(uas->getRoll(), 0.0);
154 155 156
}
void UASUnitTest::getPitch_test()
{
157
    QCOMPARE(uas->getPitch(), 0.0);
158 159 160
}
void UASUnitTest::getYaw_test()
{
161 162
    QCOMPARE(uas->getYaw(), 0.0);
}
163 164

void UASUnitTest::getSelected_test()
165
{
166
    QCOMPARE(uas->getSelected(), false);
167 168
}

169
void UASUnitTest::getSystemType_test()
Jessica's avatar
Jessica committed
170 171
{   //best guess: it is not initialized in the constructor,
    //what should it be initialized to?
172
    QCOMPARE(uas->getSystemType(), 13);
173 174
}

175
void UASUnitTest::getAirframe_test()
176
{
177
    //when uas is constructed, airframe is set to QGC_AIRFRAME_GENERIC which is 0
178
    QCOMPARE(uas->getAirframe(), 0);
179
}
180

181 182
void UASUnitTest::setAirframe_test()
{
183 184 185 186 187 188 189 190 191 192 193
    //check at construction, that airframe=0 (GENERIC)
    QVERIFY(uas->getAirframe() == 0);

    //check that set airframe works
    uas->setAirframe(11);
    QVERIFY(uas->getAirframe() == 11);

    //check that setAirframe will not assign a number to airframe, that is 
    //not defined in the enum 
    uas->setAirframe(12);
    QVERIFY(uas->getAirframe() == 11);
194
}
195
void UASUnitTest::getWaypointList_test()
196
{
197
    QVector<Waypoint*> kk = uas->getWaypointManager()->getWaypointEditableList();
198 199
    QCOMPARE(kk.count(), 0);

200 201
    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);
202

203
    kk = uas->getWaypointManager()->getWaypointEditableList();
204 205 206
    QCOMPARE(kk.count(), 1);

    wp = new Waypoint();
207
    uas->getWaypointManager()->addWaypointEditable(wp, false);
208

209
    kk = uas->getWaypointManager()->getWaypointEditableList();
210 211 212
    QCOMPARE(kk.count(), 2);

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

    uas->getWaypointManager()->removeWaypoint(0);
217
    kk = uas->getWaypointManager()->getWaypointEditableList();
218 219 220
    QCOMPARE(kk.count(), 0);

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

222 223 224 225
}

void UASUnitTest::getWaypoint_test()
{
Jessica's avatar
Jessica committed
226
    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");
227

228
    uas->getWaypointManager()->addWaypointEditable(wp, true);
229

230
    QVector<Waypoint*> wpList = uas->getWaypointManager()->getWaypointEditableList();
231 232 233 234

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

Jessica's avatar
Jessica committed
235
    Waypoint*  wp3 = new Waypoint(1, 5.6, 2.0, 3.0);
Jessica's avatar
Jessica committed
236
    uas->getWaypointManager()->addWaypointEditable(wp3, true);
Jessica's avatar
Jessica committed
237
    wpList = uas->getWaypointManager()->getWaypointEditableList();
238 239
    Waypoint* wp2 = static_cast<Waypoint*>(wpList.at(0));

Jessica's avatar
Jessica committed
240
    QCOMPARE(wpList.count(), 2);
Jessica's avatar
Jessica committed
241 242 243
    QCOMPARE(wp3->getX(), wp2->getX());
    QCOMPARE(wp3->getY(), wp2->getY());
    QCOMPARE(wp3->getZ(), wp2->getZ());
Jessica's avatar
Jessica committed
244
    QCOMPARE(wpList.at(1)->getId(), static_cast<quint16>(1));
Jessica's avatar
Jessica committed
245 246
    QCOMPARE(wp3->getFrame(), MAV_FRAME_GLOBAL);
    QCOMPARE(wp3->getFrame(), wp2->getFrame());
Jessica's avatar
Jessica committed
247

Jessica's avatar
Jessica committed
248 249
    delete wp3;
    delete wp;
250 251
}

252
void UASUnitTest::signalWayPoint_test()
253
{
Jessica's avatar
Jessica committed
254
    QSignalSpy spy(uas->getWaypointManager(), SIGNAL(waypointListChanged(UASID)));
255 256 257
	
    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);
258

Jessica's avatar
Jessica committed
259 260
    printf("spy.count = %d\n", spy.count());
    //QCOMPARE(spy.count(), 1); // 1 listChanged for add wayPoint
261 262 263 264 265 266 267 268 269 270 271 272 273
    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);

274
    uas->getWaypointManager()->addWaypointEditable(wp, true);
275 276 277
    QCOMPARE(spy2.count(), 1);

    uas->getWaypointManager()->clearWaypointList();
278
    QVector<Waypoint*> wpList = uas->getWaypointManager()->getWaypointEditableList();
279
    QCOMPARE(wpList.count(), 1);
280

281 282
}

283
void UASUnitTest::signalUASLink_test()
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 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
    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);
339

340 341
}

342
void UASUnitTest::signalIdUASLink_test()
343
{
344 345 346 347 348 349 350 351 352 353 354 355 356 357 358 359 360 361 362
    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"));
363

364
}