From c6c2a2b81a223be52768f49937c6e11ce01a9646 Mon Sep 17 00:00:00 2001 From: Gus Grubba Date: Thu, 5 Apr 2018 13:53:46 -0400 Subject: [PATCH 1/4] Set video capture status for missions --- src/MissionManager/CameraSection.cc | 12 ++++++------ src/MissionManager/CameraSection.h | 2 ++ src/MissionManager/CameraSectionTest.cc | 9 +-------- 3 files changed, 9 insertions(+), 14 deletions(-) diff --git a/src/MissionManager/CameraSection.cc b/src/MissionManager/CameraSection.cc index f16d54a..9114c8f 100644 --- a/src/MissionManager/CameraSection.cc +++ b/src/MissionManager/CameraSection.cc @@ -180,11 +180,11 @@ void CameraSection::appendSectionItems(QList& items, QObject* miss item = new MissionItem(nextSequenceNumber++, MAV_CMD_VIDEO_START_CAPTURE, MAV_FRAME_MISSION, - 0, // Reserved (Set to 0) - 0, // No CAMERA_CAPTURE_STATUS streaming - NAN, NAN, NAN, NAN, NAN, // param 3-7 reserved - true, // autoContinue - false, // isCurrentItem + 0, // Reserved (Set to 0) + VIDEO_CAPTURE_STATUS_INTERVAL, // CAMERA_CAPTURE_STATUS (default to every 5 seconds) + NAN, NAN, NAN, NAN, NAN, // param 3-7 reserved + true, // autoContinue + false, // isCurrentItem missionItemParent); break; @@ -360,7 +360,7 @@ bool CameraSection::_scanTakeVideo(QmlObjectListModel* visualItems, int scanInde if (item) { MissionItem& missionItem = item->missionItem(); if ((MAV_CMD)item->command() == MAV_CMD_VIDEO_START_CAPTURE) { - if (missionItem.param1() == 0 && missionItem.param2() == 0) { + if (missionItem.param1() == 0 && missionItem.param2() == VIDEO_CAPTURE_STATUS_INTERVAL) { cameraAction()->setRawValue(TakeVideo); visualItems->removeAt(scanIndex)->deleteLater(); return true; diff --git a/src/MissionManager/CameraSection.h b/src/MissionManager/CameraSection.h index 32d019e..9b105ea 100644 --- a/src/MissionManager/CameraSection.h +++ b/src/MissionManager/CameraSection.h @@ -14,6 +14,8 @@ #include "MissionItem.h" #include "Fact.h" +#define VIDEO_CAPTURE_STATUS_INTERVAL 0.2 //-- Send capture status every 5 seconds + class CameraSection : public Section { Q_OBJECT diff --git a/src/MissionManager/CameraSectionTest.cc b/src/MissionManager/CameraSectionTest.cc index 69eb38d..b48ec30 100644 --- a/src/MissionManager/CameraSectionTest.cc +++ b/src/MissionManager/CameraSectionTest.cc @@ -70,7 +70,7 @@ void CameraSectionTest::init(void) MAV_CMD_VIDEO_START_CAPTURE, MAV_FRAME_MISSION, 0, // Reserved (Set to 0) - 0, // No CAMERA_CAPTURE_STATUS streaming + VIDEO_CAPTURE_STATUS_INTERVAL, // CAMERA_CAPTURE_STATUS (default to every 5 seconds) NAN, NAN, NAN, NAN, NAN, // param 3-7 reserved true, // autocontinue false), // isCurrentItem @@ -896,13 +896,6 @@ void CameraSectionTest::_testScanForStartVideoSection(void) QCOMPARE(_cameraSection->settingsSpecified(), false); visualItems.clear(); - invalidSimpleItem.missionItem() = _validStartVideoItem->missionItem(); - invalidSimpleItem.missionItem().setParam2(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::_testScanForStopVideoSection(void) From 7811fc40aa81957d40b6e0212337435197478826 Mon Sep 17 00:00:00 2001 From: Gus Grubba Date: Thu, 5 Apr 2018 16:23:12 -0400 Subject: [PATCH 2/4] Removed all "reserved" arguments from the (Json) list so it they not shown. Added param2 for start video capture (update interval) Excluded param2 above from PX4 as it's fixed to 0.2Hz Re-added param2 test within CameraSectionTest (start video capture) --- src/FirmwarePlugin/PX4/MavCmdInfoCommon.json | 5 +++++ src/MissionManager/CameraSectionTest.cc | 8 ++++++++ src/MissionManager/MavCmdInfoCommon.json | 27 ++++++--------------------- 3 files changed, 19 insertions(+), 21 deletions(-) diff --git a/src/FirmwarePlugin/PX4/MavCmdInfoCommon.json b/src/FirmwarePlugin/PX4/MavCmdInfoCommon.json index f50fe22..8657261 100644 --- a/src/FirmwarePlugin/PX4/MavCmdInfoCommon.json +++ b/src/FirmwarePlugin/PX4/MavCmdInfoCommon.json @@ -18,6 +18,11 @@ "id": 201, "comment": "MAV_CMD_DO_SET_ROI", "paramRemove": "1,2,3" + }, + { + "id": 2500, + "comment": "MAV_CMD_VIDEO_START_CAPTURE", + "paramRemove": "2" } ] } diff --git a/src/MissionManager/CameraSectionTest.cc b/src/MissionManager/CameraSectionTest.cc index b48ec30..76894ed 100644 --- a/src/MissionManager/CameraSectionTest.cc +++ b/src/MissionManager/CameraSectionTest.cc @@ -931,6 +931,14 @@ void CameraSectionTest::_testScanForStopVideoSection(void) QCOMPARE(visualItems.count(), 1); QCOMPARE(_cameraSection->settingsSpecified(), false); visualItems.clear(); + + invalidSimpleItem.missionItem() = _validStartVideoItem->missionItem(); + invalidSimpleItem.missionItem().setParam2(VIDEO_CAPTURE_STATUS_INTERVAL + 1); // must be VIDEO_CAPTURE_STATUS_INTERVAL + visualItems.append(&invalidSimpleItem); + QCOMPARE(_cameraSection->scanForSection(&visualItems, scanIndex), false); + QCOMPARE(visualItems.count(), 1); + QCOMPARE(_cameraSection->settingsSpecified(), false); + visualItems.clear(); } void CameraSectionTest::_testScanForStopImageSection(void) diff --git a/src/MissionManager/MavCmdInfoCommon.json b/src/MissionManager/MavCmdInfoCommon.json index 9a7dd6c..9a15299 100644 --- a/src/MissionManager/MavCmdInfoCommon.json +++ b/src/MissionManager/MavCmdInfoCommon.json @@ -1005,11 +1005,6 @@ "friendlyName": "Start image capture" , "description": "Start taking one or more photos.", "category": "Camera", - "param1": { - "label": "Reserved", - "default": 0, - "decimalPlaces": 0 - }, "param2": { "label": "Interval", "default": 0, @@ -1027,12 +1022,7 @@ "rawName": "MAV_CMD_IMAGE_STOP_CAPTURE", "friendlyName": "Stop image capture", "description": "Stop taking photos.", - "category": "Camera", - "param1": { - "label": "Reserved", - "default": 0, - "decimalPlaces": 0 - } + "category": "Camera" }, { "id": 2003, "rawName": "MAV_CMD_DO_TRIGGER_CONTROL", "friendlyName": "Trigger control" }, { @@ -1041,10 +1031,10 @@ "friendlyName": "Start video capture", "description": "Start video capture.", "category": "Camera", - "param1": { - "label": "Reserved", - "default": 0, - "decimalPlaces": 0 + "param2": { + "label": "Status Interval", + "default": 0.2, + "decimalPlaces": 2 } }, { @@ -1052,12 +1042,7 @@ "rawName": "MAV_CMD_VIDEO_STOP_CAPTURE", "friendlyName": "Stop video capture", "description": "Stop video capture.", - "category": "Camera", - "param1": { - "label": "Reserved", - "default": 0, - "decimalPlaces": 0 - } + "category": "Camera" }, { "id": 2800, "rawName": "MAV_CMD_PANORAMA_CREATE", "friendlyName": "Create panorama" }, { From 9983ad494b36df99d5fe720a033828828300d1a2 Mon Sep 17 00:00:00 2001 From: Gus Grubba Date: Thu, 5 Apr 2018 16:29:24 -0400 Subject: [PATCH 3/4] Add units --- src/MissionManager/MavCmdInfoCommon.json | 1 + 1 file changed, 1 insertion(+) diff --git a/src/MissionManager/MavCmdInfoCommon.json b/src/MissionManager/MavCmdInfoCommon.json index 9a15299..9f659e2 100644 --- a/src/MissionManager/MavCmdInfoCommon.json +++ b/src/MissionManager/MavCmdInfoCommon.json @@ -1034,6 +1034,7 @@ "param2": { "label": "Status Interval", "default": 0.2, + "units": "Hz", "decimalPlaces": 2 } }, From 43228ad9ea48c7efb67e4da2e5ebb54ddee7b087 Mon Sep 17 00:00:00 2001 From: Gus Grubba Date: Thu, 5 Apr 2018 16:31:28 -0400 Subject: [PATCH 4/4] Renamed to "Frequency" as this is what it is. --- src/MissionManager/MavCmdInfoCommon.json | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/MissionManager/MavCmdInfoCommon.json b/src/MissionManager/MavCmdInfoCommon.json index 9f659e2..63a3459 100644 --- a/src/MissionManager/MavCmdInfoCommon.json +++ b/src/MissionManager/MavCmdInfoCommon.json @@ -1032,7 +1032,7 @@ "description": "Start video capture.", "category": "Camera", "param2": { - "label": "Status Interval", + "label": "Status Frequency", "default": 0.2, "units": "Hz", "decimalPlaces": 2