Commit 257fc085 authored by Don Gagne's avatar Don Gagne Committed by GitHub

Merge pull request #5413 from DonLakeFlyer/ImagesEverywhere

Survey fixes
parents 3349f5a2 4b8147d3
......@@ -166,7 +166,9 @@ void CameraSection::appendSectionItems(QList<MissionItem*>& items, QObject* miss
MAV_CMD_DO_SET_CAM_TRIGG_DIST,
MAV_FRAME_MISSION,
_cameraPhotoIntervalDistanceFact.rawValue().toDouble(), // Trigger distance
0, 0, 0, 0, 0, 0, // param 2-7 not used
0, // No shutter integartion
1, // Trigger immediately
0, 0, 0, 0, // param 4-7 not used
true, // autoContinue
false, // isCurrentItem
missionItemParent);
......@@ -314,13 +316,31 @@ bool CameraSection::_scanStopTakingPhotos(QmlObjectListModel* visualItems, int s
return false;
}
bool CameraSection::_scanTriggerDistance(QmlObjectListModel* visualItems, int scanIndex)
bool CameraSection::_scanTriggerStartDistance(QmlObjectListModel* visualItems, int scanIndex)
{
SimpleMissionItem* item = visualItems->value<SimpleMissionItem*>(scanIndex);
if (item) {
MissionItem& missionItem = item->missionItem();
if ((MAV_CMD)item->command() == MAV_CMD_DO_SET_CAM_TRIGG_DIST) {
if (missionItem.param1() >= 0 && missionItem.param2() == 0 && missionItem.param3() == 0 && missionItem.param4() == 0 && missionItem.param5() == 0 && missionItem.param6() == 0 && missionItem.param7() == 0) {
if (missionItem.param1() > 0 && missionItem.param2() == 0 && missionItem.param3() == 1 && missionItem.param4() == 0 && missionItem.param5() == 0 && missionItem.param6() == 0 && missionItem.param7() == 0) {
cameraAction()->setRawValue(TakePhotoIntervalDistance);
cameraPhotoIntervalDistance()->setRawValue(missionItem.param1());
visualItems->removeAt(scanIndex)->deleteLater();
return true;
}
}
}
return false;
}
bool CameraSection::_scanTriggerStopDistance(QmlObjectListModel* visualItems, int scanIndex)
{
SimpleMissionItem* item = visualItems->value<SimpleMissionItem*>(scanIndex);
if (item) {
MissionItem& missionItem = item->missionItem();
if ((MAV_CMD)item->command() == MAV_CMD_DO_SET_CAM_TRIGG_DIST) {
if (missionItem.param1() == 0 && missionItem.param2() == 0 && missionItem.param3() == 0 && missionItem.param4() == 0 && missionItem.param5() == 0 && missionItem.param6() == 0 && missionItem.param7() == 0) {
cameraAction()->setRawValue(TakePhotoIntervalDistance);
cameraPhotoIntervalDistance()->setRawValue(missionItem.param1());
visualItems->removeAt(scanIndex)->deleteLater();
......@@ -416,7 +436,11 @@ bool CameraSection::scanForSection(QmlObjectListModel* visualItems, int scanInde
foundCameraAction = true;
continue;
}
if (!foundCameraAction && _scanTriggerDistance(visualItems, scanIndex)) {
if (!foundCameraAction && _scanTriggerStartDistance(visualItems, scanIndex)) {
foundCameraAction = true;
continue;
}
if (!foundCameraAction && _scanTriggerStopDistance(visualItems, scanIndex)) {
foundCameraAction = true;
continue;
}
......
......@@ -94,7 +94,8 @@ private:
bool _scanTakePhoto(QmlObjectListModel* visualItems, int scanIndex);
bool _scanTakePhotosIntervalTime(QmlObjectListModel* visualItems, int scanIndex);
bool _scanStopTakingPhotos(QmlObjectListModel* visualItems, int scanIndex);
bool _scanTriggerDistance(QmlObjectListModel* visualItems, int scanIndex);
bool _scanTriggerStartDistance(QmlObjectListModel* visualItems, int scanIndex);
bool _scanTriggerStopDistance(QmlObjectListModel* visualItems, int scanIndex);
bool _scanTakeVideo(QmlObjectListModel* visualItems, int scanIndex);
bool _scanStopTakingVideo(QmlObjectListModel* visualItems, int scanIndex);
bool _scanSetCameraMode(QmlObjectListModel* visualItems, int scanIndex);
......
......@@ -50,7 +50,14 @@ void CameraSectionTest::init(void)
MissionItem(0, MAV_CMD_IMAGE_START_CAPTURE, MAV_FRAME_MISSION, 0, 48, 0, NAN, NAN, NAN, NAN, true, false),
this);
_validDistanceItem = new SimpleMissionItem(_offlineVehicle,
MissionItem(0, MAV_CMD_DO_SET_CAM_TRIGG_DIST, MAV_FRAME_MISSION, 72, 0, 0, 0, 0, 0, 0, true, false),
MissionItem(0,
MAV_CMD_DO_SET_CAM_TRIGG_DIST,
MAV_FRAME_MISSION,
72, // trigger distance
0, // not shutter integration
1, // trigger immediately
0, 0, 0, 0,
true, false),
this);
_validStartVideoItem = new SimpleMissionItem(_offlineVehicle,
MissionItem(0, // sequence number
......@@ -732,15 +739,15 @@ void CameraSectionTest::_testScanForPhotoIntervalDistanceSection(void)
_commonScanTest(_cameraSection);
/*
MAV_CMD_DO_SET_CAM_TRIGG_DIST Mission command to set CAM_TRIGG_DIST for this flight
Mission Param #1 Camera trigger distance (meters)
Mission Param #2 Empty
Mission Param #3 Empty
MAV_CMD_DO_SET_CAM_TRIGG_DIST Mission command to set camera trigger distance for this flight. The camera is trigerred each time this distance is exceeded. This command can also be used to set the shutter integration time for the camera.
Mission Param #1 Camera trigger distance (meters). 0 to stop triggering.
Mission Param #2 Camera shutter integration time (milliseconds). -1 or 0 to ignore
Mission Param #3 Trigger camera once immediately. (0 = no trigger, 1 = trigger)
Mission Param #4 Empty
Mission Param #5 Empty
Mission Param #6 Empty
Mission Param #7 Empty
*/
*/
SimpleMissionItem* newValidDistanceItem = new SimpleMissionItem(_offlineVehicle, this);
newValidDistanceItem->missionItem() = _validDistanceItem->missionItem();
......@@ -772,7 +779,7 @@ void CameraSectionTest::_testScanForPhotoIntervalDistanceSection(void)
visualItems.clear();
invalidSimpleItem.missionItem() = _validDistanceItem->missionItem();
invalidSimpleItem.missionItem().setParam3(1); // must be 0
invalidSimpleItem.missionItem().setParam3(0); // must be 1
visualItems.append(&invalidSimpleItem);
QCOMPARE(_cameraSection->scanForSection(&visualItems, scanIndex), false);
QCOMPARE(visualItems.count(), 1);
......
......@@ -1138,9 +1138,11 @@ int SurveyMissionItem::_appendWaypointToMission(QList<MissionItem*>& items, int
MAV_CMD_DO_SET_CAM_TRIGG_DIST,
MAV_FRAME_MISSION,
cameraTrigger == CameraTriggerOn ? _triggerDistance() : 0,
0, 0, 0, 0, 0, 0, // param 2-7 unused
true, // autoContinue
false, // isCurrentItem
0, // shutter integration (ignore)
cameraTrigger == CameraTriggerOn ? 1 : 0, // trigger immediately when starting
0, 0, 0, 0, // param 4-7 unused
true, // autoContinue
false, // isCurrentItem
missionItemParent);
items.append(item);
break;
......@@ -1196,21 +1198,14 @@ bool SurveyMissionItem::_nextTransectCoord(const QList<QGeoCoordinate>& transect
/// @return false: Generation failed
bool SurveyMissionItem::_appendMissionItemsWorker(QList<MissionItem*>& items, QObject* missionItemParent, int& seqNum, bool hasRefly, bool buildRefly)
{
bool firstWaypointTrigger = false;
qCDebug(SurveyMissionItemLog) << "hasTurnaround:triggerCamera:hoverAndCapture:imagesEverywhere:hasRefly:buildRefly" << _hasTurnaround() << _triggerCamera() << _hoverAndCaptureEnabled() << _imagesEverywhere() << hasRefly << buildRefly;
QList<QList<QGeoCoordinate>>& transectSegments = buildRefly ? _reflyTransectSegments : _transectSegments;
if (!buildRefly && _imagesEverywhere()) {
// We are taking images in turnaround, so we start command once at beginning
MissionItem* item = new MissionItem(seqNum++,
MAV_CMD_DO_SET_CAM_TRIGG_DIST,
MAV_FRAME_MISSION,
_triggerDistance(),
0, 0, 0, 0, 0, 0, // param 2-7 unused
true, // autoContinue
false, // isCurrentItem
missionItemParent);
items.append(item);
firstWaypointTrigger = true;
}
for (int segmentIndex=0; segmentIndex<transectSegments.count(); segmentIndex++) {
......@@ -1226,15 +1221,21 @@ bool SurveyMissionItem::_appendMissionItemsWorker(QList<MissionItem*>& items, QO
if (!_nextTransectCoord(segment, pointIndex++, coord)) {
return false;
}
seqNum = _appendWaypointToMission(items, seqNum, coord, CameraTriggerNone, missionItemParent);
seqNum = _appendWaypointToMission(items, seqNum, coord, firstWaypointTrigger ? CameraTriggerOn : CameraTriggerNone, missionItemParent);
firstWaypointTrigger = false;
}
// Add polygon entry point
if (!_nextTransectCoord(segment, pointIndex++, coord)) {
return false;
}
cameraTrigger = _imagesEverywhere() || !_triggerCamera() ? CameraTriggerNone : (_hoverAndCaptureEnabled() ? CameraTriggerHoverAndCapture : CameraTriggerOn);
if (firstWaypointTrigger) {
cameraTrigger = CameraTriggerOn;
} else {
cameraTrigger = _imagesEverywhere() || !_triggerCamera() ? CameraTriggerNone : (_hoverAndCaptureEnabled() ? CameraTriggerHoverAndCapture : CameraTriggerOn);
}
seqNum = _appendWaypointToMission(items, seqNum, coord, cameraTrigger, missionItemParent);
firstWaypointTrigger = false;
// Add internal hover and capture points
if (_hoverAndCaptureEnabled()) {
......
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