Commit 178fa4f7 authored by DonLakeFlyer's avatar DonLakeFlyer

Big investment in Plan oriented unit tests

Fixed all the bugs the new tests found
parent 982232c1
......@@ -384,13 +384,17 @@ DebugBuild { PX4FirmwarePlugin { PX4FirmwarePluginFactory { APMFirmwarePlugin {
src/FactSystem/FactSystemTestGeneric.h \
src/FactSystem/FactSystemTestPX4.h \
src/FactSystem/ParameterManagerTest.h \
src/MissionManager/SurveyMissionItemTest.h \
src/MissionManager/CameraSectionTest.h \
src/MissionManager/MissionCommandTreeTest.h \
src/MissionManager/MissionControllerManagerTest.h \
src/MissionManager/MissionControllerTest.h \
src/MissionManager/MissionItemTest.h \
src/MissionManager/MissionManagerTest.h \
src/MissionManager/SectionTest.h \
src/MissionManager/SimpleMissionItemTest.h \
src/MissionManager/SpeedSectionTest.h \
src/MissionManager/SurveyMissionItemTest.h \
src/MissionManager/VisualMissionItemTest.h \
src/qgcunittest/FileDialogTest.h \
src/qgcunittest/FileManagerTest.h \
src/qgcunittest/FlightGearTest.h \
......@@ -412,13 +416,17 @@ DebugBuild { PX4FirmwarePlugin { PX4FirmwarePluginFactory { APMFirmwarePlugin {
src/FactSystem/FactSystemTestGeneric.cc \
src/FactSystem/FactSystemTestPX4.cc \
src/FactSystem/ParameterManagerTest.cc \
src/MissionManager/SurveyMissionItemTest.cc \
src/MissionManager/CameraSectionTest.cc \
src/MissionManager/MissionCommandTreeTest.cc \
src/MissionManager/MissionControllerManagerTest.cc \
src/MissionManager/MissionControllerTest.cc \
src/MissionManager/MissionItemTest.cc \
src/MissionManager/MissionManagerTest.cc \
src/MissionManager/SectionTest.cc \
src/MissionManager/SimpleMissionItemTest.cc \
src/MissionManager/SpeedSectionTest.cc \
src/MissionManager/SurveyMissionItemTest.cc \
src/MissionManager/VisualMissionItemTest.cc \
src/qgcunittest/FileDialogTest.cc \
src/qgcunittest/FileManagerTest.cc \
src/qgcunittest/FlightGearTest.cc \
......
......@@ -48,13 +48,14 @@ CameraSection::CameraSection(Vehicle* vehicle, QObject* parent)
_cameraPhotoIntervalDistanceFact.setRawValue (_cameraPhotoIntervalDistanceFact.rawDefaultValue());
_cameraPhotoIntervalTimeFact.setRawValue (_cameraPhotoIntervalTimeFact.rawDefaultValue());
connect(this, &CameraSection::specifyGimbalChanged, this, &CameraSection::_setDirtyAndUpdateItemCount);
connect(&_cameraActionFact, &Fact::valueChanged, this, &CameraSection::_setDirtyAndUpdateItemCount);
connect(this, &CameraSection::specifyGimbalChanged, this, &CameraSection::_specifyGimbalChanged);
connect(&_cameraActionFact, &Fact::valueChanged, this, &CameraSection::_cameraActionChanged);
connect(&_gimbalPitchFact, &Fact::valueChanged, this, &CameraSection::_setDirty);
connect(&_gimbalYawFact, &Fact::valueChanged, this, &CameraSection::_setDirty);
connect(&_cameraPhotoIntervalDistanceFact, &Fact::valueChanged, this, &CameraSection::_setDirty);
connect(&_cameraPhotoIntervalTimeFact, &Fact::valueChanged, this, &CameraSection::_setDirty);
connect(&_gimbalPitchFact, &Fact::valueChanged, this, &CameraSection::_setDirty);
connect(&_gimbalYawFact, &Fact::valueChanged, this, &CameraSection::_setDirty);
connect(&_cameraPhotoIntervalDistanceFact, &Fact::valueChanged, this, &CameraSection::_setDirty);
connect(&_cameraPhotoIntervalTimeFact, &Fact::valueChanged, this, &CameraSection::_setDirty);
connect(this, &CameraSection::specifyGimbalChanged, this, &CameraSection::_setDirty);
connect(&_gimbalYawFact, &Fact::valueChanged, this, &CameraSection::_updateSpecifiedGimbalYaw);
}
......@@ -188,7 +189,7 @@ void CameraSection::appendSectionItems(QList<MissionItem*>& items, QObject* miss
}
}
bool CameraSection::scanForSection(QmlObjectListModel* visualItems, int& scanIndex)
bool CameraSection::scanForSection(QmlObjectListModel* visualItems, int scanIndex)
{
bool foundGimbal = false;
bool foundCameraAction = false;
......@@ -218,7 +219,6 @@ bool CameraSection::scanForSection(QmlObjectListModel* visualItems, int& scanInd
case MAV_CMD_DO_MOUNT_CONTROL:
if (!foundGimbal && missionItem.param2() == 0 && missionItem.param4() == 0 && missionItem.param5() == 0 && missionItem.param6() == 0 && missionItem.param7() == MAV_MOUNT_MODE_MAVLINK_TARGETING) {
foundGimbal = true;
scanIndex++;
setSpecifyGimbal(true);
gimbalPitch()->setRawValue(missionItem.param1());
gimbalYaw()->setRawValue(missionItem.param3());
......@@ -231,7 +231,6 @@ bool CameraSection::scanForSection(QmlObjectListModel* visualItems, int& scanInd
case MAV_CMD_IMAGE_START_CAPTURE:
if (!foundCameraAction && missionItem.param1() != 0 && missionItem.param2() == 0 && missionItem.param3() == -1 && missionItem.param4() == 0 && missionItem.param5() == 0 && missionItem.param6() == 0 && missionItem.param7() == 0) {
foundCameraAction = true;
scanIndex++;
cameraAction()->setRawValue(TakePhotosIntervalTime);
cameraPhotoIntervalTime()->setRawValue(missionItem.param1());
visualItems->removeAt(scanIndex)->deleteLater();
......@@ -251,7 +250,6 @@ bool CameraSection::scanForSection(QmlObjectListModel* visualItems, int& scanInd
if (nextMissionItem.command() == MAV_CMD_IMAGE_STOP_CAPTURE && nextMissionItem.param1() == 0 && nextMissionItem.param2() == 0 && nextMissionItem.param3() == 0 && nextMissionItem.param4() == 0 && nextMissionItem.param5() == 0 && nextMissionItem.param6() == 0 && nextMissionItem.param7() == 0) {
// We found a stop taking photos pair
foundCameraAction = true;
scanIndex += 2;
cameraAction()->setRawValue(StopTakingPhotos);
visualItems->removeAt(scanIndex)->deleteLater();
visualItems->removeAt(scanIndex)->deleteLater();
......@@ -264,7 +262,6 @@ bool CameraSection::scanForSection(QmlObjectListModel* visualItems, int& scanInd
// We didn't find a stop taking photos pair, check for trigger distance
if (missionItem.param1() > 0) {
foundCameraAction = true;
scanIndex++;
cameraAction()->setRawValue(TakePhotoIntervalDistance);
cameraPhotoIntervalDistance()->setRawValue(missionItem.param1());
visualItems->removeAt(scanIndex)->deleteLater();
......@@ -278,7 +275,6 @@ bool CameraSection::scanForSection(QmlObjectListModel* visualItems, int& scanInd
case MAV_CMD_VIDEO_START_CAPTURE:
if (!foundCameraAction && missionItem.param1() == 0 && missionItem.param2() == -1 && missionItem.param3() == -1 && missionItem.param4() == 0 && missionItem.param5() == 0 && missionItem.param6() == 0 && missionItem.param7() == 0) {
foundCameraAction = true;
scanIndex++;
cameraAction()->setRawValue(TakeVideo);
visualItems->removeAt(scanIndex)->deleteLater();
}
......@@ -288,7 +284,6 @@ bool CameraSection::scanForSection(QmlObjectListModel* visualItems, int& scanInd
case MAV_CMD_VIDEO_STOP_CAPTURE:
if (!foundCameraAction && missionItem.param1() == 0 && missionItem.param2() == 0 && missionItem.param3() == 0 && missionItem.param4() == 0 && missionItem.param5() == 0 && missionItem.param6() == 0 && missionItem.param7() == 0) {
foundCameraAction = true;
scanIndex++;
cameraAction()->setRawValue(StopTakingVideo);
visualItems->removeAt(scanIndex)->deleteLater();
}
......@@ -337,3 +332,25 @@ void CameraSection::_updateSpecifiedGimbalYaw(void)
{
emit specifiedGimbalYawChanged(specifiedGimbalYaw());
}
void CameraSection::_updateSettingsSpecified(void)
{
bool newSettingsSpecified = _specifyGimbal || _cameraActionFact.rawValue().toInt() != CameraActionNone;
if (newSettingsSpecified != _settingsSpecified) {
_settingsSpecified = newSettingsSpecified;
emit settingsSpecifiedChanged(newSettingsSpecified);
}
}
void CameraSection::_specifyGimbalChanged(bool specifyGimbal)
{
Q_UNUSED(specifyGimbal);
_setDirtyAndUpdateItemCount();
_updateSettingsSpecified();
}
void CameraSection::_cameraActionChanged(void)
{
_setDirtyAndUpdateItemCount();
_updateSettingsSpecified();
}
......@@ -56,7 +56,7 @@ public:
bool dirty (void) const override { return _dirty; }
void setAvailable (bool available) override;
void setDirty (bool dirty) override;
bool scanForSection (QmlObjectListModel* visualItems, int& scanIndex) override;
bool scanForSection (QmlObjectListModel* visualItems, int scanIndex) override;
void appendSectionItems (QList<MissionItem*>& items, QObject* missionItemParent, int& seqNum) override;
int itemCount (void) const override;
bool settingsSpecified (void) const override {return _settingsSpecified; }
......@@ -69,6 +69,9 @@ private slots:
void _setDirty(void);
void _setDirtyAndUpdateItemCount(void);
void _updateSpecifiedGimbalYaw(void);
void _specifyGimbalChanged(bool specifyGimbal);
void _updateSettingsSpecified(void);
void _cameraActionChanged(void);
private:
bool _available;
......
This diff is collapsed.
/****************************************************************************
*
* (c) 2009-2016 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org>
*
* QGroundControl is licensed according to the terms in the file
* COPYING.md in the root of the source code directory.
*
****************************************************************************/
#pragma once
#include "SectionTest.h"
#include "CameraSection.h"
/// Unit test for CameraSection
class CameraSectionTest : public SectionTest
{
Q_OBJECT
public:
CameraSectionTest(void);
void init(void) override;
void cleanup(void) override;
private slots:
void _testDirty(void);
void _testSettingsAvailable(void);
void _checkAvailable(void);
void _testItemCount(void);
void _testAppendSectionItems(void);
void _testScanForGimbalSection(void);
void _testScanForPhotoIntervalTimeSection(void);
void _testScanForPhotoIntervalDistanceSection(void);
void _testScanForStartVideoSection(void);
void _testScanForStopVideoSection(void);
void _testScanForStopImageSection(void);
void _testScanForFullSection(void);
private:
void _createSpy(CameraSection* cameraSection, MultiSignalSpy** cameraSpy);
enum {
specifyGimbalChangedIndex = 0,
specifiedGimbalYawChangedIndex,
maxSignalIndex,
};
enum {
specifyGimbalChangedMask = 1 << specifyGimbalChangedIndex,
specifiedGimbalYawChangedMask = 1 << specifiedGimbalYawChangedIndex
};
static const size_t cCameraSignals = maxSignalIndex;
const char* rgCameraSignals[cCameraSignals];
MultiSignalSpy* _spyCamera;
MultiSignalSpy* _spySection;
CameraSection* _cameraSection;
SimpleMissionItem* _validGimbalItem;
SimpleMissionItem* _validDistanceItem;
SimpleMissionItem* _validTimeItem;
SimpleMissionItem* _validStartVideoItem;
SimpleMissionItem* _validStopVideoItem;
SimpleMissionItem* _validStopDistanceItem;
SimpleMissionItem* _validStopTimeItem;
};
......@@ -1543,7 +1543,9 @@ void MissionController::_scanForAdditionalSettings(QmlObjectListModel* visualIte
qCDebug(MissionControllerLog) << "MissionController::_scanForAdditionalSettings count:scanIndex" << visualItems->count() << scanIndex;
MissionSettingsItem* settingsItem = qobject_cast<MissionSettingsItem*>(visualItem);
if (settingsItem && settingsItem->scanForMissionSettings(visualItems, scanIndex)) {
if (settingsItem) {
scanIndex++;
settingsItem->scanForMissionSettings(visualItems, scanIndex);
continue;
}
......
......@@ -43,11 +43,12 @@ MissionSettingsItem::MissionSettingsItem(Vehicle* vehicle, QObject* parent)
}
_plannedHomePositionAltitudeFact.setMetaData (_metaDataMap[_plannedHomePositionAltitudeName]);
_plannedHomePositionAltitudeFact.setRawValue (_plannedHomePositionAltitudeFact.rawDefaultValue());
setHomePositionSpecialCase(true);
_cameraSection.setAvailable(true);
_speedSection.setAvailable(true);
connect(this, &MissionSettingsItem::specifyMissionFlightSpeedChanged, this, &MissionSettingsItem::_setDirtyAndUpdateLastSequenceNumber);
connect(this, &MissionSettingsItem::missionEndRTLChanged, this, &MissionSettingsItem::_setDirtyAndUpdateLastSequenceNumber);
connect(&_cameraSection, &CameraSection::itemCountChanged, this, &MissionSettingsItem::_setDirtyAndUpdateLastSequenceNumber);
......@@ -184,17 +185,9 @@ bool MissionSettingsItem::scanForMissionSettings(QmlObjectListModel* visualItems
qCDebug(MissionSettingsComplexItemLog) << "MissionSettingsItem::scanForMissionSettings count:scanIndex" << visualItems->count() << scanIndex;
MissionSettingsItem* settingsItem = visualItems->value<MissionSettingsItem*>(scanIndex);
if (!settingsItem) {
qWarning() << "Item specified by scanIndex not MissionSettingsItem";
return false;
}
// Scan through the initial mission items for possible mission settings
scanIndex++;
foundCameraSection = settingsItem->_cameraSection.scanForSection(visualItems, scanIndex);
foundSpeedSection = settingsItem->_speedSection.scanForSection(visualItems, scanIndex);
foundCameraSection = _cameraSection.scanForSection(visualItems, scanIndex);
foundSpeedSection = _speedSection.scanForSection(visualItems, scanIndex);
// Look at the end of the mission for end actions
......@@ -206,7 +199,7 @@ bool MissionSettingsItem::scanForMissionSettings(QmlObjectListModel* visualItems
if (missionItem.command() == MAV_CMD_NAV_RETURN_TO_LAUNCH &&
missionItem.param1() == 0 && missionItem.param2() == 0 && missionItem.param3() == 0 && missionItem.param4() == 0 && missionItem.param5() == 0 && missionItem.param6() == 0 && missionItem.param7() == 0) {
qCDebug(MissionSettingsComplexItemLog) << "Scan: Found end action RTL";
settingsItem->_missionEndRTL = true;
_missionEndRTL = true;
visualItems->removeAt(lastIndex)->deleteLater();
}
}
......
......@@ -37,7 +37,7 @@ public:
QObject* speedSection(void) { return &_speedSection; }
/// Scans the loaded items for settings items
static bool scanForMissionSettings(QmlObjectListModel* visualItems, int scanIndex);
bool scanForMissionSettings(QmlObjectListModel* visualItems, int scanIndex);
/// Adds the optional mission end action to the list
/// @param items Mission items list to append to
......
......@@ -41,9 +41,9 @@ public:
/// Scans the loaded items for the section items
/// @param visualItems Item list
/// @param scanIndex[in,out] Index to start scanning from
/// @param scanIndex Index to start scanning from
/// @return true: section found, items added, scanIndex updated
virtual bool scanForSection(QmlObjectListModel* visualItems, int& scanIndex) = 0;
virtual bool scanForSection(QmlObjectListModel* visualItems, int scanIndex) = 0;
/// Appends the mission items associated with this section
/// @param items List to append to
......
/****************************************************************************
*
* (c) 2009-2016 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org>
*
* QGroundControl is licensed according to the terms in the file
* COPYING.md in the root of the source code directory.
*
****************************************************************************/
#include "SectionTest.h"
#include "SurveyMissionItem.h"
SectionTest::SectionTest(void)
: _simpleItem(NULL)
{
}
void SectionTest::init(void)
{
VisualMissionItemTest::init();
rgSectionSignals[availableChangedIndex] = SIGNAL(availableChanged(bool));
rgSectionSignals[settingsSpecifiedChangedIndex] = SIGNAL(settingsSpecifiedChanged(bool));
rgSectionSignals[dirtyChangedIndex] = SIGNAL(dirtyChanged(bool));
rgSectionSignals[itemCountChangedIndex] = SIGNAL(itemCountChanged(int));
MissionItem missionItem(1, // sequence number
MAV_CMD_NAV_WAYPOINT,
MAV_FRAME_GLOBAL_RELATIVE_ALT,
10.1234567, // param 1-7
20.1234567,
30.1234567,
40.1234567,
50.1234567,
60.1234567,
70.1234567,
true, // autoContinue
false); // isCurrentItem
_simpleItem = new SimpleMissionItem(_offlineVehicle, missionItem);
}
void SectionTest::cleanup(void)
{
delete _simpleItem;
VisualMissionItemTest::cleanup();
}
void SectionTest::_createSpy(Section* section, MultiSignalSpy** sectionSpy)
{
*sectionSpy = NULL;
MultiSignalSpy* spy = new MultiSignalSpy();
QCOMPARE(spy->init(section, rgSectionSignals, cSectionSignals), true);
*sectionSpy = spy;
}
void SectionTest::_missionItemsEqual(MissionItem& item1, MissionItem& item2)
{
QCOMPARE(item1.command(), item2.command());
QCOMPARE(item1.frame(), item2.frame());
QCOMPARE(item1.autoContinue(), item2.autoContinue());
QCOMPARE(item1.param1(), item2.param1());
QCOMPARE(item1.param2(), item2.param2());
QCOMPARE(item1.param3(), item2.param3());
QCOMPARE(item1.param4(), item2.param4());
QCOMPARE(item1.param5(), item2.param5());
QCOMPARE(item1.param6(), item2.param6());
QCOMPARE(item1.param7(), item2.param7());
}
void SectionTest::_commonScanTest(Section* section)
{
QCOMPARE(section->available(), true);
QmlObjectListModel emptyVisualItems;
QmlObjectListModel waypointVisualItems;
MissionItem waypointItem(0, MAV_CMD_NAV_WAYPOINT, MAV_FRAME_GLOBAL_RELATIVE_ALT, 0, 0, 0, 0, 0, 0, 0, true, false);
SimpleMissionItem simpleItem(_offlineVehicle, waypointItem);
waypointVisualItems.append(&simpleItem);
waypointVisualItems.append(&simpleItem);
waypointVisualItems.append(&simpleItem);
QmlObjectListModel complexVisualItems;
SurveyMissionItem surveyItem(_offlineVehicle);
complexVisualItems.append(&surveyItem);
// This tests the common cases which should not lead to scan succeess
int scanIndex = 0;
QCOMPARE(section->scanForSection(&emptyVisualItems, scanIndex), false);
QCOMPARE(scanIndex, 0);
scanIndex = 0;
QCOMPARE(section->scanForSection(&waypointVisualItems, scanIndex), false);
QCOMPARE(scanIndex, 0);
scanIndex = 0;
QCOMPARE(section->scanForSection(&complexVisualItems, scanIndex), false);
QCOMPARE(scanIndex, 0);
}
/****************************************************************************
*
* (c) 2009-2016 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org>
*
* QGroundControl is licensed according to the terms in the file
* COPYING.md in the root of the source code directory.
*
****************************************************************************/
#pragma once
#include "VisualMissionItemTest.h"
#include "SimpleMissionItemTest.h"
/// Unit test for Sections
class SectionTest : public VisualMissionItemTest
{
Q_OBJECT
public:
SectionTest(void);
void init(void) override;
void cleanup(void) override;
protected:
void _createSpy(Section* section, MultiSignalSpy** sectionSpy);
void _missionItemsEqual(MissionItem& item1, MissionItem& item2);
void _commonScanTest(Section* section);
enum {
availableChangedIndex = 0,
settingsSpecifiedChangedIndex,
dirtyChangedIndex,
itemCountChangedIndex,
maxSignalIndex,
};
enum {
availableChangedMask = 1 << availableChangedIndex,
settingsSpecifiedChangedMask = 1 << settingsSpecifiedChangedIndex,
dirtyChangedMask = 1 << dirtyChangedIndex,
itemCountChangedMask = 1 << itemCountChangedIndex
};
static const size_t cSectionSignals = maxSignalIndex;
const char* rgSectionSignals[cSectionSignals];
SimpleMissionItem* _simpleItem;
};
......@@ -560,7 +560,10 @@ void SimpleMissionItem::setDirty(bool dirty)
{
if (!_homePositionSpecialCase || (_dirty != dirty)) {
_dirty = dirty;
_cameraSection->setDirty(false);
if (!dirty) {
_cameraSection->setDirty(false);
_speedSection->setDirty(false);
}
emit dirtyChanged(dirty);
}
}
......@@ -690,7 +693,7 @@ double SimpleMissionItem::specifiedGimbalYaw(void)
return _cameraSection->available() ? _cameraSection->specifiedGimbalYaw() : missionItem().specifiedGimbalYaw();
}
bool SimpleMissionItem::scanForSections(QmlObjectListModel* visualItems, int& scanIndex, Vehicle* vehicle)
bool SimpleMissionItem::scanForSections(QmlObjectListModel* visualItems, int scanIndex, Vehicle* vehicle)
{
bool sectionFound = false;
......
......@@ -52,7 +52,7 @@ public:
/// @param scanIndex Index to start scanning from
/// @param vehicle Vehicle associated with this mission
/// @return true: section found, scanIndex updated
bool scanForSections(QmlObjectListModel* visualItems, int& scanIndex, Vehicle* vehicle);
bool scanForSections(QmlObjectListModel* visualItems, int scanIndex, Vehicle* vehicle);
// Property accesors
......
This diff is collapsed.
......@@ -7,18 +7,13 @@
*
****************************************************************************/
#pragma once
#ifndef SimpleMissionItemTest_H
#define SimpleMissionItemTest_H
#include "UnitTest.h"
#include "TCPLink.h"
#include "MultiSignalSpy.h"
#include <QGeoCoordinate>
#include "VisualMissionItemTest.h"
#include "SimpleMissionItem.h"
/// Unit test for SimpleMissionItem
class SimpleMissionItemTest : public UnitTest
class SimpleMissionItemTest : public VisualMissionItemTest
{
Q_OBJECT
......@@ -30,10 +25,34 @@ public:
private slots:
void _testSignals(void);
void _testCameraSectionSignals(void);
void _testEditorFacts(void);
void _testDefaultValues(void);
private:
enum {
commandChangedIndex = 0,
frameChangedIndex,
friendlyEditAllowedChangedIndex,
headingDegreesChangedIndex,
rawEditChangedIndex,
cameraSectionChangedIndex,
speedSectionChangedIndex,
maxSignalIndex,
};
enum {
commandChangedMask = 1 << commandChangedIndex,
frameChangedMask = 1 << frameChangedIndex,
friendlyEditAllowedChangedMask = 1 << friendlyEditAllowedChangedIndex,
headingDegreesChangedMask = 1 << headingDegreesChangedIndex,
rawEditChangedMask = 1 << rawEditChangedIndex,
cameraSectionChangedMask = 1 << cameraSectionChangedIndex,
speedSectionChangedMask = 1 << speedSectionChangedIndex
};
static const size_t cSimpleItemSignals = maxSignalIndex;
const char* rgSimpleItemSignals[cSimpleItemSignals];
typedef struct {
MAV_CMD command;
......@@ -51,7 +70,9 @@ private:
bool relativeAltCheckbox;
} ItemExpected_t;
Vehicle* _offlineVehicle;
SimpleMissionItem* _simpleItem;
MultiSignalSpy* _spySimpleItem;
MultiSignalSpy* _spyVisualItem;
static const ItemInfo_t _rgItemInfo[];
static const ItemExpected_t _rgItemExpected[];
......@@ -64,5 +85,3 @@ private:
static const FactValue_t _rgFactValuesConditionDelay[];
static const FactValue_t _rgFactValuesDoJump[];
};
#endif
......@@ -41,7 +41,6 @@ SpeedSection::SpeedSection(Vehicle* vehicle, QObject* parent)
_flightSpeedFact.setMetaData(_metaDataMap[_flightSpeedName]);
_flightSpeedFact.setRawValue(flightSpeed);
connect(this, &SpeedSection::specifyFlightSpeedChanged, this, &SpeedSection::_setDirtyAndUpdateItemCount);
connect(this, &SpeedSection::specifyFlightSpeedChanged, this, &SpeedSection::settingsSpecifiedChanged);
connect(&_flightSpeedFact, &Fact::valueChanged, this, &SpeedSection::_setDirty);
}
......@@ -66,12 +65,6 @@ void SpeedSection::_setDirty(void)
setDirty(true);
}
void SpeedSection::_setDirtyAndUpdateItemCount(void)
{
setDirty(true);
emit itemCountChanged(itemCount());
}
void SpeedSection::setDirty(bool dirty)
{
if (_dirty != dirty) {
......@@ -85,6 +78,8 @@ void SpeedSection::setSpecifyFlightSpeed(bool specifyFlightSpeed)
if (specifyFlightSpeed != _specifyFlightSpeed) {
_specifyFlightSpeed = specifyFlightSpeed;
emit specifyFlightSpeedChanged(specifyFlightSpeed);
setDirty(true);
emit itemCountChanged(itemCount());
}
}
......@@ -113,7 +108,7 @@ void SpeedSection::appendSectionItems(QList<MissionItem*>& items, QObject* missi
}
}
bool SpeedSection::scanForSection(QmlObjectListModel* visualItems, int& scanIndex)
bool SpeedSection::scanForSection(QmlObjectListModel* visualItems, int scanIndex)
{
if (!_available || scanIndex >= visualItems->count()) {
return false;
......@@ -137,7 +132,6 @@ bool SpeedSection::scanForSection(QmlObjectListModel* visualItems, int& scanInde
visualItems->removeAt(scanIndex)->deleteLater();
_flightSpeedFact.setRawValue(missionItem.param2());
setSpecifyFlightSpeed(true);
scanIndex++;
return true;
}
......
......@@ -32,7 +32,7 @@ public:
bool dirty (void) const override { return _dirty; }
void setAvailable (bool available) override;
void setDirty (bool dirty) override;
bool scanForSection (QmlObjectListModel* visualItems, int& scanIndex) override;
bool scanForSection (QmlObjectListModel* visualItems, int scanIndex) override;
void appendSectionItems (QList<MissionItem*>& items, QObject* missionItemParent, int& seqNum) override;
int itemCount (void) const override;
bool settingsSpecified (void) const override;
......@@ -42,13 +42,12 @@ signals:
private slots:
void _setDirty(void);
void _setDirtyAndUpdateItemCount(void);
private:
bool _available;
bool _dirty;
bool _specifyFlightSpeed;
Fact _flightSpeedFact;
bool _available;
bool _dirty;
bool _specifyFlightSpeed;
Fact _flightSpeedFact;
static QMap<QString, FactMetaData*> _metaDataMap;
......
This diff is collapsed.
/****************************************************************************
*
* (c) 2009-2016 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org>
*
* QGroundControl is licensed according to the terms in the file
* COPYING.md in the root of the source code directory.
*
****************************************************************************/
#pragma once
#include "SectionTest.h"
#include "SpeedSection.h"
/// Unit test for CameraSection
class SpeedSectionTest : public SectionTest
{
Q_OBJECT
public:
SpeedSectionTest(void);
void init(void) override;
void cleanup(void) override;
private slots:
void _testDirty(void);
void _testSettingsAvailable(void);
void _checkAvailable(void);
void _testItemCount(void);
void _testAppendSectionItems(void);
void _testScanForSection(void);
private:
void _createSpy(SpeedSection* speedSection, MultiSignalSpy** speedSpy);
enum {
specifyFlightSpeedChangedIndex = 0,
maxSignalIndex,
};
enum {
specifyFlightSpeedChangedMask = 1 << specifyFlightSpeedChangedIndex
};
static const size_t cSpeedSignals = maxSignalIndex;
const char* rgSpeedSignals[cSpeedSignals];
MultiSignalSpy* _spySpeed;
MultiSignalSpy* _spySection;
SpeedSection* _speedSection;
};
/****************************************************************************
*
* (c) 2009-2016 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org>
*
* QGroundControl is licensed according to the terms in the file
* COPYING.md in the root of the source code directory.
*
****************************************************************************/
#include "VisualMissionItemTest.h"
#include "SimpleMissionItem.h"
#include "QGCApplication.h"
VisualMissionItemTest::VisualMissionItemTest(void)
: _offlineVehicle(NULL)
{
}
void VisualMissionItemTest::init(void)
{
UnitTest::init();
_offlineVehicle = new Vehicle(MAV_AUTOPILOT_PX4,
MAV_TYPE_QUADROTOR,
qgcApp()->toolbox()->firmwarePluginManager(),
this);
rgVisualItemSignals[altDifferenceChangedIndex] = SIGNAL(altDifferenceChanged(double));
rgVisualItemSignals[altPercentChangedIndex] = SIGNAL(altPercentChanged(double));
rgVisualItemSignals[azimuthChangedIndex] = SIGNAL(azimuthChanged(double));
rgVisualItemSignals[commandDescriptionChangedIndex] = SIGNAL(commandDescriptionChanged());
rgVisualItemSignals[commandNameChangedIndex] = SIGNAL(commandNameChanged());
rgVisualItemSignals[abbreviationChangedIndex] = SIGNAL(abbreviationChanged());
rgVisualItemSignals[coordinateChangedIndex] = SIGNAL(coordinateChanged(const QGeoCoordinate&));
rgVisualItemSignals[exitCoordinateChangedIndex] = SIGNAL(exitCoordinateChanged(const QGeoCoordinate&));
rgVisualItemSignals[dirtyChangedIndex] = SIGNAL(dirtyChanged(bool));
rgVisualItemSignals[distanceChangedIndex] = SIGNAL(distanceChanged(double));
rgVisualItemSignals[isCurrentItemChangedIndex] = SIGNAL(isCurrentItemChanged(bool));
rgVisualItemSignals[sequenceNumberChangedIndex] = SIGNAL(sequenceNumberChanged(int));
rgVisualItemSignals[isSimpleItemChangedIndex] = SIGNAL(isSimpleItemChanged(bool));
rgVisualItemSignals[specifiesCoordinateChangedIndex] = SIGNAL(specifiesCoordinateChanged());
rgVisualItemSignals[isStandaloneCoordinateChangedIndex] = SIGNAL(isStandaloneCoordinateChanged());
rgVisualItemSignals[specifiesAltitudeOnlyChangedIndex] = SIGNAL(specifiesAltitudeOnlyChanged());
rgVisualItemSignals[specifiedFlightSpeedChangedIndex] = SIGNAL(specifiedFlightSpeedChanged());
rgVisualItemSignals[specifiedGimbalYawChangedIndex] = SIGNAL(specifiedGimbalYawChanged());
rgVisualItemSignals[lastSequenceNumberChangedIndex] = SIGNAL(lastSequenceNumberChanged(int));
rgVisualItemSignals[missionGimbalYawChangedIndex] = SIGNAL(missionGimbalYawChanged(double));
rgVisualItemSignals[missionVehicleYawChangedIndex] = SIGNAL(missionVehicleYawChanged(double));
rgVisualItemSignals[coordinateHasRelativeAltitudeChangedIndex] = SIGNAL(coordinateHasRelativeAltitudeChanged(bool));
rgVisualItemSignals[exitCoordinateHasRelativeAltitudeChangedIndex] = SIGNAL(exitCoordinateHasRelativeAltitudeChanged(bool));
rgVisualItemSignals[exitCoordinateSameAsEntryChangedIndex] = SIGNAL(exitCoordinateSameAsEntryChanged(bool));
}
void VisualMissionItemTest::cleanup(void)
{
delete _offlineVehicle;
UnitTest::cleanup();
}
/****************************************************************************
*
* (c) 2009-2016 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org>
*
* QGroundControl is licensed according to the terms in the file
* COPYING.md in the root of the source code directory.
*
****************************************************************************/
#pragma once
#include "UnitTest.h"
#include "TCPLink.h"
#include "MultiSignalSpy.h"
#include <QGeoCoordinate>
/// Unit test for SimpleMissionItem
class VisualMissionItemTest : public UnitTest
{
Q_OBJECT
public:
VisualMissionItemTest(void);
void init(void) override;
void cleanup(void) override;
protected:
enum {
altDifferenceChangedIndex = 0,
altPercentChangedIndex,
azimuthChangedIndex,
commandDescriptionChangedIndex,
commandNameChangedIndex,
abbreviationChangedIndex,
coordinateChangedIndex,
exitCoordinateChangedIndex,
dirtyChangedIndex,
distanceChangedIndex,
isCurrentItemChangedIndex,
sequenceNumberChangedIndex,
isSimpleItemChangedIndex,
specifiesCoordinateChangedIndex,
isStandaloneCoordinateChangedIndex,
specifiesAltitudeOnlyChangedIndex,
specifiedFlightSpeedChangedIndex,
specifiedGimbalYawChangedIndex,
lastSequenceNumberChangedIndex,
missionGimbalYawChangedIndex,
missionVehicleYawChangedIndex,
coordinateHasRelativeAltitudeChangedIndex,
exitCoordinateHasRelativeAltitudeChangedIndex,
exitCoordinateSameAsEntryChangedIndex,
maxSignalIndex,
};
enum {
altDifferenceChangedMask = 1 << altDifferenceChangedIndex,
altPercentChangedMask = 1 << altPercentChangedIndex,
azimuthChangedMask = 1 << azimuthChangedIndex,
commandDescriptionChangedMask = 1 << commandDescriptionChangedIndex,
commandNameChangedMask = 1 << commandNameChangedIndex,
abbreviationChangedMask = 1 << abbreviationChangedIndex,
coordinateChangedMask = 1 << coordinateChangedIndex,
exitCoordinateChangedMask = 1 << exitCoordinateChangedIndex,
dirtyChangedMask = 1 << dirtyChangedIndex,
distanceChangedMask = 1 << distanceChangedIndex,
isCurrentItemChangedMask = 1 << isCurrentItemChangedIndex,
sequenceNumberChangedMask = 1 << sequenceNumberChangedIndex,
isSimpleItemChangedMask = 1 << isSimpleItemChangedIndex,
specifiesCoordinateChangedMask = 1 << specifiesCoordinateChangedIndex,
isStandaloneCoordinateChangedMask = 1 << isStandaloneCoordinateChangedIndex,
specifiesAltitudeOnlyChangedMask = 1 << specifiesAltitudeOnlyChangedIndex,
specifiedFlightSpeedChangedMask = 1 << specifiedFlightSpeedChangedIndex,
specifiedGimbalYawChangedMask = 1 << specifiedGimbalYawChangedIndex,
lastSequenceNumberChangedMask = 1 << lastSequenceNumberChangedIndex,
missionGimbalYawChangedMask = 1 << missionGimbalYawChangedIndex,
missionVehicleYawChangedMask = 1 << missionVehicleYawChangedIndex,
coordinateHasRelativeAltitudeChangedMask = 1 << coordinateHasRelativeAltitudeChangedIndex,
exitCoordinateHasRelativeAltitudeChangedMask = 1 << exitCoordinateHasRelativeAltitudeChangedIndex,
exitCoordinateSameAsEntryChangedMask = 1 << exitCoordinateSameAsEntryChangedIndex,
};
static const size_t cVisualItemSignals = maxSignalIndex;
const char* rgVisualItemSignals[cVisualItemSignals];
Vehicle* _offlineVehicle;
};
......@@ -32,6 +32,9 @@
#include "MissionCommandTreeTest.h"
#include "LogDownloadTest.h"
#include "SendMavCommandTest.h"
#include "VisualMissionItemTest.h"
#include "CameraSectionTest.h"
#include "SpeedSectionTest.h"
UT_REGISTER_TEST(FactSystemTestGeneric)
UT_REGISTER_TEST(FactSystemTestPX4)
......@@ -51,6 +54,8 @@ UT_REGISTER_TEST(MissionCommandTreeTest)
UT_REGISTER_TEST(LogDownloadTest)
UT_REGISTER_TEST(SendMavCommandTest)
UT_REGISTER_TEST(SurveyMissionItemTest)
UT_REGISTER_TEST(CameraSectionTest)
UT_REGISTER_TEST(SpeedSectionTest)
// List of unit test which are currently disabled.
// If disabling a new test, include reason in comment.
......
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