Commit c999a76c authored by DonLakeFlyer's avatar DonLakeFlyer
Browse files

Scanning fixes plus unit test

parent e9896fec
......@@ -220,18 +220,18 @@ void CameraSection::appendSectionItems(QList<MissionItem*>& items, QObject* miss
break;
case TakePhoto:
item = new MissionItem(nextSequenceNumber++,
MAV_CMD_IMAGE_START_CAPTURE,
MAV_FRAME_MISSION,
0, // camera id = 0, all cameras
0, // Interval (none)
1, // Take 1 photo
-1, // Max horizontal resolution
-1, // Max vertical resolution
0, 0, // param 6-7 not used
true, // autoContinue
false, // isCurrentItem
missionItemParent);
item = new MissionItem(nextSequenceNumber++,
MAV_CMD_IMAGE_START_CAPTURE,
MAV_FRAME_MISSION,
0, // camera id = 0, all cameras
0, // Interval (none)
1, // Take 1 photo
-1, // Max horizontal resolution
-1, // Max vertical resolution
0, 0, // param 6-7 not used
true, // autoContinue
false, // isCurrentItem
missionItemParent);
break;
}
if (item) {
......@@ -240,139 +240,208 @@ void CameraSection::appendSectionItems(QList<MissionItem*>& items, QObject* miss
}
}
bool CameraSection::scanForSection(QmlObjectListModel* visualItems, int scanIndex)
bool CameraSection::_scanGimbal(QmlObjectListModel* visualItems, int scanIndex)
{
bool foundGimbal = false;
bool foundCameraAction = false;
bool foundCameraMode = false;
bool stopLooking = false;
qCDebug(CameraSectionLog) << "CameraSection::scanForCameraSection" << visualItems->count() << scanIndex;
if (!_available || scanIndex >= visualItems->count()) {
return false;
}
// Scan through the initial mission items for possible mission settings
while (!stopLooking && visualItems->count() > scanIndex) {
SimpleMissionItem* item = visualItems->value<SimpleMissionItem*>(scanIndex);
if (!item) {
// We hit a complex item there can be no more possible mission settings
return foundGimbal || foundCameraAction;
}
SimpleMissionItem* item = visualItems->value<SimpleMissionItem*>(scanIndex);
if (item) {
MissionItem& missionItem = item->missionItem();
qCDebug(CameraSectionLog) << item->command() << missionItem.param1() << missionItem.param2() << missionItem.param3() << missionItem.param4() << missionItem.param5() << missionItem.param6() << missionItem.param7() ;
// See CameraSection::appendMissionItems for specs on what compomises a known camera section item
switch ((MAV_CMD)item->command()) {
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;
if ((MAV_CMD)item->command() == MAV_CMD_DO_MOUNT_CONTROL) {
if (missionItem.param2() == 0 && missionItem.param4() == 0 && missionItem.param5() == 0 && missionItem.param6() == 0 && missionItem.param7() == MAV_MOUNT_MODE_MAVLINK_TARGETING) {
setSpecifyGimbal(true);
gimbalPitch()->setRawValue(missionItem.param1());
gimbalYaw()->setRawValue(missionItem.param3());
visualItems->removeAt(scanIndex)->deleteLater();
} else {
stopLooking = true;
return true;
}
break;
}
}
case MAV_CMD_IMAGE_START_CAPTURE:
// This could possibly be TakePhotosIntervalTime or TakePhoto
if (!foundCameraAction &&
// TakePhotosIntervalTime matching
((missionItem.param1() == 0 && missionItem.param2() >= 1 && missionItem.param3() == 0 && missionItem.param4() == -1 && missionItem.param5() == -1 && missionItem.param6() == 0 && missionItem.param7() == 0) ||
// TakePhoto matching
(missionItem.param1() == 0 && missionItem.param2() == 0 && missionItem.param3() == 1 && missionItem.param4() == -1 && missionItem.param5() == -1 && missionItem.param6() == 0 && missionItem.param7() == 0))) {
foundCameraAction = true;
if (missionItem.param2() == 0) {
cameraAction()->setRawValue(TakePhoto);
} else {
cameraAction()->setRawValue(TakePhotosIntervalTime);
cameraPhotoIntervalTime()->setRawValue(missionItem.param2());
}
return false;
}
bool CameraSection::_scanTakePhoto(QmlObjectListModel* visualItems, int scanIndex)
{
SimpleMissionItem* item = visualItems->value<SimpleMissionItem*>(scanIndex);
if (item) {
MissionItem& missionItem = item->missionItem();
if ((MAV_CMD)item->command() == MAV_CMD_IMAGE_START_CAPTURE) {
if (missionItem.param1() == 0 && missionItem.param2() == 0 && missionItem.param3() == 1 && missionItem.param4() == -1 && missionItem.param5() == -1 && missionItem.param6() == 0 && missionItem.param7() == 0) {
cameraAction()->setRawValue(TakePhoto);
visualItems->removeAt(scanIndex)->deleteLater();
} else {
stopLooking = true;
return true;
}
break;
}
}
case MAV_CMD_DO_SET_CAM_TRIGG_DIST:
if (!foundCameraAction && missionItem.param1() >= 0 && missionItem.param2() == 0 && missionItem.param3() == 0 && missionItem.param4() == 0 && missionItem.param5() == 0 && missionItem.param6() == 0 && missionItem.param7() == 0) {
// At this point we don't know if we have a stop taking photos pair, or just a distance trigger
return false;
}
if (missionItem.param1() == 0 && scanIndex < visualItems->count() - 1) {
// Possible stop taking photos pair
bool CameraSection::_scanTakePhotosIntervalTime(QmlObjectListModel* visualItems, int scanIndex)
{
SimpleMissionItem* item = visualItems->value<SimpleMissionItem*>(scanIndex);
if (item) {
MissionItem& missionItem = item->missionItem();
if ((MAV_CMD)item->command() == MAV_CMD_IMAGE_START_CAPTURE) {
if (missionItem.param1() == 0 && missionItem.param2() >= 1 && missionItem.param3() == 0 && missionItem.param4() == -1 && missionItem.param5() == -1 && missionItem.param6() == 0 && missionItem.param7() == 0) {
cameraAction()->setRawValue(TakePhotosIntervalTime);
cameraPhotoIntervalTime()->setRawValue(missionItem.param2());
visualItems->removeAt(scanIndex)->deleteLater();
return true;
}
}
}
return false;
}
bool CameraSection::_scanStopTakingPhotos(QmlObjectListModel* visualItems, int scanIndex)
{
SimpleMissionItem* item = visualItems->value<SimpleMissionItem*>(scanIndex);
if (item) {
MissionItem& missionItem = item->missionItem();
if ((MAV_CMD)item->command() == MAV_CMD_DO_SET_CAM_TRIGG_DIST) {
if (missionItem.param1() == 0 && missionItem.param2() == 0 && missionItem.param3() == 0 && missionItem.param4() == 0 && missionItem.param5() == 0 && missionItem.param6() == 0 && missionItem.param7() == 0) {
if (scanIndex < visualItems->count() - 1) {
SimpleMissionItem* nextItem = visualItems->value<SimpleMissionItem*>(scanIndex + 1);
if (nextItem) {
MissionItem& nextMissionItem = nextItem->missionItem();
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;
cameraAction()->setRawValue(StopTakingPhotos);
visualItems->removeAt(scanIndex)->deleteLater();
visualItems->removeAt(scanIndex)->deleteLater();
stopLooking = true;
break;
return true;
}
}
}
}
}
}
// We didn't find a stop taking photos pair, check for trigger distance
if (missionItem.param1() > 0) {
foundCameraAction = true;
cameraAction()->setRawValue(TakePhotoIntervalDistance);
cameraPhotoIntervalDistance()->setRawValue(missionItem.param1());
visualItems->removeAt(scanIndex)->deleteLater();
stopLooking = true;
break;
}
return false;
}
bool CameraSection::_scanTriggerDistance(QmlObjectListModel* visualItems, int scanIndex)
{
SimpleMissionItem* item = visualItems->value<SimpleMissionItem*>(scanIndex);
if (item) {
MissionItem& missionItem = item->missionItem();
if ((MAV_CMD)item->command() == MAV_CMD_DO_SET_CAM_TRIGG_DIST) {
if (missionItem.param1() >= 0 && missionItem.param2() == 0 && missionItem.param3() == 0 && missionItem.param4() == 0 && missionItem.param5() == 0 && missionItem.param6() == 0 && missionItem.param7() == 0) {
cameraAction()->setRawValue(TakePhotoIntervalDistance);
cameraPhotoIntervalDistance()->setRawValue(missionItem.param1());
visualItems->removeAt(scanIndex)->deleteLater();
return true;
}
stopLooking = true;
break;
}
}
return false;
}
case MAV_CMD_VIDEO_START_CAPTURE:
if (!foundCameraAction && missionItem.param1() == 0 && missionItem.param2() == -1 && missionItem.param3() == -1 && missionItem.param4() == -1 && missionItem.param5() == 0 && missionItem.param6() == 0 && missionItem.param7() == 0) {
foundCameraAction = true;
bool CameraSection::_scanTakeVideo(QmlObjectListModel* visualItems, int scanIndex)
{
SimpleMissionItem* item = visualItems->value<SimpleMissionItem*>(scanIndex);
if (item) {
MissionItem& missionItem = item->missionItem();
if ((MAV_CMD)item->command() == MAV_CMD_VIDEO_START_CAPTURE) {
if (missionItem.param1() == 0 && missionItem.param2() == -1 && missionItem.param3() == -1 && missionItem.param4() == -1 && missionItem.param5() == 0 && missionItem.param6() == 0 && missionItem.param7() == 0) {
cameraAction()->setRawValue(TakeVideo);
visualItems->removeAt(scanIndex)->deleteLater();
} else {
stopLooking = true;
return true;
}
break;
}
}
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;
return false;
}
bool CameraSection::_scanStopTakingVideo(QmlObjectListModel* visualItems, int scanIndex)
{
SimpleMissionItem* item = visualItems->value<SimpleMissionItem*>(scanIndex);
if (item) {
MissionItem& missionItem = item->missionItem();
if ((MAV_CMD)item->command() == MAV_CMD_VIDEO_STOP_CAPTURE) {
if (missionItem.param1() == 0 && missionItem.param2() == 0 && missionItem.param3() == 0 && missionItem.param4() == 0 && missionItem.param5() == 0 && missionItem.param6() == 0 && missionItem.param7() == 0) {
cameraAction()->setRawValue(StopTakingVideo);
visualItems->removeAt(scanIndex)->deleteLater();
} else {
stopLooking = true;
return true;
}
break;
}
}
case MAV_CMD_SET_CAMERA_MODE:
return false;
}
bool CameraSection::_scanSetCameraMode(QmlObjectListModel* visualItems, int scanIndex)
{
SimpleMissionItem* item = visualItems->value<SimpleMissionItem*>(scanIndex);
if (item) {
MissionItem& missionItem = item->missionItem();
if ((MAV_CMD)item->command() == MAV_CMD_SET_CAMERA_MODE) {
// We specifically don't test param 5/6/7 since we don't have NaN persistence for those fields
if (!foundCameraMode && missionItem.param1() == 0 && (missionItem.param2() == 0 || missionItem.param2() == 1) && qIsNaN(missionItem.param3())) {
foundCameraMode = true;
if (missionItem.param1() == 0 && (missionItem.param2() == 0 || missionItem.param2() == 1) && qIsNaN(missionItem.param3())) {
setSpecifyCameraMode(true);
cameraMode()->setRawValue(missionItem.param2());
visualItems->removeAt(scanIndex)->deleteLater();
} else {
stopLooking = true;
return true;
}
break;
}
}
default:
stopLooking = true;
break;
return false;
}
bool CameraSection::scanForSection(QmlObjectListModel* visualItems, int scanIndex)
{
bool foundGimbal = false;
bool foundCameraAction = false;
bool foundCameraMode = false;
qCDebug(CameraSectionLog) << "CameraSection::scanForCameraSection visualItems->count():scanIndex;" << visualItems->count() << scanIndex;
if (!_available || scanIndex >= visualItems->count()) {
return false;
}
// Scan through the initial mission items for possible mission settings
while (visualItems->count() > scanIndex) {
if (!foundGimbal && _scanGimbal(visualItems, scanIndex)) {
foundGimbal = true;
continue;
}
if (!foundCameraAction && _scanTakePhoto(visualItems, scanIndex)) {
foundCameraAction = true;
continue;
}
if (!foundCameraAction && _scanTakePhotosIntervalTime(visualItems, scanIndex)) {
foundCameraAction = true;
continue;
}
if (!foundCameraAction && _scanStopTakingPhotos(visualItems, scanIndex)) {
foundCameraAction = true;
continue;
}
if (!foundCameraAction && _scanTriggerDistance(visualItems, scanIndex)) {
foundCameraAction = true;
continue;
}
if (!foundCameraAction && _scanTakeVideo(visualItems, scanIndex)) {
foundCameraAction = true;
continue;
}
if (!foundCameraAction && _scanStopTakingVideo(visualItems, scanIndex)) {
foundCameraAction = true;
continue;
}
if (!foundCameraMode && _scanSetCameraMode(visualItems, scanIndex)) {
foundCameraMode = true;
continue;
}
break;
}
qCDebug(CameraSectionLog) << foundGimbal << foundCameraAction << foundCameraMode;
qCDebug(CameraSectionLog) << "CameraSection::scanForCameraSection foundGimbal:foundCameraAction:foundCameraMode;" << foundGimbal << foundCameraAction << foundCameraMode;
_settingsSpecified = foundGimbal || foundCameraAction || foundCameraMode;
emit settingsSpecifiedChanged(_settingsSpecified);
......
......@@ -90,6 +90,15 @@ private slots:
void _cameraActionChanged(void);
private:
bool _scanGimbal(QmlObjectListModel* visualItems, int scanIndex);
bool _scanTakePhoto(QmlObjectListModel* visualItems, int scanIndex);
bool _scanTakePhotosIntervalTime(QmlObjectListModel* visualItems, int scanIndex);
bool _scanStopTakingPhotos(QmlObjectListModel* visualItems, int scanIndex);
bool _scanTriggerDistance(QmlObjectListModel* visualItems, int scanIndex);
bool _scanTakeVideo(QmlObjectListModel* visualItems, int scanIndex);
bool _scanStopTakingVideo(QmlObjectListModel* visualItems, int scanIndex);
bool _scanSetCameraMode(QmlObjectListModel* visualItems, int scanIndex);
bool _available;
bool _settingsSpecified;
bool _specifyGimbal;
......
......@@ -8,6 +8,9 @@
****************************************************************************/
#include "CameraSectionTest.h"
#include "QGCApplication.h"
#include "MissionCommandTree.h"
#include "MissionCommandUIInfo.h"
CameraSectionTest::CameraSectionTest(void)
: _spyCamera(NULL)
......@@ -20,6 +23,8 @@ CameraSectionTest::CameraSectionTest(void)
, _validStopVideoItem(NULL)
, _validStopDistanceItem(NULL)
, _validStopTimeItem(NULL)
, _validCameraPhotoModeItem(NULL)
, _validCameraVideoModeItem(NULL)
{
}
......@@ -116,6 +121,8 @@ void CameraSectionTest::cleanup(void)
delete _validStopDistanceItem;
delete _validStopTimeItem;
delete _validTakePhotoItem;
delete _validCameraPhotoModeItem;
delete _validCameraVideoModeItem;
SectionTest::cleanup();
}
......@@ -567,7 +574,7 @@ void CameraSectionTest::_testScanForGimbalSection(void)
visualItems.clear();
scanIndex = 0;
/*
/*
MAV_CMD_DO_MOUNT_CONTROL
Mission Param #1 pitch (WIP: DEPRECATED: or lat in degrees) depending on mount mode.
Mission Param #2 roll (WIP: DEPRECATED: or lon in degrees) depending on mount mode.
......@@ -662,7 +669,7 @@ void CameraSectionTest::_testScanForCameraModeSection(void)
visualItems.clear();
scanIndex = 0;
/*
/*
MAV_CMD_SET_CAMERA_MODE
Mission Param #1 Camera ID (0 for all cameras, 1 for first, 2 for second, etc.)
Mission Param #2 Camera mode (0: photo mode, 1: video mode)
......@@ -691,7 +698,7 @@ void CameraSectionTest::_testScanForPhotoIntervalTimeSection(void)
_commonScanTest(_cameraSection);
/*
/*
MAV_CMD_IMAGE_START_CAPTURE WIP: Start image capture sequence. Sends CAMERA_IMAGE_CAPTURED after each capture.
Mission Param #1 Camera ID (0 for all cameras, 1 for first, 2 for second, etc.)
Mission Param #2 Duration between two consecutive pictures (in seconds)
......@@ -762,7 +769,7 @@ void CameraSectionTest::_testScanForPhotoIntervalDistanceSection(void)
_commonScanTest(_cameraSection);
/*
/*
MAV_CMD_DO_SET_CAM_TRIGG_DIST Mission command to set CAM_TRIGG_DIST for this flight
Mission Param #1 Camera trigger distance (meters)
Mission Param #2 Empty
......@@ -852,7 +859,7 @@ void CameraSectionTest::_testScanForStartVideoSection(void)
_commonScanTest(_cameraSection);
/*
/*
MAV_CMD_VIDEO_START_CAPTURE WIP: Starts video capture (recording)
Mission Param #1 Camera ID (0 for all cameras, 1 for first, 2 for second, etc.)
Mission Param #2 Frames per second, set to -1 for highest framerate possible.
......@@ -939,7 +946,7 @@ void CameraSectionTest::_testScanForStopVideoSection(void)
_commonScanTest(_cameraSection);
/*
/*
MAV_CMD_VIDEO_STOP_CAPTURE Stop the current video capture (recording)
Mission Param #1 WIP: Camera ID
*/
......@@ -1057,7 +1064,7 @@ void CameraSectionTest::_testScanForTakePhotoSection(void)
_commonScanTest(_cameraSection);
/*
/*
MAV_CMD_IMAGE_START_CAPTURE Start image capture sequence. Sends CAMERA_IMAGE_CAPTURED after each capture.
Mission Param #1 Camera ID (0 for all cameras, 1 for first, 2 for second, etc.)
Mission Param #2 Duration between two consecutive pictures (in seconds)
......@@ -1118,8 +1125,42 @@ void CameraSectionTest::_testScanForTakePhotoSection(void)
visualItems.clear();
}
void CameraSectionTest::_testScanForFullSection(void)
void CameraSectionTest::_validateItemScan(SimpleMissionItem* validItem)
{
QVERIFY(_cameraSection->settingsSpecified());
if (validItem == _validGimbalItem) {
QCOMPARE(_cameraSection->specifyGimbal(), true);
QCOMPARE(_cameraSection->gimbalPitch()->rawValue().toDouble(), validItem->missionItem().param1());
QCOMPARE(_cameraSection->gimbalYaw()->rawValue().toDouble(), validItem->missionItem().param3());
} else if (validItem == _validDistanceItem) {
QCOMPARE(_cameraSection->cameraAction()->rawValue().toInt(), (int)CameraSection::TakePhotoIntervalDistance);
QCOMPARE(_cameraSection->cameraPhotoIntervalDistance()->rawValue().toInt(), (int)_validDistanceItem->missionItem().param1());
} else if (validItem == _validTimeItem) {
} else if (validItem == _validStartVideoItem) {
} else if (validItem == _validStopVideoItem) {
} else if (validItem == _validTakePhotoItem) {
} else if (validItem == _validCameraPhotoModeItem) {
} else if (validItem == _validCameraVideoModeItem) {
}
}
void CameraSectionTest::_resetSection(void)
{
_cameraSection->gimbalYaw()->setRawValue(0);
_cameraSection->gimbalPitch()->setRawValue(0);
_cameraSection->setSpecifyGimbal(false);
_cameraSection->cameraPhotoIntervalTime()->setRawValue(0);
_cameraSection->cameraPhotoIntervalDistance()->setRawValue(0);
_cameraSection->cameraAction()->setRawValue(CameraSection::CameraActionNone);
_cameraSection->cameraMode()->setRawValue(CameraSection::CameraModePhoto);
_cameraSection->setSpecifyCameraMode(false);
}
/// Test that we can scan the commands associated with the camera section in various orders/combinations.
void CameraSectionTest::_testScanForMultipleItems(void)
{
MissionCommandTree* commandTree = qgcApp()->toolbox()->missionCommandTree();
QCOMPARE(_cameraSection->available(), true);
int scanIndex = 0;
......@@ -1127,19 +1168,51 @@ void CameraSectionTest::_testScanForFullSection(void)
_commonScanTest(_cameraSection);
SimpleMissionItem* newValidGimbalItem = new SimpleMissionItem(_offlineVehicle, this);
SimpleMissionItem* newValidDistanceItem = new SimpleMissionItem(_offlineVehicle, this);
newValidGimbalItem->missionItem() = _validGimbalItem->missionItem();
newValidDistanceItem->missionItem() = _validDistanceItem->missionItem();
visualItems.append(newValidGimbalItem);
visualItems.append(newValidDistanceItem);
QCOMPARE(_cameraSection->scanForSection(&visualItems, scanIndex), true);
QCOMPARE(visualItems.count(), 0);
QCOMPARE(_cameraSection->settingsSpecified(), true);
QCOMPARE(_cameraSection->specifyGimbal(), true);
QCOMPARE(_cameraSection->cameraAction()->rawValue().toInt(), (int)CameraSection::TakePhotoIntervalDistance);
QCOMPARE(_cameraSection->cameraPhotoIntervalDistance()->rawValue().toInt(), (int)_validDistanceItem->missionItem().param1());
QCOMPARE(_cameraSection->gimbalPitch()->rawValue().toDouble(), _validGimbalItem->missionItem().param1());
QCOMPARE(_cameraSection->gimbalYaw()->rawValue().toDouble(), _validGimbalItem->missionItem().param3());
visualItems.clear();
QList<SimpleMissionItem*> rgCameraItems;
rgCameraItems << _validGimbalItem << _validCameraPhotoModeItem << _validCameraVideoModeItem;
QList<SimpleMissionItem*> rgActionItems;
rgActionItems << _validDistanceItem << _validTimeItem << _validStartVideoItem << _validStopVideoItem << _validTakePhotoItem;
// Camera action followed by gimbal/mode
foreach (SimpleMissionItem* actionItem, rgActionItems) {
foreach (SimpleMissionItem* cameraItem, rgCameraItems) {
SimpleMissionItem* item1 = new SimpleMissionItem(_offlineVehicle, this);
item1->missionItem() = actionItem->missionItem();
SimpleMissionItem* item2 = new SimpleMissionItem(_offlineVehicle, this);
item2->missionItem() = cameraItem->missionItem();
visualItems.append(item1);
visualItems.append(item2);
qDebug() << commandTree->getUIInfo(_offlineVehicle, (MAV_CMD)item1->command())->rawName() << commandTree->getUIInfo(_offlineVehicle, (MAV_CMD)item2->command())->rawName();;
scanIndex = 0;
QCOMPARE(_cameraSection->scanForSection(&visualItems, scanIndex), true);
_validateItemScan(cameraItem);
_resetSection();
visualItems.clearAndDeleteContents();
}
}
// Gimbal/Mode followed by camera action
foreach (SimpleMissionItem* actionItem, rgCameraItems) {
foreach (SimpleMissionItem* cameraItem, rgActionItems) {
SimpleMissionItem* item1 = new SimpleMissionItem(_offlineVehicle, this);
item1->missionItem() = actionItem->missionItem();
SimpleMissionItem* item2 = new SimpleMissionItem(_offlineVehicle, this);
item2->missionItem() = cameraItem->missionItem();
visualItems.append(item1);
visualItems.append(item2);
qDebug() << commandTree->getUIInfo(_offlineVehicle, (MAV_CMD)item1->command())->rawName() << commandTree->getUIInfo(_offlineVehicle, (MAV_CMD)item2->command())->rawName();;
scanIndex = 0;
QCOMPARE(_cameraSection->scanForSection(&visualItems, scanIndex), true);
_validateItemScan(cameraItem);
_resetSection();
visualItems.clearAndDeleteContents();
}
}
}
......@@ -37,10 +37,12 @@ private slots:
void _testScanForStopImageSection(void);
void _testScanForCameraModeSection(void);
void _testScanForTakePhotoSection(void);
void _testScanForFullSection(void);
void _testScanForMultipleItems(void);
private:
void _createSpy(CameraSection* cameraSection, MultiSignalSpy** cameraSpy);
void _validateItemScan(SimpleMissionItem* validItem);
void _resetSection(void);
enum {
specifyGimbalChangedIndex = 0,
......
Supports Markdown
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