Commit 1b27f221 authored by Don Gagne's avatar Don Gagne

Add camera start to transect entry even when taking images throughout survey area.

parent 1bf12b5b
...@@ -172,7 +172,7 @@ void CorridorScanComplexItem::_buildAndAppendMissionItems(QList<MissionItem*>& i ...@@ -172,7 +172,7 @@ void CorridorScanComplexItem::_buildAndAppendMissionItems(QList<MissionItem*>& i
//qDebug() << "_buildAndAppendMissionItems"; //qDebug() << "_buildAndAppendMissionItems";
for (const QList<TransectStyleComplexItem::CoordInfo_t>& transect: _transects) { for (const QList<TransectStyleComplexItem::CoordInfo_t>& transect: _transects) {
bool entryPoint = true; bool transectEntry = true;
//qDebug() << "start transect"; //qDebug() << "start transect";
for (const CoordInfo_t& transectCoordInfo: transect) { for (const CoordInfo_t& transectCoordInfo: transect) {
...@@ -193,7 +193,7 @@ void CorridorScanComplexItem::_buildAndAppendMissionItems(QList<MissionItem*>& i ...@@ -193,7 +193,7 @@ void CorridorScanComplexItem::_buildAndAppendMissionItems(QList<MissionItem*>& i
missionItemParent); missionItemParent);
items.append(item); items.append(item);
if (firstOverallPoint && addTriggerAtBeginning) { if (triggerCamera() && firstOverallPoint && addTriggerAtBeginning) {
// Start triggering // Start triggering
addTriggerAtBeginning = false; addTriggerAtBeginning = false;
item = new MissionItem(seqNum++, item = new MissionItem(seqNum++,
...@@ -210,9 +210,12 @@ void CorridorScanComplexItem::_buildAndAppendMissionItems(QList<MissionItem*>& i ...@@ -210,9 +210,12 @@ void CorridorScanComplexItem::_buildAndAppendMissionItems(QList<MissionItem*>& i
} }
firstOverallPoint = false; firstOverallPoint = false;
if (transectCoordInfo.coordType == TransectStyleComplexItem::CoordTypeSurveyEdge && !imagesEverywhere) { // Possibly add trigger start/stop to survey area entrance/exit
if (entryPoint) { if (triggerCamera()) {
// Start of transect, start triggering if (transectCoordInfo.coordType == TransectStyleComplexItem::CoordTypeSurveyEdge && 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++, item = new MissionItem(seqNum++,
MAV_CMD_DO_SET_CAM_TRIGG_DIST, MAV_CMD_DO_SET_CAM_TRIGG_DIST,
MAV_FRAME_MISSION, MAV_FRAME_MISSION,
...@@ -224,7 +227,8 @@ void CorridorScanComplexItem::_buildAndAppendMissionItems(QList<MissionItem*>& i ...@@ -224,7 +227,8 @@ void CorridorScanComplexItem::_buildAndAppendMissionItems(QList<MissionItem*>& i
false, // isCurrentItem false, // isCurrentItem
missionItemParent); missionItemParent);
items.append(item); items.append(item);
} else { transectEntry = false;
} else if (!imagesEverywhere && !transectEntry){
// End of transect, stop triggering // End of transect, stop triggering
item = new MissionItem(seqNum++, item = new MissionItem(seqNum++,
MAV_CMD_DO_SET_CAM_TRIGG_DIST, MAV_CMD_DO_SET_CAM_TRIGG_DIST,
...@@ -238,7 +242,6 @@ void CorridorScanComplexItem::_buildAndAppendMissionItems(QList<MissionItem*>& i ...@@ -238,7 +242,6 @@ void CorridorScanComplexItem::_buildAndAppendMissionItems(QList<MissionItem*>& i
missionItemParent); missionItemParent);
items.append(item); items.append(item);
} }
entryPoint = !entryPoint;
} }
} }
} }
......
This diff is collapsed.
...@@ -117,7 +117,7 @@ private: ...@@ -117,7 +117,7 @@ private:
void _rebuildTransectsPhase1WorkerSinglePolygon(bool refly); void _rebuildTransectsPhase1WorkerSinglePolygon(bool refly);
void _rebuildTransectsPhase1WorkerSplitPolygons(bool refly); void _rebuildTransectsPhase1WorkerSplitPolygons(bool refly);
/// Adds to the _transects array from one polygon /// 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 // Decompose polygon into list of convex sub polygons
void _PolygonDecomposeConvex(const QPolygonF& polygon, QList<QPolygonF>& decomposedPolygons); void _PolygonDecomposeConvex(const QPolygonF& polygon, QList<QPolygonF>& decomposedPolygons);
// return true if vertex a can see vertex b // return true if vertex a can see vertex b
......
...@@ -719,10 +719,12 @@ int TransectStyleComplexItem::lastSequenceNumber(void) const ...@@ -719,10 +719,12 @@ int TransectStyleComplexItem::lastSequenceNumber(void) const
} }
if (!hoverAndCaptureEnabled()) { if (!hoverAndCaptureEnabled() && triggerCamera()) {
if (_cameraTriggerInTurnAroundFact.rawValue().toBool()) { if (_cameraTriggerInTurnAroundFact.rawValue().toBool()) {
// Only one camera start and on camera stop // One camera start/stop for beginning/end of entire survey
itemCount += 2; itemCount += 2;
// One camera start for each transect
itemCount += _transects.count();
} else { } else {
// Each transect will have a camera start and stop in it // Each transect will have a camera start and stop in it
itemCount += _transects.count() * 2; 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