Commit 80f39ce1 authored by DonLakeFlyer's avatar DonLakeFlyer

Add support for stop camera actions

parent 98b317d3
...@@ -3,8 +3,8 @@ ...@@ -3,8 +3,8 @@
"name": "CameraAction", "name": "CameraAction",
"shortDescription": "Specify whether the camera should take photos or video", "shortDescription": "Specify whether the camera should take photos or video",
"type": "uint32", "type": "uint32",
"enumStrings": "Continue current action,Take photos (time),Take photos (distance),Take video", "enumStrings": "Continue current action,Take photos (time),Take photos (distance),Stop taking photos,Start recording video,Stop recording video",
"enumValues": "0,1,2,3", "enumValues": "0,1,2,3,4,5",
"defaultValue": 0 "defaultValue": 0
}, },
{ {
......
...@@ -150,6 +150,37 @@ void CameraSection::appendMissionItems(QList<MissionItem*>& items, QObject* miss ...@@ -150,6 +150,37 @@ void CameraSection::appendMissionItems(QList<MissionItem*>& items, QObject* miss
false, // isCurrentItem false, // isCurrentItem
missionItemParent); missionItemParent);
break; break;
case StopTakingVideo:
item = new MissionItem(nextSequenceNumber++,
MAV_CMD_VIDEO_STOP_CAPTURE,
MAV_FRAME_MISSION,
0, // Camera ID
0, 0, 0, 0, 0, 0, // param 2-7 not used
true, // autoContinue
false, // isCurrentItem
missionItemParent);
break;
case StopTakingPhotos:
item = new MissionItem(nextSequenceNumber++,
MAV_CMD_DO_SET_CAM_TRIGG_DIST,
MAV_FRAME_MISSION,
0, // Trigger distance = 0 means stop
0, 0, 0, 0, 0, 0, // param 2-7 not used
true, // autoContinue
false, // isCurrentItem
missionItemParent);
items.append(item);
item = new MissionItem(nextSequenceNumber++,
MAV_CMD_IMAGE_STOP_CAPTURE,
MAV_FRAME_MISSION,
0, // camera id
0, 0, 0, 0, 0, 0, // param 2-7 not used
true, // autoContinue
false, // isCurrentItem
missionItemParent);
break;
} }
if (item) { if (item) {
items.append(item); items.append(item);
...@@ -204,14 +235,32 @@ bool CameraSection::scanForCameraSection(QmlObjectListModel* visualItems, int sc ...@@ -204,14 +235,32 @@ bool CameraSection::scanForCameraSection(QmlObjectListModel* visualItems, int sc
break; break;
case MAV_CMD_DO_SET_CAM_TRIGG_DIST: 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) { 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 a single distance trigger where the user specified 0
// We need to look at the next item to check for the stop taking photos pari
if (missionItem.param1() == 0 && scanIndex < visualItems->count() - 1) {
SimpleMissionItem* nextItem = visualItems->value<SimpleMissionItem*>(scanIndex + 1);
if (nextItem) {
missionItem = nextItem->missionItem();
if ((MAV_CMD)item->command() == MAV_CMD_IMAGE_STOP_CAPTURE && missionItem.param1() == 0 && missionItem.param2() == 0 && missionItem.param3() == 0 && missionItem.param4() == 0 && missionItem.param5() == 0 && missionItem.param6() == 0 && missionItem.param7() == 0) {
foundCameraAction = true;
cameraAction()->setRawValue(StopTakingPhotos);
visualItems->removeAt(scanIndex)->deleteLater();
visualItems->removeAt(scanIndex)->deleteLater();
break;
}
}
}
// We didn't find a stop taking photos pair, so this is a regular trigger distance item
foundCameraAction = true; foundCameraAction = true;
cameraAction()->setRawValue(TakePhotoIntervalDistance); cameraAction()->setRawValue(TakePhotoIntervalDistance);
cameraPhotoIntervalDistance()->setRawValue(missionItem.param1()); cameraPhotoIntervalDistance()->setRawValue(missionItem.param1());
visualItems->removeAt(scanIndex)->deleteLater(); visualItems->removeAt(scanIndex)->deleteLater();
} else { break;
stopLooking = true;
} }
stopLooking = true;
break; break;
case MAV_CMD_VIDEO_START_CAPTURE: case MAV_CMD_VIDEO_START_CAPTURE:
...@@ -224,6 +273,16 @@ bool CameraSection::scanForCameraSection(QmlObjectListModel* visualItems, int sc ...@@ -224,6 +273,16 @@ bool CameraSection::scanForCameraSection(QmlObjectListModel* visualItems, int sc
} }
break; 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;
cameraAction()->setRawValue(StopTakingVideo);
visualItems->removeAt(scanIndex)->deleteLater();
} else {
stopLooking = true;
}
break;
default: default:
stopLooking = true; stopLooking = true;
break; break;
......
...@@ -23,11 +23,14 @@ class CameraSection : public QObject ...@@ -23,11 +23,14 @@ class CameraSection : public QObject
public: public:
CameraSection(QObject* parent = NULL); CameraSection(QObject* parent = NULL);
// These nume values must match the json meta data
enum CameraAction { enum CameraAction {
CameraActionNone, CameraActionNone,
TakePhotosIntervalTime, TakePhotosIntervalTime,
TakePhotoIntervalDistance, TakePhotoIntervalDistance,
TakeVideo StopTakingPhotos,
TakeVideo,
StopTakingVideo
}; };
Q_ENUMS(CameraAction) Q_ENUMS(CameraAction)
......
...@@ -991,7 +991,7 @@ ...@@ -991,7 +991,7 @@
"id": 2500, "id": 2500,
"rawName": "MAV_CMD_VIDEO_START_CAPTURE", "rawName": "MAV_CMD_VIDEO_START_CAPTURE",
"friendlyName": "Start video capture", "friendlyName": "Start video capture",
"description": "Start taking video.", "description": "Start video capture.",
"category": "Camera", "category": "Camera",
"param1": { "param1": {
"label": "Camera id", "label": "Camera id",
...@@ -1009,6 +1009,18 @@ ...@@ -1009,6 +1009,18 @@
"decimalPlaces": 0 "decimalPlaces": 0
} }
}, },
{
"id": 2501,
"rawName": "MAV_CMD_VIDEO_STOP_CAPTURE",
"friendlyName": "Stop video capture",
"description": "Stop video capture.",
"category": "Camera",
"param1": {
"label": "Camera id",
"default": 0,
"decimalPlaces": 0
}
},
{ "id": 2800, "rawName": "MAV_CMD_PANORAMA_CREATE", "friendlyName": "Create panorama" }, { "id": 2800, "rawName": "MAV_CMD_PANORAMA_CREATE", "friendlyName": "Create panorama" },
{ {
"id": 3000, "id": 3000,
......
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