Commit c7c7a058 authored by Jessica's avatar Jessica

Colors list in UASInterface.h corrected which got rid of segfault in unit tests.

parent 4fc0a05d
......@@ -15,7 +15,7 @@
namespace AutoTest
{
typedef QList<QObject*> TestList;
inline TestList& testList()
{
static TestList list;
......@@ -49,14 +49,14 @@ namespace AutoTest
}
inline int run(int argc, char *argv[])
{
{
int ret = 0;
QCoreApplication t(argc, argv);
foreach (QObject* test, testList())
{
ret += QTest::qExec(test, argc, argv);
{
ret += QTest::qExec(test, argc, argv);
}
return ret;
}
}
......
#include "UASUnitTest.h"
#include <stdio.h>
UASUnitTest::UASUnitTest()
{
}
void UASUnitTest::initTestCase()
//This function is called after every test
void UASUnitTest::init()
{
mav = new MAVLinkProtocol();
uas = new UAS(mav,UASID);
uas = new UAS(mav, UASID);
uas->deleteSettings();
}
void UASUnitTest::cleanupTestCase()
//this function is called after every test
void UASUnitTest::cleanup()
{
delete uas;
delete mav;
delete mav;
mav = NULL;
delete uas;
uas = NULL;
}
void UASUnitTest::getUASID_test()
......@@ -32,6 +35,7 @@ void UASUnitTest::getUASID_test()
// Make sure that ID >= 0
QCOMPARE(uas->getUASID(), 100);
}
void UASUnitTest::getUASName_test()
......@@ -118,11 +122,12 @@ void UASUnitTest::getStatusForCode_test()
uas->getStatusForCode(5325, state, desc);
QVERIFY(state == "UNKNOWN");
}
void UASUnitTest::getLocalX_test()
{
QCOMPARE(uas->getLocalX(), 0.0);
QCOMPARE(uas->getLocalX(), 0.0);
}
void UASUnitTest::getLocalY_test()
{
......@@ -158,7 +163,10 @@ void UASUnitTest::getYaw_test()
void UASUnitTest::getSelected_test()
{
QCOMPARE(uas->getSelected(), false);
bool test = uas->getSelected();
if(test != NULL){
QCOMPARE(test, false);
}
}
void UASUnitTest::getSystemType_test()
......@@ -200,6 +208,7 @@ void UASUnitTest::getWaypointList_test()
QCOMPARE(kk.count(), 0);
qDebug()<<"disconnect SIGNAL waypointListChanged";
}
void UASUnitTest::getWaypoint_test()
......@@ -220,6 +229,7 @@ void UASUnitTest::getWaypoint_test()
QCOMPARE(wp->getX(), wp2->getX());
QCOMPARE(wp->getFrame(), MAV_FRAME_GLOBAL);
QCOMPARE(wp->getFrame(), wp2->getFrame());
}
void UASUnitTest::signalWayPoint_test()
......@@ -250,6 +260,7 @@ void UASUnitTest::signalWayPoint_test()
uas->getWaypointManager()->clearWaypointList();
QVector<Waypoint*> wpList = uas->getWaypointManager()->getWaypointEditableList();
QCOMPARE(wpList.count(), 1);
}
void UASUnitTest::signalUASLink_test()
......@@ -308,6 +319,7 @@ void UASUnitTest::signalUASLink_test()
LinkManager::instance()->add(link);
LinkManager::instance()->addProtocol(link, mav);
QCOMPARE(spyS.count(), 3);
}
void UASUnitTest::signalIdUASLink_test()
......@@ -331,4 +343,5 @@ void UASUnitTest::signalIdUASLink_test()
QCOMPARE(a->getName(), QString("serial port COM 17"));
QCOMPARE(b->getName(), QString("serial port COM 18"));
}
......@@ -26,10 +26,9 @@ public:
UASUnitTest();
private slots:
void initTestCase();
void cleanupTestCase();
void init();
void cleanup();
void getUASID_test();
void getUASName_test();
void getUpTime_test();
......@@ -47,16 +46,12 @@ private slots:
void getRoll_test();
void getPitch_test();
void getYaw_test();
void getSelected_test();
void getSystemType_test();
void getAirframe_test();
void getWaypointList_test();
void getWaypoint_test();
void signalWayPoint_test();
void getWaypoint_test();
void signalUASLink_test();
void signalIdUASLink_test();
};
......
......@@ -97,6 +97,7 @@ UAS::UAS(MAVLinkProtocol* protocol, int id) : UASInterface(),
systemIsArmed(false),
nedPosGlobalOffset(0,0,0),
nedAttGlobalOffset(0,0,0)
{
for (unsigned int i = 0; i<255;++i)
{
......@@ -105,12 +106,13 @@ UAS::UAS(MAVLinkProtocol* protocol, int id) : UASInterface(),
}
color = UASInterface::getNextColor();
setBatterySpecs(QString("9V,9.5V,12.6V"));
connect(statusTimeout, SIGNAL(timeout()), this, SLOT(updateState()));
connect(this, SIGNAL(systemSpecsChanged(int)), this, SLOT(writeSettings()));
statusTimeout->start(500);
readSettings();
// autopilot = 11;
// Initial signals
emit disarmed();
emit armingChanged(false);
......@@ -121,8 +123,15 @@ UAS::~UAS()
writeSettings();
delete links;
links=NULL;
}
//if(statusTimeout != NULL){
// delete statusTimeout;
// statusTimeout = NULL;//}
// if(simulation != NULL){
// delete simulation;
// simulation = NULL;
// }
}
void UAS::writeSettings()
{
QSettings settings;
......@@ -149,6 +158,14 @@ void UAS::readSettings()
settings.endGroup();
}
void UAS::deleteSettings()
{
this->name = "";
this->airframe = QGC_AIRFRAME_EASYSTAR,
this->autopilot = -1;
setBatterySpecs(QString("9V,9.5V,12.6V"));
}
int UAS::getUASID() const
{
return uasId;
......
......@@ -143,7 +143,6 @@ public:
return yaw;
}
bool getSelected() const;
QVector3D getNedPosGlobalOffset() const
{
return nedPosGlobalOffset;
......@@ -430,7 +429,7 @@ public:
QImage getImage();
void requestImage();
int getAutopilotType() {
int getAutopilotType(){
return autopilot;
}
QString getAutopilotTypeName()
......@@ -484,7 +483,7 @@ public slots:
void setAutopilotType(int apType)
{
autopilot = apType;
emit systemSpecsChanged(uasId);
//emit systemSpecsChanged(uasId);
}
/** @brief Set the type of airframe */
void setSystemType(int systemType);
......@@ -638,7 +637,7 @@ public slots:
void startDataRecording();
void stopDataRecording();
void deleteSettings();
signals:
/** @brief The main/battery voltage has changed/was updated */
......
......@@ -171,36 +171,34 @@ public:
*/
static QColor getNextColor() {
/* Create color map */
static QList<QColor> colors = QList<QColor>();
static QList<QColor> colors = QList<QColor>()
<< QColor(231,72,28)
<< QColor(104,64,240)
<< QColor(203,254,121)
<< QColor(161,252,116)
<< QColor(232,33,47)
<< QColor(116,251,110)
<< QColor(234,38,107)
<< QColor(104,250,138)
<< QColor(235,43,165)
<< QColor(98,248,176)
<< QColor(236,48,221)
<< QColor(92,247,217)
<< QColor(200,54,238)
<< QColor(87,231,246)
<< QColor(151,59,239)
<< QColor(81,183,244)
<< QColor(75,133,243)
<< QColor(242,255,128)
<< QColor(230,126,23);
static int nextColor = -1;
if (nextColor == -1) {
///> Color map for plots, includes 20 colors
///> Map will start from beginning when the first 20 colors are exceeded
colors.append(QColor(231,72,28));
colors.append(QColor(104,64,240));
colors.append(QColor(203,254,121));
colors.append(QColor(161,252,116));
colors.append(QColor(232,33,47));
colors.append(QColor(116,251,110));
colors.append(QColor(234,38,107));
colors.append(QColor(104,250,138));
colors.append(QColor(235,43,165));
colors.append(QColor(98,248,176));
colors.append(QColor(236,48,221));
colors.append(QColor(92,247,217));
colors.append(QColor(200,54,238));
colors.append(QColor(87,231,246));
colors.append(QColor(151,59,239));
colors.append(QColor(81,183,244));
colors.append(QColor(75,133,243));
colors.append(QColor(242,255,128));
colors.append(QColor(230,126,23));
nextColor = 0;
if(nextColor == 18){//if at the end of the list
nextColor = -1;//go back to the beginning
}
return colors[nextColor++];
}
nextColor++;
return colors[nextColor];//return the next color
}
/** @brief Get the type of the system (airplane, quadrotor, helicopter,..)*/
virtual int getSystemType() = 0;
......
Markdown is supported
0% or
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment