Browse Source

Add support for TakePhoto

Move set camera photo mode to be first item
QGC4.4
DonLakeFlyer 8 years ago
parent
commit
a9ba93f055
  1. 4
      src/MissionManager/CameraSection.FactMetaData.json
  2. 56
      src/MissionManager/CameraSection.cc
  3. 14
      src/MissionManager/CameraSection.h
  4. 175
      src/MissionManager/CameraSectionTest.cc
  5. 2
      src/MissionManager/CameraSectionTest.h

4
src/MissionManager/CameraSection.FactMetaData.json

@ -3,8 +3,8 @@ @@ -3,8 +3,8 @@
"name": "CameraAction",
"shortDescription": "Specify whether the camera should take photos or video",
"type": "uint32",
"enumStrings": "Continue current action,Take photos (time),Take photos (distance),Stop taking photos,Start recording video,Stop recording video",
"enumValues": "0,1,2,3,4,5",
"enumStrings": "Continue current action,Take photo,Take photos (time),Take photos (distance),Stop taking photos,Start recording video,Stop recording video",
"enumValues": "0,6,1,2,3,4,5",
"defaultValue": 0
},
{

56
src/MissionManager/CameraSection.cc

@ -115,6 +115,19 @@ void CameraSection::appendSectionItems(QList<MissionItem*>& items, QObject* miss @@ -115,6 +115,19 @@ void CameraSection::appendSectionItems(QList<MissionItem*>& items, QObject* miss
{
// IMPORTANT NOTE: If anything changes here you must also change CameraSection::scanForSection
if (_specifyCameraMode) {
MissionItem* item = new MissionItem(nextSequenceNumber++,
MAV_CMD_SET_CAMERA_MODE,
MAV_FRAME_MISSION,
0, // camera id, all cameras
_cameraModeFact.rawValue().toDouble(),
NAN, NAN, NAN, NAN, NAN, // param 3-7 unused
true, // autoContinue
false, // isCurrentItem
missionItemParent);
items.append(item);
}
if (_specifyGimbal) {
MissionItem* item = new MissionItem(nextSequenceNumber++,
MAV_CMD_DO_MOUNT_CONTROL,
@ -203,24 +216,26 @@ void CameraSection::appendSectionItems(QList<MissionItem*>& items, QObject* miss @@ -203,24 +216,26 @@ void CameraSection::appendSectionItems(QList<MissionItem*>& items, QObject* miss
false, // isCurrentItem
missionItemParent);
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);
break;
}
if (item) {
items.append(item);
}
}
if (_specifyCameraMode) {
MissionItem* item = new MissionItem(nextSequenceNumber++,
MAV_CMD_SET_CAMERA_MODE,
MAV_FRAME_MISSION,
0, // camera id, all cameras
_cameraModeFact.rawValue().toDouble(),
NAN, NAN, NAN, NAN, NAN, // param 3-7 unused
true, // autoContinue
false, // isCurrentItem
missionItemParent);
items.append(item);
}
}
bool CameraSection::scanForSection(QmlObjectListModel* visualItems, int scanIndex)
@ -264,10 +279,19 @@ bool CameraSection::scanForSection(QmlObjectListModel* visualItems, int scanInde @@ -264,10 +279,19 @@ bool CameraSection::scanForSection(QmlObjectListModel* visualItems, int scanInde
break;
case MAV_CMD_IMAGE_START_CAPTURE:
if (!foundCameraAction && missionItem.param1() == 0 && missionItem.param2() >= 1 && missionItem.param3() == 0 && missionItem.param4() == -1 && missionItem.param5() == -1 && missionItem.param6() == 0 && missionItem.param7() == 0) {
// 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;
cameraAction()->setRawValue(TakePhotosIntervalTime);
cameraPhotoIntervalTime()->setRawValue(missionItem.param2());
if (missionItem.param2() == 0) {
cameraAction()->setRawValue(TakePhoto);
} else {
cameraAction()->setRawValue(TakePhotosIntervalTime);
cameraPhotoIntervalTime()->setRawValue(missionItem.param2());
}
visualItems->removeAt(scanIndex)->deleteLater();
} else {
stopLooking = true;

14
src/MissionManager/CameraSection.h

@ -21,17 +21,25 @@ class CameraSection : public Section @@ -21,17 +21,25 @@ class CameraSection : public Section
public:
CameraSection(Vehicle* vehicle, QObject* parent = NULL);
// These nume values must match the json meta data
// These enum values must match the json meta data
enum CameraAction {
CameraActionNone,
TakePhotosIntervalTime,
TakePhotoIntervalDistance,
StopTakingPhotos,
TakeVideo,
StopTakingVideo
};
StopTakingVideo,
TakePhoto
};
Q_ENUMS(CameraAction)
enum CameraMode {
CameraModePhoto,
CameraModeVideo
};
Q_ENUMS(CameraMode)
Q_PROPERTY(bool specifyGimbal READ specifyGimbal WRITE setSpecifyGimbal NOTIFY specifyGimbalChanged)
Q_PROPERTY(Fact* gimbalPitch READ gimbalPitch CONSTANT)
Q_PROPERTY(Fact* gimbalYaw READ gimbalYaw CONSTANT)

175
src/MissionManager/CameraSectionTest.cc

@ -60,25 +60,38 @@ void CameraSectionTest::init(void) @@ -60,25 +60,38 @@ void CameraSectionTest::init(void)
MissionItem(1, MAV_CMD_IMAGE_STOP_CAPTURE, MAV_FRAME_MISSION, 0, 0, 0, 0, 0, 0, 0, true, false),
this);
_validCameraPhotoModeItem = new SimpleMissionItem(_offlineVehicle,
MissionItem(0, // sequence number
MAV_CMD_SET_CAMERA_MODE,
MAV_FRAME_MISSION,
0, // camera id = 0, all cameras
0, // photo mode
NAN, NAN, NAN, NAN, NAN, // param 3-7 unused
true, // autocontinue
false), // isCurrentItem
this);
MissionItem(0, // sequence number
MAV_CMD_SET_CAMERA_MODE,
MAV_FRAME_MISSION,
0, // camera id = 0, all cameras
CameraSection::CameraModePhoto,
NAN, NAN, NAN, NAN, NAN, // param 3-7 unused
true, // autocontinue
false), // isCurrentItem
this);
_validCameraVideoModeItem = new SimpleMissionItem(_offlineVehicle,
MissionItem(0, // sequence number
MAV_CMD_SET_CAMERA_MODE,
MAV_FRAME_MISSION,
0, // camera id = 0, all cameras
1, // video mode
NAN, NAN, NAN, NAN, NAN, // param 3-7 unused
true, // autocontinue
false), // isCurrentItem
this);
MissionItem(0, // sequence number
MAV_CMD_SET_CAMERA_MODE,
MAV_FRAME_MISSION,
0, // camera id = 0, all cameras
CameraSection::CameraModeVideo,
NAN, NAN, NAN, NAN, NAN, // param 3-7 unused
true, // autocontinue
false), // isCurrentItem
this);
_validTakePhotoItem = new SimpleMissionItem(_offlineVehicle,
MissionItem(0,
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
this);
}
void CameraSectionTest::cleanup(void)
@ -92,6 +105,7 @@ void CameraSectionTest::cleanup(void) @@ -92,6 +105,7 @@ void CameraSectionTest::cleanup(void)
delete _validStopVideoItem;
delete _validStopDistanceItem;
delete _validStopTimeItem;
delete _validTakePhotoItem;
SectionTest::cleanup();
}
@ -353,7 +367,7 @@ void CameraSectionTest::_testItemCount(void) @@ -353,7 +367,7 @@ void CameraSectionTest::_testItemCount(void)
// Check camera actions
QList<int> rgCameraActions;
rgCameraActions << CameraSection::TakePhotosIntervalTime << CameraSection::TakePhotoIntervalDistance << CameraSection::StopTakingPhotos << CameraSection::TakeVideo << CameraSection::StopTakingVideo;
rgCameraActions << CameraSection::TakePhotosIntervalTime << CameraSection::TakePhotoIntervalDistance << CameraSection::StopTakingPhotos << CameraSection::TakeVideo << CameraSection::StopTakingVideo << CameraSection::TakePhoto;
foreach(int cameraAction, rgCameraActions) {
qDebug() << "camera action" << cameraAction;
@ -420,7 +434,7 @@ void CameraSectionTest::_testAppendSectionItems(void) @@ -420,7 +434,7 @@ void CameraSectionTest::_testAppendSectionItems(void)
// Test specifyCameraMode
_cameraSection->setSpecifyCameraMode(true);
_cameraSection->cameraMode()->setRawValue(0);
_cameraSection->cameraMode()->setRawValue(CameraSection::CameraModePhoto);
_cameraSection->appendSectionItems(rgMissionItems, this, seqNum);
QCOMPARE(rgMissionItems.count(), 1);
QCOMPARE(seqNum, 1);
@ -430,7 +444,7 @@ void CameraSectionTest::_testAppendSectionItems(void) @@ -430,7 +444,7 @@ void CameraSectionTest::_testAppendSectionItems(void)
seqNum = 0;
_cameraSection->setSpecifyCameraMode(true);
_cameraSection->cameraMode()->setRawValue(1);
_cameraSection->cameraMode()->setRawValue(CameraSection::CameraModeVideo);
_cameraSection->appendSectionItems(rgMissionItems, this, seqNum);
QCOMPARE(rgMissionItems.count(), 1);
QCOMPARE(seqNum, 1);
@ -441,6 +455,15 @@ void CameraSectionTest::_testAppendSectionItems(void) @@ -441,6 +455,15 @@ void CameraSectionTest::_testAppendSectionItems(void)
// Test camera actions
_cameraSection->cameraAction()->setRawValue(CameraSection::TakePhoto);
_cameraSection->appendSectionItems(rgMissionItems, this, seqNum);
QCOMPARE(rgMissionItems.count(), 1);
QCOMPARE(seqNum, 1);
_missionItemsEqual(*rgMissionItems[0], _validTakePhotoItem->missionItem());
_cameraSection->cameraAction()->setRawValue(CameraSection::CameraActionNone);
rgMissionItems.clear();
seqNum = 0;
_cameraSection->cameraAction()->setRawValue(CameraSection::TakePhotosIntervalTime);
_cameraSection->cameraPhotoIntervalTime()->setRawValue(_validTimeItem->missionItem().param2());
_cameraSection->appendSectionItems(rgMissionItems, this, seqNum);
@ -489,17 +512,21 @@ void CameraSectionTest::_testAppendSectionItems(void) @@ -489,17 +512,21 @@ void CameraSectionTest::_testAppendSectionItems(void)
rgMissionItems.clear();
seqNum = 0;
// Test both
// Test multiple
_cameraSection->setSpecifyGimbal(true);
_cameraSection->gimbalPitch()->setRawValue(_validGimbalItem->missionItem().param1());
_cameraSection->gimbalYaw()->setRawValue(_validGimbalItem->missionItem().param3());
_cameraSection->cameraAction()->setRawValue(CameraSection::TakePhotosIntervalTime);
_cameraSection->cameraPhotoIntervalTime()->setRawValue(_validTimeItem->missionItem().param2());
_cameraSection->setSpecifyCameraMode(true);
_cameraSection->cameraMode()->setRawValue(CameraSection::CameraModePhoto);
_cameraSection->appendSectionItems(rgMissionItems, this, seqNum);
QCOMPARE(rgMissionItems.count(), 2);
QCOMPARE(seqNum, 2);
_missionItemsEqual(*rgMissionItems[0], _validGimbalItem->missionItem());
_missionItemsEqual(*rgMissionItems[1], _validTimeItem->missionItem());
QCOMPARE(rgMissionItems.count(), 3);
QCOMPARE(seqNum, 3);
_missionItemsEqual(*rgMissionItems[0], _validCameraPhotoModeItem->missionItem()); // Camera mode change must always be first
_missionItemsEqual(*rgMissionItems[1], _validGimbalItem->missionItem());
_missionItemsEqual(*rgMissionItems[2], _validTimeItem->missionItem());
_cameraSection->setSpecifyGimbal(false);
rgMissionItems.clear();
seqNum = 0;
@ -530,7 +557,7 @@ void CameraSectionTest::_testScanForGimbalSection(void) @@ -530,7 +557,7 @@ void CameraSectionTest::_testScanForGimbalSection(void)
visualItems.clear();
scanIndex = 0;
#if 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.
@ -539,7 +566,7 @@ void CameraSectionTest::_testScanForGimbalSection(void) @@ -539,7 +566,7 @@ void CameraSectionTest::_testScanForGimbalSection(void)
Mission Param #5 WIP: latitude in degrees * 1E7, set if appropriate mount mode.
Mission Param #6 WIP: longitude in degrees * 1E7, set if appropriate mount mode.
Mission Param #7 MAV_MOUNT_MODE enum value
#endif
*/
// Gimbal command but incorrect settings
@ -625,13 +652,13 @@ void CameraSectionTest::_testScanForCameraModeSection(void) @@ -625,13 +652,13 @@ void CameraSectionTest::_testScanForCameraModeSection(void)
visualItems.clear();
scanIndex = 0;
#if 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)
Mission Param #3 Audio recording enabled (0: off 1: on)
Mission Param #4 Reserved (all remaining params)
#endif
*/
// Mode command but incorrect settings
@ -654,14 +681,14 @@ void CameraSectionTest::_testScanForPhotoIntervalTimeSection(void) @@ -654,14 +681,14 @@ void CameraSectionTest::_testScanForPhotoIntervalTimeSection(void)
_commonScanTest(_cameraSection);
#if 0
/*
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)
Mission Param #3 Number of images to capture total - 0 for unlimited capture
Mission Param #4 Resolution horizontal in pixels (set to -1 for highest resolution possible)
Mission Param #5 Resolution vertical in pixels (set to -1 for highest resolution possible)
#endif
*/
SimpleMissionItem* newValidTimeItem = new SimpleMissionItem(_offlineVehicle, this);
newValidTimeItem->missionItem() = _validTimeItem->missionItem();
@ -725,7 +752,7 @@ void CameraSectionTest::_testScanForPhotoIntervalDistanceSection(void) @@ -725,7 +752,7 @@ void CameraSectionTest::_testScanForPhotoIntervalDistanceSection(void)
_commonScanTest(_cameraSection);
#if 0
/*
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
@ -734,7 +761,7 @@ void CameraSectionTest::_testScanForPhotoIntervalDistanceSection(void) @@ -734,7 +761,7 @@ void CameraSectionTest::_testScanForPhotoIntervalDistanceSection(void)
Mission Param #5 Empty
Mission Param #6 Empty
Mission Param #7 Empty
#endif
*/
SimpleMissionItem* newValidDistanceItem = new SimpleMissionItem(_offlineVehicle, this);
newValidDistanceItem->missionItem() = _validDistanceItem->missionItem();
@ -815,7 +842,7 @@ void CameraSectionTest::_testScanForStartVideoSection(void) @@ -815,7 +842,7 @@ void CameraSectionTest::_testScanForStartVideoSection(void)
_commonScanTest(_cameraSection);
#if 0
/*
MAV_CMD_VIDEO_STOP_CAPTURE Stop the current video capture (recording)
Mission Param #1 WIP: Camera ID
Mission Param #2 Reserved
@ -823,7 +850,7 @@ void CameraSectionTest::_testScanForStartVideoSection(void) @@ -823,7 +850,7 @@ void CameraSectionTest::_testScanForStartVideoSection(void)
Mission Param #4 WIP: Resolution horizontal in pixels
Mission Param #5 WIP: Resolution horizontal in pixels
Mission Param #6 WIP: Frequency CAMERA_CAPTURE_STATUS messages should be sent while recording (0 for no messages, otherwise time in Hz)
#endif
*/
SimpleMissionItem* newValidStartVideoItem = new SimpleMissionItem(_offlineVehicle, this);
newValidStartVideoItem->missionItem() = _validStartVideoItem->missionItem();
@ -903,10 +930,10 @@ void CameraSectionTest::_testScanForStopVideoSection(void) @@ -903,10 +930,10 @@ void CameraSectionTest::_testScanForStopVideoSection(void)
_commonScanTest(_cameraSection);
#if 0
/*
MAV_CMD_VIDEO_STOP_CAPTURE Stop the current video capture (recording)
Mission Param #1 WIP: Camera ID
#endif
*/
SimpleMissionItem* newValidStopVideoItem = new SimpleMissionItem(_offlineVehicle, this);
newValidStopVideoItem->missionItem() = _validStopVideoItem->missionItem();
@ -1012,6 +1039,76 @@ void CameraSectionTest::_testScanForStopImageSection(void) @@ -1012,6 +1039,76 @@ void CameraSectionTest::_testScanForStopImageSection(void)
visualItems.clear();
}
void CameraSectionTest::_testScanForTakePhotoSection(void)
{
QCOMPARE(_cameraSection->available(), true);
int scanIndex = 0;
QmlObjectListModel visualItems;
_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)
Mission Param #3 Number of images to capture total - 0 for unlimited capture
Mission Param #4 Resolution horizontal in pixels (set to -1 for highest resolution possible)
Mission Param #5 Resolution vertical in pixels (set to -1 for highest resolution possible)
*/
SimpleMissionItem* newValidTakePhotoItem = new SimpleMissionItem(_offlineVehicle, this);
newValidTakePhotoItem->missionItem() = _validTakePhotoItem->missionItem();
visualItems.append(newValidTakePhotoItem);
QCOMPARE(_cameraSection->scanForSection(&visualItems, scanIndex), true);
QCOMPARE(visualItems.count(), 0);
QCOMPARE(_cameraSection->settingsSpecified(), true);
QCOMPARE(_cameraSection->cameraAction()->rawValue().toInt(), (int)CameraSection::TakePhoto);
visualItems.clear();
scanIndex = 0;
// Take Photo command but incorrect settings
SimpleMissionItem invalidSimpleItem(_offlineVehicle, _validTimeItem->missionItem());
invalidSimpleItem.missionItem().setParam3(10); // must be 1 for single photo
visualItems.append(&invalidSimpleItem);
QCOMPARE(_cameraSection->scanForSection(&visualItems, scanIndex), false);
QCOMPARE(visualItems.count(), 1);
visualItems.clear();
invalidSimpleItem.missionItem() = _validTimeItem->missionItem();
invalidSimpleItem.missionItem().setParam4(10); // must be -1 for highest res
visualItems.append(&invalidSimpleItem);
QCOMPARE(_cameraSection->scanForSection(&visualItems, scanIndex), false);
QCOMPARE(visualItems.count(), 1);
QCOMPARE(_cameraSection->settingsSpecified(), false);
visualItems.clear();
invalidSimpleItem.missionItem() = _validTimeItem->missionItem();
invalidSimpleItem.missionItem().setParam5(10); // must be -1 for highest res
visualItems.append(&invalidSimpleItem);
QCOMPARE(_cameraSection->scanForSection(&visualItems, scanIndex), false);
QCOMPARE(visualItems.count(), 1);
QCOMPARE(_cameraSection->settingsSpecified(), false);
visualItems.clear();
invalidSimpleItem.missionItem() = _validTimeItem->missionItem();
invalidSimpleItem.missionItem().setParam6(10); // must be 0
visualItems.append(&invalidSimpleItem);
QCOMPARE(_cameraSection->scanForSection(&visualItems, scanIndex), false);
QCOMPARE(visualItems.count(), 1);
QCOMPARE(_cameraSection->settingsSpecified(), false);
visualItems.clear();
invalidSimpleItem.missionItem() = _validTimeItem->missionItem();
invalidSimpleItem.missionItem().setParam7(10); // must be 0
visualItems.append(&invalidSimpleItem);
QCOMPARE(_cameraSection->scanForSection(&visualItems, scanIndex), false);
QCOMPARE(visualItems.count(), 1);
QCOMPARE(_cameraSection->settingsSpecified(), false);
visualItems.clear();
}
void CameraSectionTest::_testScanForFullSection(void)
{
QCOMPARE(_cameraSection->available(), true);
@ -1032,8 +1129,8 @@ void CameraSectionTest::_testScanForFullSection(void) @@ -1032,8 +1129,8 @@ void CameraSectionTest::_testScanForFullSection(void)
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());
QCOMPARE(_cameraSection->cameraPhotoIntervalDistance()->rawValue().toInt(), (int)_validDistanceItem->missionItem().param1());
visualItems.clear();
}

2
src/MissionManager/CameraSectionTest.h

@ -36,6 +36,7 @@ private slots: @@ -36,6 +36,7 @@ private slots:
void _testScanForStopVideoSection(void);
void _testScanForStopImageSection(void);
void _testScanForCameraModeSection(void);
void _testScanForTakePhotoSection(void);
void _testScanForFullSection(void);
private:
@ -69,4 +70,5 @@ private: @@ -69,4 +70,5 @@ private:
SimpleMissionItem* _validStopTimeItem;
SimpleMissionItem* _validCameraPhotoModeItem;
SimpleMissionItem* _validCameraVideoModeItem;
SimpleMissionItem* _validTakePhotoItem;
};

Loading…
Cancel
Save