From c6c2a2b81a223be52768f49937c6e11ce01a9646 Mon Sep 17 00:00:00 2001 From: Gus Grubba Date: Thu, 5 Apr 2018 13:53:46 -0400 Subject: [PATCH] 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 f16d54aaf..9114c8f7c 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 32d019e5e..9b105eaa9 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 69eb38db7..b48ec308e 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) -- 2.22.0