UASUnitTest.cc 8.61 KB
Newer Older
1
#include "UASUnitTest.h"
2
#include <stdio.h>
3
#include <QObject>
Lorenz Meier's avatar
Lorenz Meier committed
4 5
#include <QThread>

6 7 8
UASUnitTest::UASUnitTest()
{
}
9 10
//This function is called after every test
void UASUnitTest::init()
11
{
12
    mav = new MAVLinkProtocol();
Lorenz Meier's avatar
Lorenz Meier committed
13
    uas = new UAS(mav, QThread::currentThread(), UASID);
14
    uas->deleteSettings();
15
}
16 17
//this function is called after every test
void UASUnitTest::cleanup()
18
{
19 20 21 22 23
    delete uas;
    uas = NULL;

    delete mav;
    mav = NULL;
24 25 26 27 28
}

void UASUnitTest::getUASID_test()
{
    // Test a default ID of zero is assigned
Lorenz Meier's avatar
Lorenz Meier committed
29
    UAS* uas2 = new UAS(mav, QThread::currentThread());
30 31 32 33 34 35
    QCOMPARE(uas2->getUASID(), 0);
    delete uas2;

    // Test that the chosen ID was assigned at construction
    QCOMPARE(uas->getUASID(), UASID);

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

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

43 44 45 46
}

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

}

void UASUnitTest::getUpTime_test()
{
Lorenz Meier's avatar
Lorenz Meier committed
54
    UAS* uas2 = new UAS(mav, QThread::currentThread());
55 56 57
    // Test that the uptime starts at zero to a
    // precision of seconds
    QCOMPARE(floor(uas2->getUptime()/1000.0), 0.0);
58

59 60
    // Sleep for three seconds
    QTest::qSleep(3000);
61

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

66
    delete uas2;
67 68 69 70
}

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

void UASUnitTest::filterVoltage_test()
{
    float verificar=uas->filterVoltage(0.4f);
78 79 80 81 82

    // We allow the voltage returned to be within a small delta
    const float allowedDelta = 0.05f;
    const float desiredVoltage = 7.36f;
    QVERIFY(verificar > (desiredVoltage - allowedDelta) && verificar < (desiredVoltage + allowedDelta));
83
}
84

85 86
void UASUnitTest:: getAutopilotType_test()
{
87 88 89
    int type = uas->getAutopilotType();
    // Verify that upon construction the autopilot is set to -1
    QCOMPARE(type, -1);
90
}
91

92 93
void UASUnitTest::setAutopilotType_test()
{
94 95 96
    uas->setAutopilotType(2);
    // Verify that the autopilot is set
    QCOMPARE(uas->getAutopilotType(), 2);
97 98
}

99
//verify that the correct status is returned if a certain statue is given to uas
100 101
void UASUnitTest::getStatusForCode_test()
{
102 103 104
    QString state, desc;
    state = "";
    desc = "";
105

106 107
    uas->getStatusForCode(MAV_STATE_UNINIT, state, desc);
    QVERIFY(state == "UNINIT");
108

109 110
    uas->getStatusForCode(MAV_STATE_UNINIT, state, desc);
    QVERIFY(state == "UNINIT");
111

112 113
    uas->getStatusForCode(MAV_STATE_BOOT, state, desc);
    QVERIFY(state == "BOOT");
114

115 116
    uas->getStatusForCode(MAV_STATE_CALIBRATING, state, desc);
    QVERIFY(state == "CALIBRATING");
117

118 119
    uas->getStatusForCode(MAV_STATE_ACTIVE, state, desc);
    QVERIFY(state == "ACTIVE");
120

121 122
    uas->getStatusForCode(MAV_STATE_STANDBY, state, desc);
    QVERIFY(state == "STANDBY");
123

124 125
    uas->getStatusForCode(MAV_STATE_CRITICAL, state, desc);
    QVERIFY(state == "CRITICAL");
126

127 128
    uas->getStatusForCode(MAV_STATE_EMERGENCY, state, desc);
    QVERIFY(state == "EMERGENCY");
129

130 131
    uas->getStatusForCode(MAV_STATE_POWEROFF, state, desc);
    QVERIFY(state == "SHUTDOWN");
132

133 134
    uas->getStatusForCode(5325, state, desc);
    QVERIFY(state == "UNKNOWN");
135 136 137 138
}

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

void UASUnitTest::getSelected_test()
179
{
180
    QCOMPARE(uas->getSelected(), false);
181 182
}

183
void UASUnitTest::getSystemType_test()
184 185 186
{    //check that system type is set to MAV_TYPE_GENERIC when initialized
    QCOMPARE(uas->getSystemType(), 0);
    uas->setSystemType(13);
187
    QCOMPARE(uas->getSystemType(), 13);
188 189
}

190
void UASUnitTest::getAirframe_test()
191
{
192 193
    //when uas is constructed, airframe is set to QGC_AIRFRAME_GENERIC
    QVERIFY(uas->getAirframe() == UASInterface::QGC_AIRFRAME_GENERIC);
194
}
195

196 197
void UASUnitTest::setAirframe_test()
{
198
    //check at construction, that airframe=0 (GENERIC)
199
    QVERIFY(uas->getAirframe() == UASInterface::QGC_AIRFRAME_GENERIC);
200 201

    //check that set airframe works
202 203
    uas->setAirframe(UASInterface::QGC_AIRFRAME_HEXCOPTER);
    QVERIFY(uas->getAirframe() == UASInterface::QGC_AIRFRAME_HEXCOPTER);
204 205 206

    //check that setAirframe will not assign a number to airframe, that is 
    //not defined in the enum 
207 208
    uas->setAirframe(UASInterface::QGC_AIRFRAME_END_OF_ENUM);
    QVERIFY(uas->getAirframe() == UASInterface::QGC_AIRFRAME_HEXCOPTER);
209
}
210

211
void UASUnitTest::getWaypointList_test()
212
{
Don Gagne's avatar
Don Gagne committed
213
    QList<Waypoint*> kk = uas->getWaypointManager()->getWaypointEditableList();
214 215
    QCOMPARE(kk.count(), 0);

216 217
    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);
218

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

    wp = new Waypoint();
223
    uas->getWaypointManager()->addWaypointEditable(wp, false);
224

225
    kk = uas->getWaypointManager()->getWaypointEditableList();
226 227 228
    QCOMPARE(kk.count(), 2);

    uas->getWaypointManager()->removeWaypoint(1);
229
    kk = uas->getWaypointManager()->getWaypointEditableList();
230 231 232
    QCOMPARE(kk.count(), 1);

    uas->getWaypointManager()->removeWaypoint(0);
233
    kk = uas->getWaypointManager()->getWaypointEditableList();
234 235 236
    QCOMPARE(kk.count(), 0);

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

238 239 240 241
}

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

244
    uas->getWaypointManager()->addWaypointEditable(wp, true);
245

Don Gagne's avatar
Don Gagne committed
246
    QList<Waypoint*> wpList = uas->getWaypointManager()->getWaypointEditableList();
247 248 249 250

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

Jessica's avatar
Jessica committed
251
    Waypoint*  wp3 = new Waypoint(1, 5.6, 2.0, 3.0);
Jessica's avatar
Jessica committed
252
    uas->getWaypointManager()->addWaypointEditable(wp3, true);
Jessica's avatar
Jessica committed
253
    wpList = uas->getWaypointManager()->getWaypointEditableList();
254 255
    Waypoint* wp2 = static_cast<Waypoint*>(wpList.at(0));

Jessica's avatar
Jessica committed
256
    QCOMPARE(wpList.count(), 2);
Jessica's avatar
Jessica committed
257 258 259
    QCOMPARE(wp3->getX(), wp2->getX());
    QCOMPARE(wp3->getY(), wp2->getY());
    QCOMPARE(wp3->getZ(), wp2->getZ());
Jessica's avatar
Jessica committed
260
    QCOMPARE(wpList.at(1)->getId(), static_cast<quint16>(1));
Jessica's avatar
Jessica committed
261 262
    QCOMPARE(wp3->getFrame(), MAV_FRAME_GLOBAL);
    QCOMPARE(wp3->getFrame(), wp2->getFrame());
Jessica's avatar
Jessica committed
263

Jessica's avatar
Jessica committed
264 265
    delete wp3;
    delete wp;
266 267
}

268
void UASUnitTest::signalWayPoint_test()
269
{
Jessica's avatar
Jessica committed
270 271
    QSignalSpy spy(uas->getWaypointManager(), SIGNAL(waypointEditableListChanged()));

Jessica's avatar
Jessica committed
272
    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");
273
    uas->getWaypointManager()->addWaypointEditable(wp, true);
274

275
    QCOMPARE(spy.count(), 1); // 1 listChanged for add wayPoint
276 277
    uas->getWaypointManager()->removeWaypoint(0);
    QCOMPARE(spy.count(), 2); // 2 listChanged for remove wayPoint
Jessica's avatar
Jessica committed
278

279 280 281 282 283
    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
284
    uas = NULL;
285
    QCOMPARE(spyDestroyed.count(), 1);// count destroyed uas should are 1
Lorenz Meier's avatar
Lorenz Meier committed
286
    uas = new UAS(mav, QThread::currentThread(), UASID);
Jessica's avatar
Jessica committed
287
    QSignalSpy spy2(uas->getWaypointManager(), SIGNAL(waypointEditableListChanged()));
288
    QCOMPARE(spy2.count(), 0);
Jessica's avatar
Jessica committed
289
    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");
290

Jessica's avatar
Jessica committed
291
    uas->getWaypointManager()->addWaypointEditable(wp2, true);
292 293 294
    QCOMPARE(spy2.count(), 1);

    uas->getWaypointManager()->clearWaypointList();
Don Gagne's avatar
Don Gagne committed
295
    QList<Waypoint*> wpList = uas->getWaypointManager()->getWaypointEditableList();
296
    QCOMPARE(wpList.count(), 1);
297 298
    delete uas;
    uas = NULL;
Jessica's avatar
Jessica committed
299
    delete wp2;
300
}