Commit 5ed1b5bc authored by Jessica's avatar Jessica

System type is set to generic in constructor of UAS.

parent 6bc3fbec
#include "UASUnitTest.h" #include "UASUnitTest.h"
#include <stdio.h> #include <stdio.h>
#include <QObject>
UASUnitTest::UASUnitTest() UASUnitTest::UASUnitTest()
{ {
} }
...@@ -167,8 +168,9 @@ void UASUnitTest::getSelected_test() ...@@ -167,8 +168,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,13 +253,12 @@ void UASUnitTest::getWaypoint_test() ...@@ -251,13 +253,12 @@ 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(UASID)));
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,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(wp, true);
printf("spy.count = %d\n", spy.count()); 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()));
......
...@@ -111,7 +111,8 @@ UAS::UAS(MAVLinkProtocol* protocol, int id) : UASInterface(), ...@@ -111,7 +111,8 @@ UAS::UAS(MAVLinkProtocol* protocol, int id) : UASInterface(),
connect(statusTimeout, SIGNAL(timeout()), this, SLOT(updateState())); connect(statusTimeout, SIGNAL(timeout()), this, SLOT(updateState()));
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) ...@@ -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)
{ {
switch (systemType) type = systemType;
{
case MAV_TYPE_FIXED_WING: // If the airframe is still generic, change it to a close default type
airframe = QGC_AIRFRAME_EASYSTAR; if (airframe == 0)
break; {
case MAV_TYPE_QUADROTOR: switch (systemType)
airframe = QGC_AIRFRAME_MIKROKOPTER; {
break; case MAV_TYPE_FIXED_WING:
} airframe = QGC_AIRFRAME_EASYSTAR;
} break;
emit systemSpecsChanged(uasId); case MAV_TYPE_QUADROTOR:
airframe = QGC_AIRFRAME_MIKROKOPTER;
break;
}
}
emit systemSpecsChanged(uasId);
}
} }
void UAS::setUASName(const QString& name) void UAS::setUASName(const QString& name)
......
...@@ -490,7 +490,7 @@ public slots: ...@@ -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: ...@@ -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 */
......
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