diff --git a/src/MissionManager/CameraSection.FactMetaData.json b/src/MissionManager/CameraSection.FactMetaData.json index d60c7243f7f7b0c423d4d9a049a64751a516ba37..3895f1ac02b1f06f1878de9f0e6fb2e7689b9ff4 100644 --- a/src/MissionManager/CameraSection.FactMetaData.json +++ b/src/MissionManager/CameraSection.FactMetaData.json @@ -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),Take video", - "enumValues": "0,1,2,3", + "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", "defaultValue": 0 }, { diff --git a/src/MissionManager/CameraSection.cc b/src/MissionManager/CameraSection.cc index 20594ca622551b133cc0d6c9f0b60eb094f66f63..247487e91bcbaedf6da1b038449387f9d8e8060b 100644 --- a/src/MissionManager/CameraSection.cc +++ b/src/MissionManager/CameraSection.cc @@ -150,6 +150,37 @@ void CameraSection::appendMissionItems(QList& items, QObject* miss false, // isCurrentItem missionItemParent); 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) { items.append(item); @@ -204,14 +235,32 @@ bool CameraSection::scanForCameraSection(QmlObjectListModel* visualItems, int sc 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) { + 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(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; cameraAction()->setRawValue(TakePhotoIntervalDistance); cameraPhotoIntervalDistance()->setRawValue(missionItem.param1()); visualItems->removeAt(scanIndex)->deleteLater(); - } else { - stopLooking = true; + break; } + stopLooking = true; break; case MAV_CMD_VIDEO_START_CAPTURE: @@ -224,6 +273,16 @@ bool CameraSection::scanForCameraSection(QmlObjectListModel* visualItems, int sc } 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: stopLooking = true; break; diff --git a/src/MissionManager/CameraSection.h b/src/MissionManager/CameraSection.h index 7d01492b93e8a9e5ec40545b76c3035807348caa..b5ad6f244e1ab441a4e6ed76d0ef89a86ef6960d 100644 --- a/src/MissionManager/CameraSection.h +++ b/src/MissionManager/CameraSection.h @@ -23,11 +23,14 @@ class CameraSection : public QObject public: CameraSection(QObject* parent = NULL); + // These nume values must match the json meta data enum CameraAction { CameraActionNone, TakePhotosIntervalTime, TakePhotoIntervalDistance, - TakeVideo + StopTakingPhotos, + TakeVideo, + StopTakingVideo }; Q_ENUMS(CameraAction) diff --git a/src/MissionManager/MavCmdInfoCommon.json b/src/MissionManager/MavCmdInfoCommon.json index c139686f145a54bc6953149888ed256cb9c15eff..87f41e2a7df0da61e82fa644d46fc45ef48c343f 100644 --- a/src/MissionManager/MavCmdInfoCommon.json +++ b/src/MissionManager/MavCmdInfoCommon.json @@ -991,7 +991,7 @@ "id": 2500, "rawName": "MAV_CMD_VIDEO_START_CAPTURE", "friendlyName": "Start video capture", - "description": "Start taking video.", + "description": "Start video capture.", "category": "Camera", "param1": { "label": "Camera id", @@ -1009,6 +1009,18 @@ "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": 3000,