Commit e1fb25c6 authored by DonLakeFlyer's avatar DonLakeFlyer

CAMERA_MODE_IMAGE_SURVEY support

parent f10ac35f
...@@ -49,8 +49,8 @@ ...@@ -49,8 +49,8 @@
"name": "CameraMode", "name": "CameraMode",
"shortDescription": "Specify whether the camera should switch to photo or video mode", "shortDescription": "Specify whether the camera should switch to photo or video mode",
"type": "uint32", "type": "uint32",
"enumStrings": "Take photos,Record video", "enumStrings": "Take photos,Record video,Survey photo mode",
"enumValues": "0,1", "enumValues": "0,1,2",
"defaultValue": 0 "defaultValue": 0
} }
] ]
...@@ -392,7 +392,7 @@ bool CameraSection::_scanSetCameraMode(QmlObjectListModel* visualItems, int scan ...@@ -392,7 +392,7 @@ bool CameraSection::_scanSetCameraMode(QmlObjectListModel* visualItems, int scan
MissionItem& missionItem = item->missionItem(); MissionItem& missionItem = item->missionItem();
if ((MAV_CMD)item->command() == MAV_CMD_SET_CAMERA_MODE) { 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 // We specifically don't test param 5/6/7 since we don't have NaN persistence for those fields
if (missionItem.param1() == 0 && (missionItem.param2() == 0 || missionItem.param2() == 1) && qIsNaN(missionItem.param3())) { if (missionItem.param1() == 0 && (missionItem.param2() == CAMERA_MODE_IMAGE || missionItem.param2() == CAMERA_MODE_VIDEO || missionItem.param2() == CAMERA_MODE_IMAGE_SURVEY) && qIsNaN(missionItem.param3())) {
setSpecifyCameraMode(true); setSpecifyCameraMode(true);
cameraMode()->setRawValue(missionItem.param2()); cameraMode()->setRawValue(missionItem.param2());
visualItems->removeAt(scanIndex)->deleteLater(); visualItems->removeAt(scanIndex)->deleteLater();
......
...@@ -34,12 +34,6 @@ public: ...@@ -34,12 +34,6 @@ public:
}; };
Q_ENUMS(CameraAction) Q_ENUMS(CameraAction)
enum CameraMode {
CameraModePhoto,
CameraModeVideo
};
Q_ENUMS(CameraMode)
Q_PROPERTY(bool specifyGimbal READ specifyGimbal WRITE setSpecifyGimbal NOTIFY specifyGimbalChanged) Q_PROPERTY(bool specifyGimbal READ specifyGimbal WRITE setSpecifyGimbal NOTIFY specifyGimbalChanged)
Q_PROPERTY(Fact* gimbalPitch READ gimbalPitch CONSTANT) Q_PROPERTY(Fact* gimbalPitch READ gimbalPitch CONSTANT)
Q_PROPERTY(Fact* gimbalYaw READ gimbalYaw CONSTANT) Q_PROPERTY(Fact* gimbalYaw READ gimbalYaw CONSTANT)
......
...@@ -13,18 +13,19 @@ ...@@ -13,18 +13,19 @@
#include "MissionCommandUIInfo.h" #include "MissionCommandUIInfo.h"
CameraSectionTest::CameraSectionTest(void) CameraSectionTest::CameraSectionTest(void)
: _spyCamera(NULL) : _spyCamera (NULL)
, _spySection(NULL) , _spySection (NULL)
, _cameraSection(NULL) , _cameraSection (NULL)
, _validGimbalItem(NULL) , _validGimbalItem (NULL)
, _validDistanceItem(NULL) , _validDistanceItem (NULL)
, _validTimeItem(NULL) , _validTimeItem (NULL)
, _validStartVideoItem(NULL) , _validStartVideoItem (NULL)
, _validStopVideoItem(NULL) , _validStopVideoItem (NULL)
, _validStopDistanceItem(NULL) , _validStopDistanceItem (NULL)
, _validStopTimeItem(NULL) , _validStopTimeItem (NULL)
, _validCameraPhotoModeItem(NULL) , _validCameraPhotoModeItem (NULL)
, _validCameraVideoModeItem(NULL) , _validCameraVideoModeItem (NULL)
, _validCameraSurveyPhotoModeItem (NULL)
{ {
} }
...@@ -83,7 +84,7 @@ void CameraSectionTest::init(void) ...@@ -83,7 +84,7 @@ void CameraSectionTest::init(void)
MAV_CMD_SET_CAMERA_MODE, MAV_CMD_SET_CAMERA_MODE,
MAV_FRAME_MISSION, MAV_FRAME_MISSION,
0, // Reserved (Set to 0) 0, // Reserved (Set to 0)
CameraSection::CameraModePhoto, CAMERA_MODE_IMAGE,
NAN, NAN, NAN, NAN, NAN, // param 3-7 reserved NAN, NAN, NAN, NAN, NAN, // param 3-7 reserved
true, // autocontinue true, // autocontinue
false), // isCurrentItem false), // isCurrentItem
...@@ -93,11 +94,21 @@ void CameraSectionTest::init(void) ...@@ -93,11 +94,21 @@ void CameraSectionTest::init(void)
MAV_CMD_SET_CAMERA_MODE, MAV_CMD_SET_CAMERA_MODE,
MAV_FRAME_MISSION, MAV_FRAME_MISSION,
0, // Reserved (Set to 0) 0, // Reserved (Set to 0)
CameraSection::CameraModeVideo, CAMERA_MODE_VIDEO,
NAN, NAN, NAN, NAN, NAN, // param 3-7 reserved NAN, NAN, NAN, NAN, NAN, // param 3-7 reserved
true, // autocontinue true, // autocontinue
false), // isCurrentItem false), // isCurrentItem
this); this);
_validCameraSurveyPhotoModeItem = new SimpleMissionItem(_offlineVehicle,
MissionItem(0, // sequence number
MAV_CMD_SET_CAMERA_MODE,
MAV_FRAME_MISSION,
0, // Reserved (Set to 0)
CAMERA_MODE_IMAGE_SURVEY,
NAN, NAN, NAN, NAN, NAN, // param 3-7 reserved
true, // autocontinue
false), // isCurrentItem
this);
_validTakePhotoItem = new SimpleMissionItem(_offlineVehicle, _validTakePhotoItem = new SimpleMissionItem(_offlineVehicle,
MissionItem(0, MissionItem(0,
MAV_CMD_IMAGE_START_CAPTURE, MAV_CMD_IMAGE_START_CAPTURE,
...@@ -125,6 +136,7 @@ void CameraSectionTest::cleanup(void) ...@@ -125,6 +136,7 @@ void CameraSectionTest::cleanup(void)
delete _validTakePhotoItem; delete _validTakePhotoItem;
delete _validCameraPhotoModeItem; delete _validCameraPhotoModeItem;
delete _validCameraVideoModeItem; delete _validCameraVideoModeItem;
delete _validCameraSurveyPhotoModeItem;
SectionTest::cleanup(); SectionTest::cleanup();
} }
...@@ -453,7 +465,7 @@ void CameraSectionTest::_testAppendSectionItems(void) ...@@ -453,7 +465,7 @@ void CameraSectionTest::_testAppendSectionItems(void)
// Test specifyCameraMode // Test specifyCameraMode
_cameraSection->setSpecifyCameraMode(true); _cameraSection->setSpecifyCameraMode(true);
_cameraSection->cameraMode()->setRawValue(CameraSection::CameraModePhoto); _cameraSection->cameraMode()->setRawValue(CAMERA_MODE_IMAGE);
_cameraSection->appendSectionItems(rgMissionItems, this, seqNum); _cameraSection->appendSectionItems(rgMissionItems, this, seqNum);
QCOMPARE(rgMissionItems.count(), 1); QCOMPARE(rgMissionItems.count(), 1);
QCOMPARE(seqNum, 1); QCOMPARE(seqNum, 1);
...@@ -463,7 +475,7 @@ void CameraSectionTest::_testAppendSectionItems(void) ...@@ -463,7 +475,7 @@ void CameraSectionTest::_testAppendSectionItems(void)
seqNum = 0; seqNum = 0;
_cameraSection->setSpecifyCameraMode(true); _cameraSection->setSpecifyCameraMode(true);
_cameraSection->cameraMode()->setRawValue(CameraSection::CameraModeVideo); _cameraSection->cameraMode()->setRawValue(CAMERA_MODE_VIDEO);
_cameraSection->appendSectionItems(rgMissionItems, this, seqNum); _cameraSection->appendSectionItems(rgMissionItems, this, seqNum);
QCOMPARE(rgMissionItems.count(), 1); QCOMPARE(rgMissionItems.count(), 1);
QCOMPARE(seqNum, 1); QCOMPARE(seqNum, 1);
...@@ -472,6 +484,16 @@ void CameraSectionTest::_testAppendSectionItems(void) ...@@ -472,6 +484,16 @@ void CameraSectionTest::_testAppendSectionItems(void)
rgMissionItems.clear(); rgMissionItems.clear();
seqNum = 0; seqNum = 0;
_cameraSection->setSpecifyCameraMode(true);
_cameraSection->cameraMode()->setRawValue(CAMERA_MODE_IMAGE_SURVEY);
_cameraSection->appendSectionItems(rgMissionItems, this, seqNum);
QCOMPARE(rgMissionItems.count(), 1);
QCOMPARE(seqNum, 1);
_missionItemsEqual(*rgMissionItems[0], _validCameraSurveyPhotoModeItem->missionItem());
_cameraSection->setSpecifyCameraMode(false);
rgMissionItems.clear();
seqNum = 0;
// Test camera actions // Test camera actions
_cameraSection->cameraAction()->setRawValue(CameraSection::TakePhoto); _cameraSection->cameraAction()->setRawValue(CameraSection::TakePhoto);
...@@ -539,7 +561,7 @@ void CameraSectionTest::_testAppendSectionItems(void) ...@@ -539,7 +561,7 @@ void CameraSectionTest::_testAppendSectionItems(void)
_cameraSection->cameraAction()->setRawValue(CameraSection::TakePhotosIntervalTime); _cameraSection->cameraAction()->setRawValue(CameraSection::TakePhotosIntervalTime);
_cameraSection->cameraPhotoIntervalTime()->setRawValue(_validTimeItem->missionItem().param2()); _cameraSection->cameraPhotoIntervalTime()->setRawValue(_validTimeItem->missionItem().param2());
_cameraSection->setSpecifyCameraMode(true); _cameraSection->setSpecifyCameraMode(true);
_cameraSection->cameraMode()->setRawValue(CameraSection::CameraModePhoto); _cameraSection->cameraMode()->setRawValue(CAMERA_MODE_IMAGE);
_cameraSection->appendSectionItems(rgMissionItems, this, seqNum); _cameraSection->appendSectionItems(rgMissionItems, this, seqNum);
QCOMPARE(rgMissionItems.count(), 3); QCOMPARE(rgMissionItems.count(), 3);
QCOMPARE(seqNum, 3); QCOMPARE(seqNum, 3);
...@@ -995,7 +1017,7 @@ void CameraSectionTest::_resetSection(void) ...@@ -995,7 +1017,7 @@ void CameraSectionTest::_resetSection(void)
_cameraSection->cameraPhotoIntervalTime()->setRawValue(0); _cameraSection->cameraPhotoIntervalTime()->setRawValue(0);
_cameraSection->cameraPhotoIntervalDistance()->setRawValue(0); _cameraSection->cameraPhotoIntervalDistance()->setRawValue(0);
_cameraSection->cameraAction()->setRawValue(CameraSection::CameraActionNone); _cameraSection->cameraAction()->setRawValue(CameraSection::CameraActionNone);
_cameraSection->cameraMode()->setRawValue(CameraSection::CameraModePhoto); _cameraSection->cameraMode()->setRawValue(CAMERA_MODE_IMAGE);
_cameraSection->setSpecifyCameraMode(false); _cameraSection->setSpecifyCameraMode(false);
} }
......
...@@ -72,5 +72,6 @@ private: ...@@ -72,5 +72,6 @@ private:
SimpleMissionItem* _validStopTimeItem; SimpleMissionItem* _validStopTimeItem;
SimpleMissionItem* _validCameraPhotoModeItem; SimpleMissionItem* _validCameraPhotoModeItem;
SimpleMissionItem* _validCameraVideoModeItem; SimpleMissionItem* _validCameraVideoModeItem;
SimpleMissionItem* _validCameraSurveyPhotoModeItem;
SimpleMissionItem* _validTakePhotoItem; SimpleMissionItem* _validTakePhotoItem;
}; };
...@@ -971,17 +971,12 @@ ...@@ -971,17 +971,12 @@
"id": 530, "id": 530,
"rawName": "MAV_CMD_SET_CAMERA_MODE", "rawName": "MAV_CMD_SET_CAMERA_MODE",
"friendlyName": "Set camera modes" , "friendlyName": "Set camera modes" ,
"description": "Set camera photo, video, audio modes.", "description": "Set camera photo, video modes.",
"category": "Camera", "category": "Camera",
"param1": {
"label": "Reserved",
"default": 0,
"decimalPlaces": 0
},
"param2": { "param2": {
"label": "Mode", "label": "Mode",
"enumStrings": "Take photos,Record video", "enumStrings": "Take photos,Record video,Survey photo mode",
"enumValues": "0,1", "enumValues": "0,1,2",
"default": 0 "default": 0
} }
}, },
......
...@@ -327,7 +327,7 @@ int MissionController::insertComplexMissionItem(QString itemName, QGeoCoordinate ...@@ -327,7 +327,7 @@ int MissionController::insertComplexMissionItem(QString itemName, QGeoCoordinate
// Set camera to photo mode (leave alone if user already specified) // Set camera to photo mode (leave alone if user already specified)
if (cameraSection->cameraModeSupported() && !cameraSection->specifyCameraMode()) { if (cameraSection->cameraModeSupported() && !cameraSection->specifyCameraMode()) {
cameraSection->setSpecifyCameraMode(true); cameraSection->setSpecifyCameraMode(true);
cameraSection->cameraMode()->setRawValue(0); cameraSection->cameraMode()->setRawValue(CAMERA_MODE_IMAGE_SURVEY);
} }
// Point gimbal straight down // Point gimbal straight down
if (_controllerVehicle->firmwarePlugin()->hasGimbal(_controllerVehicle, rollSupported, pitchSupported, yawSupported) && pitchSupported) { if (_controllerVehicle->firmwarePlugin()->hasGimbal(_controllerVehicle, rollSupported, pitchSupported, yawSupported) && pitchSupported) {
......
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