Newer
Older
Mariano Lizarraga
committed
#include "UASUnitTest.h"
#include <stdio.h>
Mariano Lizarraga
committed
UASUnitTest::UASUnitTest()
{
}
//This function is called after every test
void UASUnitTest::init()
Mariano Lizarraga
committed
{
UnitTest::init();
_mavlink = new MAVLinkProtocol();
_uas = new UAS(_mavlink, UASID);
Mariano Lizarraga
committed
}
//this function is called after every test
void UASUnitTest::cleanup()
Mariano Lizarraga
committed
{
Mariano Lizarraga
committed
}
void UASUnitTest::getUASID_test()
{
// Test a default ID of zero is assigned
UAS* uas2 = new UAS(_mavlink);
Mariano Lizarraga
committed
QCOMPARE(uas2->getUASID(), 0);
delete uas2;
// Test that the chosen ID was assigned at construction
Mariano Lizarraga
committed
Bryant Mairs
committed
// Make sure that no other ID was set
Mariano Lizarraga
committed
QEXPECT_FAIL("", "When you set an ID it does not use the default ID of 0", Continue);
Mariano Lizarraga
committed
// Make sure that ID >= 0
Mariano Lizarraga
committed
}
void UASUnitTest::getUASName_test()
{
Mariano Lizarraga
committed
// Test that the name is build as MAV + ID
QCOMPARE(_uas->getUASName(), "MAV " + QString::number(UASID));
Mariano Lizarraga
committed
}
void UASUnitTest::getUpTime_test()
{
UAS* uas2 = new UAS(_mavlink);
// Test that the uptime starts at zero to a
// precision of seconds
QCOMPARE(floor(uas2->getUptime()/1000.0), 0.0);
Mariano Lizarraga
committed
// Sleep for three seconds
QTest::qSleep(3000);
Mariano Lizarraga
committed
// Test that the up time is computed correctly to a
// precision of seconds
QCOMPARE(floor(uas2->getUptime()/1000.0), 3.0);
Mariano Lizarraga
committed
delete uas2;
Mariano Lizarraga
committed
}
void UASUnitTest::filterVoltage_test()
{
// 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));
Mariano Lizarraga
committed
}
Mariano Lizarraga
committed
void UASUnitTest:: getAutopilotType_test()
{
// Verify that upon construction the autopilot is set to -1
QCOMPARE(type, -1);
Mariano Lizarraga
committed
}
Mariano Lizarraga
committed
void UASUnitTest::setAutopilotType_test()
{
// Verify that the autopilot is set
Mariano Lizarraga
committed
}
//verify that the correct status is returned if a certain statue is given to _uas
Mariano Lizarraga
committed
void UASUnitTest::getStatusForCode_test()
{
QString state, desc;
state = "";
desc = "";
Mariano Lizarraga
committed
_uas->getStatusForCode(MAV_STATE_UNINIT, state, desc);
QVERIFY(state == "UNINIT");
Mariano Lizarraga
committed
_uas->getStatusForCode(MAV_STATE_UNINIT, state, desc);
QVERIFY(state == "UNINIT");
Mariano Lizarraga
committed
_uas->getStatusForCode(MAV_STATE_BOOT, state, desc);
QVERIFY(state == "BOOT");
Mariano Lizarraga
committed
_uas->getStatusForCode(MAV_STATE_CALIBRATING, state, desc);
QVERIFY(state == "CALIBRATING");
Mariano Lizarraga
committed
_uas->getStatusForCode(MAV_STATE_ACTIVE, state, desc);
QVERIFY(state == "ACTIVE");
Mariano Lizarraga
committed
_uas->getStatusForCode(MAV_STATE_STANDBY, state, desc);
QVERIFY(state == "STANDBY");
Mariano Lizarraga
committed
_uas->getStatusForCode(MAV_STATE_CRITICAL, state, desc);
QVERIFY(state == "CRITICAL");
Mariano Lizarraga
committed
_uas->getStatusForCode(MAV_STATE_EMERGENCY, state, desc);
QVERIFY(state == "EMERGENCY");
Mariano Lizarraga
committed
_uas->getStatusForCode(MAV_STATE_POWEROFF, state, desc);
QVERIFY(state == "SHUTDOWN");
Mariano Lizarraga
committed
QVERIFY(state == "UNKNOWN");
Mariano Lizarraga
committed
}
void UASUnitTest::getLocalX_test()
{
Mariano Lizarraga
committed
}
void UASUnitTest::getLocalY_test()
{
Mariano Lizarraga
committed
}
void UASUnitTest::getLocalZ_test()
{
Mariano Lizarraga
committed
}
void UASUnitTest::getLatitude_test()
Mariano Lizarraga
committed
}
void UASUnitTest::getLongitude_test()
{
Mariano Lizarraga
committed
}
Mariano Lizarraga
committed
{
}
void UASUnitTest::getAltitudeRelative_test()
{
Mariano Lizarraga
committed
}
void UASUnitTest::getRoll_test()
{
Mariano Lizarraga
committed
}
void UASUnitTest::getPitch_test()
{
Mariano Lizarraga
committed
}
void UASUnitTest::getYaw_test()
{
}
Mariano Lizarraga
committed
void UASUnitTest::getSelected_test()
{
}
Mariano Lizarraga
committed
void UASUnitTest::getSystemType_test()
{ //check that system type is set to MAV_TYPE_GENERIC when initialized
QCOMPARE(_uas->getSystemType(), 0);
_uas->setSystemType(13);
QCOMPARE(_uas->getSystemType(), 13);
}
Mariano Lizarraga
committed
void UASUnitTest::getAirframe_test()
{
//when _uas is constructed, airframe is set to QGC_AIRFRAME_GENERIC
QVERIFY(_uas->getAirframe() == UASInterface::QGC_AIRFRAME_GENERIC);
Jessica
committed
}
Mariano Lizarraga
committed
Jessica
committed
void UASUnitTest::setAirframe_test()
{
//check at construction, that airframe=0 (GENERIC)
QVERIFY(_uas->getAirframe() == UASInterface::QGC_AIRFRAME_GENERIC);
//check that set airframe works
_uas->setAirframe(UASInterface::QGC_AIRFRAME_HEXCOPTER);
QVERIFY(_uas->getAirframe() == UASInterface::QGC_AIRFRAME_HEXCOPTER);
//check that setAirframe will not assign a number to airframe, that is
//not defined in the enum
_uas->setAirframe(UASInterface::QGC_AIRFRAME_END_OF_ENUM);
QVERIFY(_uas->getAirframe() == UASInterface::QGC_AIRFRAME_HEXCOPTER);
}
Mariano Lizarraga
committed
void UASUnitTest::getWaypointList_test()
{
QList<Waypoint*> kk = _uas->getWaypointManager()->getWaypointEditableList();
Mariano Lizarraga
committed
QCOMPARE(kk.count(), 0);
Bryant Mairs
committed
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);
Mariano Lizarraga
committed
kk = _uas->getWaypointManager()->getWaypointEditableList();
Mariano Lizarraga
committed
QCOMPARE(kk.count(), 1);
wp = new Waypoint();
_uas->getWaypointManager()->addWaypointEditable(wp, false);
Mariano Lizarraga
committed
kk = _uas->getWaypointManager()->getWaypointEditableList();
Mariano Lizarraga
committed
QCOMPARE(kk.count(), 2);
_uas->getWaypointManager()->removeWaypoint(1);
kk = _uas->getWaypointManager()->getWaypointEditableList();
Mariano Lizarraga
committed
QCOMPARE(kk.count(), 1);
_uas->getWaypointManager()->removeWaypoint(0);
kk = _uas->getWaypointManager()->getWaypointEditableList();
Mariano Lizarraga
committed
QCOMPARE(kk.count(), 0);
qDebug()<<"disconnect SIGNAL waypointListChanged";
Mariano Lizarraga
committed
}
void UASUnitTest::getWaypoint_test()
{
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");
Mariano Lizarraga
committed
_uas->getWaypointManager()->addWaypointEditable(wp, true);
Mariano Lizarraga
committed
QList<Waypoint*> wpList = _uas->getWaypointManager()->getWaypointEditableList();
Mariano Lizarraga
committed
QCOMPARE(wpList.count(), 1);
QCOMPARE(static_cast<quint16>(0), static_cast<Waypoint*>(wpList.at(0))->getId());
_uas->getWaypointManager()->addWaypointEditable(wp3, true);
wpList = _uas->getWaypointManager()->getWaypointEditableList();
Mariano Lizarraga
committed
Waypoint* wp2 = static_cast<Waypoint*>(wpList.at(0));
QCOMPARE(wp3->getX(), wp2->getX());
QCOMPARE(wp3->getY(), wp2->getY());
QCOMPARE(wp3->getZ(), wp2->getZ());
QCOMPARE(wpList.at(1)->getId(), static_cast<quint16>(1));
QCOMPARE(wp3->getFrame(), MAV_FRAME_GLOBAL);
QCOMPARE(wp3->getFrame(), wp2->getFrame());
}
Mariano Lizarraga
committed
void UASUnitTest::signalWayPoint_test()
{
QSignalSpy spy(_uas->getWaypointManager(), SIGNAL(waypointEditableListChanged()));
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");
_uas->getWaypointManager()->addWaypointEditable(wp, true);
Mariano Lizarraga
committed
QCOMPARE(spy.count(), 1); // 1 listChanged for add wayPoint
Mariano Lizarraga
committed
QCOMPARE(spy.count(), 2); // 2 listChanged for remove wayPoint
QSignalSpy spyDestroyed(_uas->getWaypointManager(), SIGNAL(destroyed()));
Mariano Lizarraga
committed
QVERIFY(spyDestroyed.isValid());
QCOMPARE( spyDestroyed.count(), 0 );
delete _uas;// delete(destroyed) _uas for validating
_uas = NULL;
QCOMPARE(spyDestroyed.count(), 1);// count destroyed _uas should are 1
_uas = new UAS(_mavlink, UASID);
QSignalSpy spy2(_uas->getWaypointManager(), SIGNAL(waypointEditableListChanged()));
Mariano Lizarraga
committed
QCOMPARE(spy2.count(), 0);
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");
Mariano Lizarraga
committed
_uas->getWaypointManager()->addWaypointEditable(wp2, true);
Mariano Lizarraga
committed
QCOMPARE(spy2.count(), 1);
_uas->getWaypointManager()->clearWaypointList();
QList<Waypoint*> wpList = _uas->getWaypointManager()->getWaypointEditableList();
Mariano Lizarraga
committed
QCOMPARE(wpList.count(), 1);