Unverified Commit 41a20fcc authored by Don Gagne's avatar Don Gagne Committed by GitHub

Merge pull request #7007 from DonLakeFlyer/TransectEntryCameraStart

Survey, CorridorScan: Add camera start to transect entry even when taking images throughout…
parents dfa866fa 373fbed3
......@@ -172,7 +172,7 @@ void CorridorScanComplexItem::_buildAndAppendMissionItems(QList<MissionItem*>& i
//qDebug() << "_buildAndAppendMissionItems";
for (const QList<TransectStyleComplexItem::CoordInfo_t>& transect: _transects) {
bool entryPoint = true;
bool transectEntry = true;
//qDebug() << "start transect";
for (const CoordInfo_t& transectCoordInfo: transect) {
......@@ -193,7 +193,7 @@ void CorridorScanComplexItem::_buildAndAppendMissionItems(QList<MissionItem*>& i
missionItemParent);
items.append(item);
if (firstOverallPoint && addTriggerAtBeginning) {
if (triggerCamera() && firstOverallPoint && addTriggerAtBeginning) {
// Start triggering
addTriggerAtBeginning = false;
item = new MissionItem(seqNum++,
......@@ -210,9 +210,12 @@ void CorridorScanComplexItem::_buildAndAppendMissionItems(QList<MissionItem*>& i
}
firstOverallPoint = false;
if (transectCoordInfo.coordType == TransectStyleComplexItem::CoordTypeSurveyEdge && !imagesEverywhere) {
if (entryPoint) {
// Start of transect, start triggering
// Possibly add trigger start/stop to survey area entrance/exit
if (triggerCamera() && transectCoordInfo.coordType == TransectStyleComplexItem::CoordTypeSurveyEdge) {
if (transectEntry) {
// Start of transect, always start triggering. We do this even if we are taking images everywhere.
// This allows a restart of the mission in mid-air without losing images from the entire mission.
// At most you may lose part of a transect.
item = new MissionItem(seqNum++,
MAV_CMD_DO_SET_CAM_TRIGG_DIST,
MAV_FRAME_MISSION,
......@@ -224,7 +227,8 @@ void CorridorScanComplexItem::_buildAndAppendMissionItems(QList<MissionItem*>& i
false, // isCurrentItem
missionItemParent);
items.append(item);
} else {
transectEntry = false;
} else if (!imagesEverywhere && !transectEntry){
// End of transect, stop triggering
item = new MissionItem(seqNum++,
MAV_CMD_DO_SET_CAM_TRIGG_DIST,
......@@ -238,7 +242,6 @@ void CorridorScanComplexItem::_buildAndAppendMissionItems(QList<MissionItem*>& i
missionItemParent);
items.append(item);
}
entryPoint = !entryPoint;
}
}
}
......
This diff is collapsed.
......@@ -117,7 +117,7 @@ private:
void _rebuildTransectsPhase1WorkerSinglePolygon(bool refly);
void _rebuildTransectsPhase1WorkerSplitPolygons(bool refly);
/// Adds to the _transects array from one polygon
void _rebuildTranscetsFromPolygon(bool refly, const QPolygonF& polygon, const QGeoCoordinate& tangentOrigin, const QPointF* const transitionPoint);
void _rebuildTransectsFromPolygon(bool refly, const QPolygonF& polygon, const QGeoCoordinate& tangentOrigin, const QPointF* const transitionPoint);
// Decompose polygon into list of convex sub polygons
void _PolygonDecomposeConvex(const QPolygonF& polygon, QList<QPolygonF>& decomposedPolygons);
// return true if vertex a can see vertex b
......
......@@ -719,10 +719,12 @@ int TransectStyleComplexItem::lastSequenceNumber(void) const
}
if (!hoverAndCaptureEnabled()) {
if (!hoverAndCaptureEnabled() && triggerCamera()) {
if (_cameraTriggerInTurnAroundFact.rawValue().toBool()) {
// Only one camera start and on camera stop
// One camera start/stop for beginning/end of entire survey
itemCount += 2;
// One camera start for each transect
itemCount += _transects.count();
} else {
// Each transect will have a camera start and stop in it
itemCount += _transects.count() * 2;
......
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