UASUnitTest.cc 9.47 KB
Newer Older
1 2 3 4 5 6 7 8
#include "UASUnitTest.h"

UASUnitTest::UASUnitTest()
{
}

void UASUnitTest::initTestCase()
{
9 10
    mav = new MAVLinkProtocol();
    uas = new UAS(mav,UASID);
11 12 13 14
}

void UASUnitTest::cleanupTestCase()
{
15 16
  delete uas;
  delete mav;
17 18 19 20 21 22 23 24 25 26 27 28
}

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

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

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

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

}

void UASUnitTest::getUpTime_test()
{
46 47 48 49
    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);
50

51 52
    // Sleep for three seconds
    QTest::qSleep(3000);
53

54 55 56
    // Test that the up time is computed correctly to a
    // precision of seconds
    QCOMPARE(floor(uas2->getUptime()/1000.0), 3.0);
57

58
    delete uas2;
59 60 61 62
}

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

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

void UASUnitTest::getStatusForCode_test()
{
88 89 90
    QString state, desc;
    state = "";
    desc = "";
91

92 93
    uas->getStatusForCode(MAV_STATE_UNINIT, state, desc);
    QVERIFY(state == "UNINIT");
94

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

98 99
    uas->getStatusForCode(MAV_STATE_BOOT, state, desc);
    QVERIFY(state == "BOOT");
100

101 102
    uas->getStatusForCode(MAV_STATE_CALIBRATING, state, desc);
    QVERIFY(state == "CALIBRATING");
103

104 105
    uas->getStatusForCode(MAV_STATE_ACTIVE, state, desc);
    QVERIFY(state == "ACTIVE");
106

107 108
    uas->getStatusForCode(MAV_STATE_STANDBY, state, desc);
    QVERIFY(state == "STANDBY");
109

110 111
    uas->getStatusForCode(MAV_STATE_CRITICAL, state, desc);
    QVERIFY(state == "CRITICAL");
112

113 114
    uas->getStatusForCode(MAV_STATE_EMERGENCY, state, desc);
    QVERIFY(state == "EMERGENCY");
115

116 117
    uas->getStatusForCode(MAV_STATE_POWEROFF, state, desc);
    QVERIFY(state == "SHUTDOWN");
118

119 120
    uas->getStatusForCode(5325, state, desc);
    QVERIFY(state == "UNKNOWN");
121 122 123 124
}

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

void UASUnitTest::getSelected_test()
160
{
161
    QCOMPARE(uas->getSelected(), false);
162 163
}

164
void UASUnitTest::getSystemType_test()
165
{
166
    QCOMPARE(uas->getSystemType(), 13);
167 168
}

169
void UASUnitTest::getAirframe_test()
170
{
171 172 173 174
    QCOMPARE(uas->getAirframe(), 0);

    uas->setAirframe(25);
    QVERIFY(uas->getAirframe() == 25);
175 176
}

177
void UASUnitTest::getWaypointList_test()
178
{
179
    QVector<Waypoint*> kk = uas->getWaypointManager()->getWaypointEditableList();
180 181
    QCOMPARE(kk.count(), 0);

182 183
    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);
184

185
    kk = uas->getWaypointManager()->getWaypointEditableList();
186 187 188
    QCOMPARE(kk.count(), 1);

    wp = new Waypoint();
189
    uas->getWaypointManager()->addWaypointEditable(wp, false);
190

191
    kk = uas->getWaypointManager()->getWaypointEditableList();
192 193 194
    QCOMPARE(kk.count(), 2);

    uas->getWaypointManager()->removeWaypoint(1);
195
    kk = uas->getWaypointManager()->getWaypointEditableList();
196 197 198
    QCOMPARE(kk.count(), 1);

    uas->getWaypointManager()->removeWaypoint(0);
199
    kk = uas->getWaypointManager()->getWaypointEditableList();
200 201 202 203 204 205 206
    QCOMPARE(kk.count(), 0);

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

void UASUnitTest::getWaypoint_test()
{
207
    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");
208

209
    uas->getWaypointManager()->addWaypointEditable(wp, true);
210

211
    QVector<Waypoint*> wpList = uas->getWaypointManager()->getWaypointEditableList();
212 213 214 215 216

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

    wp = new Waypoint(0, 5.6, 2, 3);
217
    uas->getWaypointManager()->addWaypointEditable(wp, true);
218 219 220 221 222
    Waypoint* wp2 = static_cast<Waypoint*>(wpList.at(0));

    QCOMPARE(wp->getX(), wp2->getX());
    QCOMPARE(wp->getFrame(), MAV_FRAME_GLOBAL);
    QCOMPARE(wp->getFrame(), wp2->getFrame());
223 224
}

225
void UASUnitTest::signalWayPoint_test()
226
{
227
    QSignalSpy spy(uas->getWaypointManager(), SIGNAL(waypointListChanged()));
228 229 230
	
    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);
231 232 233 234 235 236 237 238 239 240 241 242 243 244 245 246

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

247
    uas->getWaypointManager()->addWaypointEditable(wp, true);
248 249 250
    QCOMPARE(spy2.count(), 1);

    uas->getWaypointManager()->clearWaypointList();
251
    QVector<Waypoint*> wpList = uas->getWaypointManager()->getWaypointEditableList();
252
    QCOMPARE(wpList.count(), 1);
253 254
}

255
void UASUnitTest::signalUASLink_test()
256
{
257 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
    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);
311 312
}

313
void UASUnitTest::signalIdUASLink_test()
314
{
315 316 317 318 319 320 321 322 323 324 325 326 327 328 329 330 331 332 333
    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"));
334
}