Commit 4dca19f8 authored by DonLakeFlyer's avatar DonLakeFlyer

Hover and Capture support

parent 40d3d6fd
......@@ -814,7 +814,7 @@ void SurveyComplexItem::_buildAndAppendMissionItems(QList<MissionItem*>& items,
MissionItem* item;
int seqNum = _sequenceNumber;
bool imagesEverywhere = _cameraTriggerInTurnAroundFact.rawValue().toBool();
bool addTriggerAtBeginning = imagesEverywhere;
bool addTriggerAtBeginning = !hoverAndCaptureEnabled() && imagesEverywhere;
bool firstOverallPoint = true;
MAV_FRAME mavFrame = followTerrain() || !_cameraCalc.distanceToSurfaceRelative() ? MAV_FRAME_GLOBAL : MAV_FRAME_GLOBAL_RELATIVE_ALT;
......@@ -826,17 +826,31 @@ void SurveyComplexItem::_buildAndAppendMissionItems(QList<MissionItem*>& items,
item = new MissionItem(seqNum++,
MAV_CMD_NAV_WAYPOINT,
mavFrame,
0, // No hold time
0.0, // No acceptance radius specified
0.0, // Pass through waypoint
std::numeric_limits<double>::quiet_NaN(), // Yaw unchanged
hoverAndCaptureEnabled() ?
_hoverAndCaptureDelaySeconds : 0, // Hold time (delay for hover and capture to settle vehicle before image is taken)
0.0, // No acceptance radius specified
0.0, // Pass through waypoint
std::numeric_limits<double>::quiet_NaN(), // Yaw unchanged
transectCoordInfo.coord.latitude(),
transectCoordInfo.coord.longitude(),
transectCoordInfo.coord.altitude(),
true, // autoContinue
false, // isCurrentItem
true, // autoContinue
false, // isCurrentItem
missionItemParent);
items.append(item);
if (hoverAndCaptureEnabled()) {
item = new MissionItem(seqNum++,
MAV_CMD_IMAGE_START_CAPTURE,
MAV_FRAME_MISSION,
0, // Reserved (Set to 0)
0, // Interval (none)
1, // Take 1 photo
NAN, NAN, NAN, NAN, // param 4-7 reserved
true, // autoContinue
false, // isCurrentItem
missionItemParent);
items.append(item);
}
if (firstOverallPoint && addTriggerAtBeginning) {
// Start triggering
......@@ -844,29 +858,29 @@ void SurveyComplexItem::_buildAndAppendMissionItems(QList<MissionItem*>& items,
item = new MissionItem(seqNum++,
MAV_CMD_DO_SET_CAM_TRIGG_DIST,
MAV_FRAME_MISSION,
_cameraCalc.adjustedFootprintFrontal()->rawValue().toDouble(), // trigger distance
0, // shutter integration (ignore)
1, // trigger immediately when starting
0, 0, 0, 0, // param 4-7 unused
true, // autoContinue
false, // isCurrentItem
triggerDistance(), // trigger distance
0, // shutter integration (ignore)
1, // trigger immediately when starting
0, 0, 0, 0, // param 4-7 unused
true, // autoContinue
false, // isCurrentItem
missionItemParent);
items.append(item);
}
firstOverallPoint = false;
if (transectCoordInfo.coordType == TransectStyleComplexItem::CoordTypeSurveyEdge && !imagesEverywhere) {
if (transectCoordInfo.coordType == TransectStyleComplexItem::CoordTypeSurveyEdge && triggerCamera() && !hoverAndCaptureEnabled() && !imagesEverywhere) {
if (entryPoint) {
// Start of transect, start triggering
item = new MissionItem(seqNum++,
MAV_CMD_DO_SET_CAM_TRIGG_DIST,
MAV_FRAME_MISSION,
_cameraCalc.adjustedFootprintFrontal()->rawValue().toDouble(), // trigger distance
0, // shutter integration (ignore)
1, // trigger immediately when starting
0, 0, 0, 0, // param 4-7 unused
true, // autoContinue
false, // isCurrentItem
triggerDistance(), // trigger distance
0, // shutter integration (ignore)
1, // trigger immediately when starting
0, 0, 0, 0, // param 4-7 unused
true, // autoContinue
false, // isCurrentItem
missionItemParent);
items.append(item);
} else {
......@@ -888,7 +902,7 @@ void SurveyComplexItem::_buildAndAppendMissionItems(QList<MissionItem*>& items,
}
}
if (imagesEverywhere) {
if (triggerCamera() && !hoverAndCaptureEnabled() && imagesEverywhere) {
// Stop triggering
MissionItem* item = new MissionItem(seqNum++,
MAV_CMD_DO_SET_CAM_TRIGG_DIST,
......@@ -1230,6 +1244,20 @@ void SurveyComplexItem::_rebuildTransectsPhase1Worker(bool refly)
coordInfo = { transect[1], CoordTypeSurveyEdge };
coordInfoTransect.append(coordInfo);
// For hover and capture we need points for each camera location within the transect
if (triggerCamera() && hoverAndCaptureEnabled()) {
double transectLength = transect[0].distanceTo(transect[1]);
double transectAzimuth = transect[0].azimuthTo(transect[1]);
if (triggerDistance() < transectLength) {
int cInnerHoverPoints = floor(transectLength / triggerDistance());
qCDebug(SurveyComplexItemLog) << "cInnerHoverPoints" << cInnerHoverPoints;
for (int i=0; i<cInnerHoverPoints; i++) {
QGeoCoordinate hoverCoord = transect[0].atDistanceAndAzimuth(triggerDistance() * (i + 1), transectAzimuth);
TransectStyleComplexItem::CoordInfo_t coordInfo = { hoverCoord, CoordTypeInteriorHoverTrigger };
coordInfoTransect.insert(1 + i, coordInfo);
}
}
}
// Extend the transect ends for turnaround
if (_hasTurnaround()) {
......@@ -1261,9 +1289,8 @@ void SurveyComplexItem::_rebuildTransectsPhase2(void)
_complexDistance += _visualTransectPoints[i].value<QGeoCoordinate>().distanceTo(_visualTransectPoints[i+1].value<QGeoCoordinate>());
}
double triggerDistance = _cameraCalc.adjustedFootprintFrontal()->rawValue().toDouble();
if (_cameraTriggerInTurnAroundFact.rawValue().toBool()) {
_cameraShots = qCeil(_complexDistance / triggerDistance);
_cameraShots = qCeil(_complexDistance / triggerDistance());
} else {
_cameraShots = 0;
foreach (const QList<TransectStyleComplexItem::CoordInfo_t>& transect, _transects) {
......@@ -1275,7 +1302,7 @@ void SurveyComplexItem::_rebuildTransectsPhase2(void)
firstCameraCoord = transect.first().coord;
lastCameraCoord = transect.last().coord;
}
_cameraShots += qCeil(firstCameraCoord.distanceTo(lastCameraCoord) / triggerDistance);
_cameraShots += qCeil(firstCameraCoord.distanceTo(lastCameraCoord) / triggerDistance());
}
}
......@@ -1340,6 +1367,5 @@ void SurveyComplexItem::rotateEntryPoint(void)
double SurveyComplexItem::timeBetweenShots(void)
{
return _cruiseSpeed == 0 ? 0 : _cameraCalc.adjustedFootprintFrontal()->rawValue().toDouble() / _cruiseSpeed;
return _cruiseSpeed == 0 ? 0 : triggerDistance() / _cruiseSpeed;
}
......@@ -682,15 +682,18 @@ int TransectStyleComplexItem::lastSequenceNumber(void) const
int itemCount = 0;
foreach (const QList<CoordInfo_t>& rgCoordInfo, _transects) {
itemCount += rgCoordInfo.count();
itemCount += rgCoordInfo.count() * (hoverAndCaptureEnabled() ? 2 : 1);
}
if (_cameraTriggerInTurnAroundFact.rawValue().toBool()) {
// Only one camera start and on camera stop
itemCount += 2;
} else {
// Each transect will have a camera start and stop in it
itemCount += _transects.count() * 2;
if (!hoverAndCaptureEnabled()) {
if (_cameraTriggerInTurnAroundFact.rawValue().toBool()) {
// Only one camera start and on camera stop
itemCount += 2;
} else {
// Each transect will have a camera start and stop in it
itemCount += _transects.count() * 2;
}
}
return _sequenceNumber + itemCount - 1;
......
......@@ -57,6 +57,8 @@ public:
Fact* terrainAdjustMaxDescentRate (void) { return &_terrainAdjustMaxClimbRateFact; }
Fact* terrainAdjustMaxClimbRate (void) { return &_terrainAdjustMaxDescentRateFact; }
const Fact* hoverAndCapture (void) const { return &_hoverAndCaptureFact; }
int cameraShots (void) const { return _cameraShots; }
double coveredArea (void) const;
bool hoverAndCaptureAllowed (void) const;
......@@ -66,6 +68,10 @@ public:
void setFollowTerrain(bool followTerrain);
double triggerDistance (void) const { return _cameraCalc.adjustedFootprintFrontal()->rawValue().toDouble(); }
bool hoverAndCaptureEnabled (void) const { return hoverAndCapture()->rawValue().toBool(); }
bool triggerCamera (void) const { return triggerDistance() != 0; }
// Overrides from ComplexMissionItem
int lastSequenceNumber (void) const final;
......@@ -148,10 +154,11 @@ protected:
QGCMapPolygon _surveyAreaPolygon;
enum CoordType {
CoordTypeInterior,
CoordTypeInteriorTerrainAdded,
CoordTypeSurveyEdge,
CoordTypeTurnaround
CoordTypeInterior, ///< Interior waypoint for flight path only
CoordTypeInteriorHoverTrigger, ///< Interior waypoint for hover and capture trigger
CoordTypeInteriorTerrainAdded, ///< Interior waypoint added for terrain
CoordTypeSurveyEdge, ///< Waypoint at edge of survey polygon
CoordTypeTurnaround ///< Waypoint outside of survey polygon for turnaround
};
typedef struct {
......
......@@ -112,7 +112,7 @@ Rectangle {
Layout.columnSpan: 2
onClicked: {
if (checked) {
missionItem.cameraTriggerInTurnaround.rawValue = false
missionItem.cameraTriggerInTurnAround.rawValue = false
}
}
}
......
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