Unverified Commit 73cfd557 authored by Gus Grubba's avatar Gus Grubba Committed by GitHub

Merge pull request #6308 from mavlink/videoUpdates

Set video capture status for missions
parents 9b9f4b7f 43228ad9
...@@ -18,6 +18,11 @@ ...@@ -18,6 +18,11 @@
"id": 201, "id": 201,
"comment": "MAV_CMD_DO_SET_ROI", "comment": "MAV_CMD_DO_SET_ROI",
"paramRemove": "1,2,3" "paramRemove": "1,2,3"
},
{
"id": 2500,
"comment": "MAV_CMD_VIDEO_START_CAPTURE",
"paramRemove": "2"
} }
] ]
} }
...@@ -180,11 +180,11 @@ void CameraSection::appendSectionItems(QList<MissionItem*>& items, QObject* miss ...@@ -180,11 +180,11 @@ void CameraSection::appendSectionItems(QList<MissionItem*>& items, QObject* miss
item = new MissionItem(nextSequenceNumber++, item = new MissionItem(nextSequenceNumber++,
MAV_CMD_VIDEO_START_CAPTURE, MAV_CMD_VIDEO_START_CAPTURE,
MAV_FRAME_MISSION, MAV_FRAME_MISSION,
0, // Reserved (Set to 0) 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 NAN, NAN, NAN, NAN, NAN, // param 3-7 reserved
true, // autoContinue true, // autoContinue
false, // isCurrentItem false, // isCurrentItem
missionItemParent); missionItemParent);
break; break;
...@@ -360,7 +360,7 @@ bool CameraSection::_scanTakeVideo(QmlObjectListModel* visualItems, int scanInde ...@@ -360,7 +360,7 @@ bool CameraSection::_scanTakeVideo(QmlObjectListModel* visualItems, int scanInde
if (item) { if (item) {
MissionItem& missionItem = item->missionItem(); MissionItem& missionItem = item->missionItem();
if ((MAV_CMD)item->command() == MAV_CMD_VIDEO_START_CAPTURE) { 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); cameraAction()->setRawValue(TakeVideo);
visualItems->removeAt(scanIndex)->deleteLater(); visualItems->removeAt(scanIndex)->deleteLater();
return true; return true;
......
...@@ -14,6 +14,8 @@ ...@@ -14,6 +14,8 @@
#include "MissionItem.h" #include "MissionItem.h"
#include "Fact.h" #include "Fact.h"
#define VIDEO_CAPTURE_STATUS_INTERVAL 0.2 //-- Send capture status every 5 seconds
class CameraSection : public Section class CameraSection : public Section
{ {
Q_OBJECT Q_OBJECT
......
...@@ -70,7 +70,7 @@ void CameraSectionTest::init(void) ...@@ -70,7 +70,7 @@ void CameraSectionTest::init(void)
MAV_CMD_VIDEO_START_CAPTURE, MAV_CMD_VIDEO_START_CAPTURE,
MAV_FRAME_MISSION, MAV_FRAME_MISSION,
0, // Reserved (Set to 0) 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 NAN, NAN, NAN, NAN, NAN, // param 3-7 reserved
true, // autocontinue true, // autocontinue
false), // isCurrentItem false), // isCurrentItem
...@@ -896,13 +896,6 @@ void CameraSectionTest::_testScanForStartVideoSection(void) ...@@ -896,13 +896,6 @@ void CameraSectionTest::_testScanForStartVideoSection(void)
QCOMPARE(_cameraSection->settingsSpecified(), false); QCOMPARE(_cameraSection->settingsSpecified(), false);
visualItems.clear(); 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) void CameraSectionTest::_testScanForStopVideoSection(void)
...@@ -938,6 +931,14 @@ void CameraSectionTest::_testScanForStopVideoSection(void) ...@@ -938,6 +931,14 @@ void CameraSectionTest::_testScanForStopVideoSection(void)
QCOMPARE(visualItems.count(), 1); QCOMPARE(visualItems.count(), 1);
QCOMPARE(_cameraSection->settingsSpecified(), false); QCOMPARE(_cameraSection->settingsSpecified(), false);
visualItems.clear(); 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) void CameraSectionTest::_testScanForStopImageSection(void)
......
...@@ -1005,11 +1005,6 @@ ...@@ -1005,11 +1005,6 @@
"friendlyName": "Start image capture" , "friendlyName": "Start image capture" ,
"description": "Start taking one or more photos.", "description": "Start taking one or more photos.",
"category": "Camera", "category": "Camera",
"param1": {
"label": "Reserved",
"default": 0,
"decimalPlaces": 0
},
"param2": { "param2": {
"label": "Interval", "label": "Interval",
"default": 0, "default": 0,
...@@ -1027,12 +1022,7 @@ ...@@ -1027,12 +1022,7 @@
"rawName": "MAV_CMD_IMAGE_STOP_CAPTURE", "rawName": "MAV_CMD_IMAGE_STOP_CAPTURE",
"friendlyName": "Stop image capture", "friendlyName": "Stop image capture",
"description": "Stop taking photos.", "description": "Stop taking photos.",
"category": "Camera", "category": "Camera"
"param1": {
"label": "Reserved",
"default": 0,
"decimalPlaces": 0
}
}, },
{ "id": 2003, "rawName": "MAV_CMD_DO_TRIGGER_CONTROL", "friendlyName": "Trigger control" }, { "id": 2003, "rawName": "MAV_CMD_DO_TRIGGER_CONTROL", "friendlyName": "Trigger control" },
{ {
...@@ -1041,10 +1031,11 @@ ...@@ -1041,10 +1031,11 @@
"friendlyName": "Start video capture", "friendlyName": "Start video capture",
"description": "Start video capture.", "description": "Start video capture.",
"category": "Camera", "category": "Camera",
"param1": { "param2": {
"label": "Reserved", "label": "Status Frequency",
"default": 0, "default": 0.2,
"decimalPlaces": 0 "units": "Hz",
"decimalPlaces": 2
} }
}, },
{ {
...@@ -1052,12 +1043,7 @@ ...@@ -1052,12 +1043,7 @@
"rawName": "MAV_CMD_VIDEO_STOP_CAPTURE", "rawName": "MAV_CMD_VIDEO_STOP_CAPTURE",
"friendlyName": "Stop video capture", "friendlyName": "Stop video capture",
"description": "Stop video capture.", "description": "Stop video capture.",
"category": "Camera", "category": "Camera"
"param1": {
"label": "Reserved",
"default": 0,
"decimalPlaces": 0
}
}, },
{ "id": 2800, "rawName": "MAV_CMD_PANORAMA_CREATE", "friendlyName": "Create panorama" }, { "id": 2800, "rawName": "MAV_CMD_PANORAMA_CREATE", "friendlyName": "Create panorama" },
{ {
......
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