Browse Source

Merge branch 'reorganize_qgcunittest' into memCheck

QGC4.4
Jessica 13 years ago
parent
commit
c20ec5c675
  1. 2
      qgcunittest.pro
  2. 0
      src/qgcunittest/AutoTest.h
  3. 25
      src/qgcunittest/UASUnitTest.cc
  4. 0
      src/qgcunittest/UASUnitTest.h
  5. 0
      src/qgcunittest/testSuite.cc
  6. 35
      src/uas/UAS.cc
  7. 3
      src/uas/UAS.h

2
qgcunittest.pro

@ -34,7 +34,7 @@ QT += network \
TEMPLATE = app TEMPLATE = app
TARGET = qgcunittest TARGET = qgcunittest
BASEDIR = $${IN_PWD} BASEDIR = $${IN_PWD}
TESTDIR = $$BASEDIR/qgcunittest TESTDIR = $$BASEDIR/src/qgcunittest
linux-g++|linux-g++-64{ linux-g++|linux-g++-64{
debug { debug {
TARGETDIR = $${OUT_PWD}/debug TARGETDIR = $${OUT_PWD}/debug

0
qgcunittest/AutoTest.h → src/qgcunittest/AutoTest.h

25
qgcunittest/UASUnitTest.cc → src/qgcunittest/UASUnitTest.cc

@ -1,5 +1,6 @@
#include "UASUnitTest.h" #include "UASUnitTest.h"
#include <stdio.h> #include <stdio.h>
#include <QObject>
UASUnitTest::UASUnitTest() UASUnitTest::UASUnitTest()
{ {
} }
@ -15,8 +16,10 @@ void UASUnitTest::cleanup()
{ {
delete mav; delete mav;
mav = NULL; mav = NULL;
if(uas != NULL){
delete uas; delete uas;
uas = NULL; uas = NULL;
}
} }
void UASUnitTest::getUASID_test() void UASUnitTest::getUASID_test()
@ -167,8 +170,9 @@ void UASUnitTest::getSelected_test()
} }
void UASUnitTest::getSystemType_test() void UASUnitTest::getSystemType_test()
{ //best guess: it is not initialized in the constructor, { //check that system type is set to MAV_TYPE_GENERIC when initialized
//what should it be initialized to? QCOMPARE(uas->getSystemType(), 0);
uas->setSystemType(13);
QCOMPARE(uas->getSystemType(), 13); QCOMPARE(uas->getSystemType(), 13);
} }
@ -251,33 +255,36 @@ void UASUnitTest::getWaypoint_test()
void UASUnitTest::signalWayPoint_test() void UASUnitTest::signalWayPoint_test()
{ {
QSignalSpy spy(uas->getWaypointManager(), SIGNAL(waypointListChanged(UASID))); QSignalSpy spy(uas->getWaypointManager(), SIGNAL(waypointEditableListChanged()));
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"); 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); uas->getWaypointManager()->addWaypointEditable(wp, true);
printf("spy.count = %d\n", spy.count());
//QCOMPARE(spy.count(), 1); // 1 listChanged for add wayPoint QCOMPARE(spy.count(), 1); // 1 listChanged for add wayPoint
uas->getWaypointManager()->removeWaypoint(0); uas->getWaypointManager()->removeWaypoint(0);
QCOMPARE(spy.count(), 2); // 2 listChanged for remove wayPoint QCOMPARE(spy.count(), 2); // 2 listChanged for remove wayPoint
QSignalSpy spyDestroyed(uas->getWaypointManager(), SIGNAL(destroyed())); QSignalSpy spyDestroyed(uas->getWaypointManager(), SIGNAL(destroyed()));
QVERIFY(spyDestroyed.isValid()); QVERIFY(spyDestroyed.isValid());
QCOMPARE( spyDestroyed.count(), 0 ); QCOMPARE( spyDestroyed.count(), 0 );
delete uas;// delete(destroyed) uas for validating delete uas;// delete(destroyed) uas for validating
uas = NULL;
QCOMPARE(spyDestroyed.count(), 1);// count destroyed uas should are 1 QCOMPARE(spyDestroyed.count(), 1);// count destroyed uas should are 1
uas = new UAS(mav,UASID); uas = new UAS(mav,UASID);
QSignalSpy spy2(uas->getWaypointManager(), SIGNAL(waypointListChanged())); QSignalSpy spy2(uas->getWaypointManager(), SIGNAL(waypointEditableListChanged()));
QCOMPARE(spy2.count(), 0); 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");
uas->getWaypointManager()->addWaypointEditable(wp, true); uas->getWaypointManager()->addWaypointEditable(wp2, true);
QCOMPARE(spy2.count(), 1); QCOMPARE(spy2.count(), 1);
uas->getWaypointManager()->clearWaypointList(); uas->getWaypointManager()->clearWaypointList();
QVector<Waypoint*> wpList = uas->getWaypointManager()->getWaypointEditableList(); QVector<Waypoint*> wpList = uas->getWaypointManager()->getWaypointEditableList();
QCOMPARE(wpList.count(), 1); QCOMPARE(wpList.count(), 1);
delete wp2;
} }
void UASUnitTest::signalUASLink_test() void UASUnitTest::signalUASLink_test()

0
qgcunittest/UASUnitTest.h → src/qgcunittest/UASUnitTest.h

0
qgcunittest/testSuite.cc → src/qgcunittest/testSuite.cc

35
src/uas/UAS.cc

@ -112,6 +112,7 @@ UAS::UAS(MAVLinkProtocol* protocol, int id) : UASInterface(),
connect(this, SIGNAL(systemSpecsChanged(int)), this, SLOT(writeSettings())); connect(this, SIGNAL(systemSpecsChanged(int)), this, SLOT(writeSettings()));
statusTimeout->start(500); statusTimeout->start(500);
readSettings(); readSettings();
type = MAV_TYPE_GENERIC;
// Initial signals // Initial signals
emit disarmed(); emit disarmed();
emit armingChanged(false); emit armingChanged(false);
@ -2081,21 +2082,25 @@ void UAS::requestParameter(int component, const QString& parameter)
void UAS::setSystemType(int systemType) void UAS::setSystemType(int systemType)
{ {
type = systemType; if((systemType >= MAV_TYPE_GENERIC) && (systemType < MAV_TYPE_ENUM_END))
// If the airframe is still generic, change it to a close default type {
if (airframe == 0) type = systemType;
{
switch (systemType) // If the airframe is still generic, change it to a close default type
{ if (airframe == 0)
case MAV_TYPE_FIXED_WING: {
airframe = QGC_AIRFRAME_EASYSTAR; switch (systemType)
break; {
case MAV_TYPE_QUADROTOR: case MAV_TYPE_FIXED_WING:
airframe = QGC_AIRFRAME_MIKROKOPTER; airframe = QGC_AIRFRAME_EASYSTAR;
break; break;
} case MAV_TYPE_QUADROTOR:
} airframe = QGC_AIRFRAME_MIKROKOPTER;
emit systemSpecsChanged(uasId); break;
}
}
emit systemSpecsChanged(uasId);
}
} }
void UAS::setUASName(const QString& name) void UAS::setUASName(const QString& name)

3
src/uas/UAS.h

@ -490,7 +490,7 @@ public slots:
/** @brief Set the specific airframe type */ /** @brief Set the specific airframe type */
void setAirframe(int airframe) void setAirframe(int airframe)
{ {
if((airframe >= 0) && (airframe < 12)) if((airframe >= QGC_AIRFRAME_GENERIC) && (airframe < QGC_AIRFRAME_END_OF_ENUM))
{ {
this->airframe = airframe; this->airframe = airframe;
emit systemSpecsChanged(uasId); emit systemSpecsChanged(uasId);
@ -643,7 +643,6 @@ public slots:
void stopDataRecording(); void stopDataRecording();
void deleteSettings(); void deleteSettings();
signals: signals:
/** @brief The main/battery voltage has changed/was updated */ /** @brief The main/battery voltage has changed/was updated */
//void voltageChanged(int uasId, double voltage); // Defined in UASInterface already //void voltageChanged(int uasId, double voltage); // Defined in UASInterface already
/** @brief An actuator value has changed */ /** @brief An actuator value has changed */

Loading…
Cancel
Save