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

UASUnitTest::UASUnitTest()
{
}

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

void UASUnitTest::cleanupTestCase()
{
16 17
    delete uas;
    delete mav;
18 19 20 21 22 23 24 25 26 27 28 29 30 31 32 33 34 35 36 37

}

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

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

}

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

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

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

57
    delete uas2;
58 59 60 61
}

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

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

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

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

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

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

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

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

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

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

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

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

118 119
    uas->getStatusForCode(5325, state, desc);
    QVERIFY(state == "UNKNOWN");
120 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 158 159 160 161 162 163 164 165 166 167 168 169 170 171 172 173 174 175 176 177 178 179 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 224 225 226 227 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 254 255 256 257 258 259 260 261 262 263 264 265 266 267 268 269 270 271 272 273 274 275 276 277
    QCOMPARE(uas->getYaw(), 0.0);
}
void UASUnitTest::attitudeLimitsZero_test()
{
    mavlink_message_t msg;
    mavlink_attitude_t att;

    // Set zero values and encode them
    att.roll  = 0.0f;
    att.pitch = 0.0f;
    att.yaw   = 0.0f;
    mavlink_msg_attitude_encode(uas->getUASID(), MAV_COMP_ID_IMU, &msg, &att);
    // Let UAS decode message
    uas->receiveMessage(link, msg);
    // Check result
    QCOMPARE(uas->getRoll(), 0.0);
    QCOMPARE(uas->getPitch(), 0.0);
    QCOMPARE(uas->getYaw(), 0.0);
}

void UASUnitTest::attitudeLimitsPi_test()
{
    mavlink_message_t msg;
    mavlink_attitude_t att;
    // Set PI values and encode them
    att.roll  = M_PI;
    att.pitch = M_PI;
    att.yaw   = M_PI;
    mavlink_msg_attitude_encode(uas->getUASID(), MAV_COMP_ID_IMU, &msg, &att);
    // Let UAS decode message
    uas->receiveMessage(link, msg);
    // Check result
    QVERIFY((uas->getRoll() < M_PI+0.000001) && (uas->getRoll() > M_PI+-0.000001));
    QVERIFY((uas->getPitch() < M_PI+0.000001) && (uas->getPitch() > M_PI+-0.000001));
    QVERIFY((uas->getYaw() < M_PI+0.000001) && (uas->getYaw() > M_PI+-0.000001));
}

void UASUnitTest::attitudeLimitsMinusPi_test()
{
    mavlink_message_t msg;
    mavlink_attitude_t att;
    // Set -PI values and encode them
    att.roll  = -M_PI;
    att.pitch = -M_PI;
    att.yaw   = -M_PI;
    mavlink_msg_attitude_encode(uas->getUASID(), MAV_COMP_ID_IMU, &msg, &att);
    // Let UAS decode message
    uas->receiveMessage(link, msg);
    // Check result
    QVERIFY((uas->getRoll() > -M_PI-0.000001) && (uas->getRoll() < -M_PI+0.000001));
    QVERIFY((uas->getPitch() > -M_PI-0.000001) && (uas->getPitch() < -M_PI+0.000001));
    QVERIFY((uas->getYaw() > -M_PI-0.000001) && (uas->getYaw() < -M_PI+0.000001));
}

void UASUnitTest::attitudeLimitsTwoPi_test()
{
    mavlink_message_t msg;
    mavlink_attitude_t att;
    // Set off-limit values and check
    // correct wrapping
    // Set 2PI values and encode them
    att.roll  = 2*M_PI;
    att.pitch = 2*M_PI;
    att.yaw   = 2*M_PI;
    mavlink_msg_attitude_encode(uas->getUASID(), MAV_COMP_ID_IMU, &msg, &att);
    // Let UAS decode message
    uas->receiveMessage(link, msg);
    // Check result
    QVERIFY((uas->getRoll() < 0.000001) && (uas->getRoll() > -0.000001));
    QVERIFY((uas->getPitch() < 0.000001) && (uas->getPitch() > -0.000001));
    QVERIFY((uas->getYaw() < 0.000001) && (uas->getYaw() > -0.000001));
}

void UASUnitTest::attitudeLimitsMinusTwoPi_test()
{
    mavlink_message_t msg;
    mavlink_attitude_t att;
    // Set -2PI values and encode them
    att.roll  = -2*M_PI;
    att.pitch = -2*M_PI;
    att.yaw   = -2*M_PI;
    mavlink_msg_attitude_encode(uas->getUASID(), MAV_COMP_ID_IMU, &msg, &att);
    // Let UAS decode message
    uas->receiveMessage(link, msg);
    // Check result
    QVERIFY((uas->getRoll() < 0.000001) && (uas->getRoll() > -0.000001));
    QVERIFY((uas->getPitch() < 0.000001) && (uas->getPitch() > -0.000001));
    QVERIFY((uas->getYaw() < 0.000001) && (uas->getYaw() > -0.000001));
}

void UASUnitTest::attitudeLimitsTwoPiOne_test()
{
    mavlink_message_t msg;
    mavlink_attitude_t att;
    // Set over 2 PI values and encode them
    att.roll  = 2*M_PI+1.0f;
    att.pitch = 2*M_PI+1.0f;
    att.yaw   = 2*M_PI+1.0f;
    mavlink_msg_attitude_encode(uas->getUASID(), MAV_COMP_ID_IMU, &msg, &att);
    // Let UAS decode message
    uas->receiveMessage(link, msg);
    // Check result
    QVERIFY((uas->getRoll() < 1.000001) && (uas->getRoll() > 0.999999));
    QVERIFY((uas->getPitch() < 1.000001) && (uas->getPitch() > 0.999999));
    QVERIFY((uas->getYaw() < 1.000001) && (uas->getYaw() > 0.999999));
}

void UASUnitTest::attitudeLimitsMinusTwoPiOne_test()
{
    mavlink_message_t msg;
    mavlink_attitude_t att;
    // Set 3PI values and encode them
    att.roll  = -2*M_PI-1.0f;
    att.pitch = -2*M_PI-1.0f;
    att.yaw   = -2*M_PI-1.0f;
    mavlink_msg_attitude_encode(uas->getUASID(), MAV_COMP_ID_IMU, &msg, &att);
    // Let UAS decode message
    uas->receiveMessage(link, msg);
    // Check result
    QVERIFY((uas->getRoll() > -1.000001) && (uas->getRoll() < -0.999999));
    QVERIFY((uas->getPitch() > -1.000001) && (uas->getPitch() < -0.999999));
    QVERIFY((uas->getYaw() > -1.000001) && (uas->getYaw() < -0.999999));
278
}