Commit b28e00a0 authored by Don Gagne's avatar Don Gagne Committed by GitHub

Merge pull request #4899 from DonLakeFlyer/HoverAndCapture

Survey: Hover and Capture support
parents 296a43ce e5a4fef1
...@@ -267,7 +267,8 @@ QList<MAV_CMD> PX4FirmwarePlugin::supportedMissionCommands(void) ...@@ -267,7 +267,8 @@ QList<MAV_CMD> PX4FirmwarePlugin::supportedMissionCommands(void)
<< MAV_CMD_DO_LAND_START << MAV_CMD_DO_LAND_START
<< MAV_CMD_DO_MOUNT_CONFIGURE << MAV_CMD_DO_MOUNT_CONFIGURE
<< MAV_CMD_DO_MOUNT_CONTROL << MAV_CMD_DO_MOUNT_CONTROL
<< MAV_CMD_IMAGE_START_CAPTURE << MAV_CMD_IMAGE_STOP_CAPTURE << MAV_CMD_VIDEO_START_CAPTURE << MAV_CMD_VIDEO_STOP_CAPTURE; << MAV_CMD_IMAGE_START_CAPTURE << MAV_CMD_IMAGE_STOP_CAPTURE << MAV_CMD_VIDEO_START_CAPTURE << MAV_CMD_VIDEO_STOP_CAPTURE
<< MAV_CMD_NAV_DELAY;
return list; return list;
} }
......
...@@ -74,6 +74,7 @@ SurveyMissionItem::SurveyMissionItem(Vehicle* vehicle, QObject* parent) ...@@ -74,6 +74,7 @@ SurveyMissionItem::SurveyMissionItem(Vehicle* vehicle, QObject* parent)
, _sequenceNumber(0) , _sequenceNumber(0)
, _dirty(false) , _dirty(false)
, _cameraOrientationFixed(false) , _cameraOrientationFixed(false)
, _missionCommandCount(0)
, _surveyDistance(0.0) , _surveyDistance(0.0)
, _cameraShots(0) , _cameraShots(0)
, _coveredArea(0.0) , _coveredArea(0.0)
...@@ -114,6 +115,7 @@ SurveyMissionItem::SurveyMissionItem(Vehicle* vehicle, QObject* parent) ...@@ -114,6 +115,7 @@ SurveyMissionItem::SurveyMissionItem(Vehicle* vehicle, QObject* parent)
connect(&_cameraTriggerDistanceFact, &Fact::valueChanged, this, &SurveyMissionItem::_generateGrid); connect(&_cameraTriggerDistanceFact, &Fact::valueChanged, this, &SurveyMissionItem::_generateGrid);
connect(&_cameraTriggerInTurnaroundFact, &Fact::valueChanged, this, &SurveyMissionItem::_generateGrid); connect(&_cameraTriggerInTurnaroundFact, &Fact::valueChanged, this, &SurveyMissionItem::_generateGrid);
connect(&_hoverAndCaptureFact, &Fact::valueChanged, this, &SurveyMissionItem::_generateGrid); connect(&_hoverAndCaptureFact, &Fact::valueChanged, this, &SurveyMissionItem::_generateGrid);
connect(&_cameraTriggerFact, &Fact::valueChanged, this, &SurveyMissionItem::_generateGrid);
connect(&_gridAltitudeFact, &Fact::valueChanged, this, &SurveyMissionItem::_updateCoordinateAltitude); connect(&_gridAltitudeFact, &Fact::valueChanged, this, &SurveyMissionItem::_updateCoordinateAltitude);
...@@ -128,8 +130,6 @@ SurveyMissionItem::SurveyMissionItem(Vehicle* vehicle, QObject* parent) ...@@ -128,8 +130,6 @@ SurveyMissionItem::SurveyMissionItem(Vehicle* vehicle, QObject* parent)
connect(&_cameraFocalLengthFact, &Fact::valueChanged, this, &SurveyMissionItem::_cameraValueChanged); connect(&_cameraFocalLengthFact, &Fact::valueChanged, this, &SurveyMissionItem::_cameraValueChanged);
connect(&_cameraOrientationLandscapeFact, &Fact::valueChanged, this, &SurveyMissionItem::_cameraValueChanged); connect(&_cameraOrientationLandscapeFact, &Fact::valueChanged, this, &SurveyMissionItem::_cameraValueChanged);
connect(&_cameraTriggerFact, &Fact::valueChanged, this, &SurveyMissionItem::_cameraTriggerChanged);
connect(&_cameraTriggerDistanceFact, &Fact::valueChanged, this, &SurveyMissionItem::timeBetweenShotsChanged); connect(&_cameraTriggerDistanceFact, &Fact::valueChanged, this, &SurveyMissionItem::timeBetweenShotsChanged);
} }
...@@ -268,17 +268,7 @@ void SurveyMissionItem::removePolygonVertex(int vertexIndex) ...@@ -268,17 +268,7 @@ void SurveyMissionItem::removePolygonVertex(int vertexIndex)
int SurveyMissionItem::lastSequenceNumber(void) const int SurveyMissionItem::lastSequenceNumber(void) const
{ {
int lastSeq = _sequenceNumber; return _sequenceNumber + _missionCommandCount;
if (_simpleGridPoints.count()) {
lastSeq += _simpleGridPoints.count() - 1;
if (_cameraTriggerFact.rawValue().toBool()) {
// Account for two trigger messages
lastSeq += 2;
}
}
return lastSeq;
} }
void SurveyMissionItem::setCoordinate(const QGeoCoordinate& coordinate) void SurveyMissionItem::setCoordinate(const QGeoCoordinate& coordinate)
...@@ -307,6 +297,7 @@ void SurveyMissionItem::save(QJsonArray& missionItems) ...@@ -307,6 +297,7 @@ void SurveyMissionItem::save(QJsonArray& missionItems)
saveObject[_jsonCameraTriggerKey] = _cameraTriggerFact.rawValue().toBool(); saveObject[_jsonCameraTriggerKey] = _cameraTriggerFact.rawValue().toBool();
saveObject[_jsonManualGridKey] = _manualGridFact.rawValue().toBool(); saveObject[_jsonManualGridKey] = _manualGridFact.rawValue().toBool();
saveObject[_jsonFixedValueIsAltitudeKey] = _fixedValueIsAltitudeFact.rawValue().toBool(); saveObject[_jsonFixedValueIsAltitudeKey] = _fixedValueIsAltitudeFact.rawValue().toBool();
saveObject[_jsonHoverAndCaptureKey] = _hoverAndCaptureFact.rawValue().toBool();
if (_cameraTriggerFact.rawValue().toBool()) { if (_cameraTriggerFact.rawValue().toBool()) {
saveObject[_jsonCameraTriggerDistanceKey] = _cameraTriggerDistanceFact.rawValue().toDouble(); saveObject[_jsonCameraTriggerDistanceKey] = _cameraTriggerDistanceFact.rawValue().toDouble();
...@@ -397,6 +388,7 @@ bool SurveyMissionItem::load(const QJsonObject& complexObject, int sequenceNumbe ...@@ -397,6 +388,7 @@ bool SurveyMissionItem::load(const QJsonObject& complexObject, int sequenceNumbe
{ _jsonCameraTriggerDistanceKey, QJsonValue::Double, false }, { _jsonCameraTriggerDistanceKey, QJsonValue::Double, false },
{ _jsonManualGridKey, QJsonValue::Bool, true }, { _jsonManualGridKey, QJsonValue::Bool, true },
{ _jsonFixedValueIsAltitudeKey, QJsonValue::Bool, true }, { _jsonFixedValueIsAltitudeKey, QJsonValue::Bool, true },
{ _jsonHoverAndCaptureKey, QJsonValue::Bool, false },
}; };
if (!JsonHelper::validateKeys(v2Object, mainKeyInfoList, errorString)) { if (!JsonHelper::validateKeys(v2Object, mainKeyInfoList, errorString)) {
return false; return false;
...@@ -417,6 +409,7 @@ bool SurveyMissionItem::load(const QJsonObject& complexObject, int sequenceNumbe ...@@ -417,6 +409,7 @@ bool SurveyMissionItem::load(const QJsonObject& complexObject, int sequenceNumbe
_cameraTriggerFact.setRawValue (v2Object[_jsonCameraTriggerKey].toBool(false)); _cameraTriggerFact.setRawValue (v2Object[_jsonCameraTriggerKey].toBool(false));
_fixedValueIsAltitudeFact.setRawValue (v2Object[_jsonFixedValueIsAltitudeKey].toBool(true)); _fixedValueIsAltitudeFact.setRawValue (v2Object[_jsonFixedValueIsAltitudeKey].toBool(true));
_gridAltitudeRelativeFact.setRawValue (v2Object[_jsonGridAltitudeRelativeKey].toBool(true)); _gridAltitudeRelativeFact.setRawValue (v2Object[_jsonGridAltitudeRelativeKey].toBool(true));
_hoverAndCaptureFact.setRawValue (v2Object[_jsonHoverAndCaptureKey].toBool(false));
QList<JsonHelper::KeyValidateInfo> gridKeyInfoList = { QList<JsonHelper::KeyValidateInfo> gridKeyInfoList = {
{ _jsonGridAltitudeKey, QJsonValue::Double, true }, { _jsonGridAltitudeKey, QJsonValue::Double, true },
...@@ -535,6 +528,9 @@ void SurveyMissionItem::_clearGrid(void) ...@@ -535,6 +528,9 @@ void SurveyMissionItem::_clearGrid(void)
} }
emit gridPointsChanged(); emit gridPointsChanged();
_simpleGridPoints.clear(); _simpleGridPoints.clear();
_transectSegments.clear();
_missionCommandCount = 0;
} }
void _calcCameraShots() void _calcCameraShots()
...@@ -550,10 +546,11 @@ void SurveyMissionItem::_generateGrid(void) ...@@ -550,10 +546,11 @@ void SurveyMissionItem::_generateGrid(void)
} }
_simpleGridPoints.clear(); _simpleGridPoints.clear();
_transectSegments.clear();
QList<QPointF> polygonPoints; QList<QPointF> polygonPoints;
QList<QPointF> gridPoints; QList<QPointF> gridPoints;
QList<QList<QPointF>> gridSegments; QList<QList<QPointF>> transectSegments;
// Convert polygon to Qt coordinate system (y positive is down) // Convert polygon to Qt coordinate system (y positive is down)
qCDebug(SurveyMissionItemLog) << "Convert polygon"; qCDebug(SurveyMissionItemLog) << "Convert polygon";
...@@ -576,10 +573,10 @@ void SurveyMissionItem::_generateGrid(void) ...@@ -576,10 +573,10 @@ void SurveyMissionItem::_generateGrid(void)
_setCoveredArea(0.5 * fabs(coveredArea)); _setCoveredArea(0.5 * fabs(coveredArea));
// Generate grid // Generate grid
_gridGenerator(polygonPoints, gridPoints, gridSegments); _gridGenerator(polygonPoints, gridPoints, transectSegments);
// Convert simple grid to QGeoCoordinates
double surveyDistance = 0.0; double surveyDistance = 0.0;
// Convert to Geo and set altitude
for (int i=0; i<gridPoints.count(); i++) { for (int i=0; i<gridPoints.count(); i++) {
QPointF& point = gridPoints[i]; QPointF& point = gridPoints[i];
...@@ -593,19 +590,48 @@ void SurveyMissionItem::_generateGrid(void) ...@@ -593,19 +590,48 @@ void SurveyMissionItem::_generateGrid(void)
} }
_setSurveyDistance(surveyDistance); _setSurveyDistance(surveyDistance);
// Convert transect segments to QGeoCoordinate
for (int i=0; i<transectSegments.count(); i++) {
QList<QGeoCoordinate> transectCoords;
const QList<QPointF>& transectPoints = transectSegments[i];
for (int j=0; j<transectPoints.count(); j++) {
QGeoCoordinate coord;
const QPointF& point = transectPoints[j];
convertNedToGeo(-point.y(), point.x(), 0, tangentOrigin, &coord);
transectCoords.append(coord);
}
_transectSegments.append(transectCoords);
}
// Set camera shots here if taking images in turnaround (otherwise it's in _gridGenerator) // Set camera shots here if taking images in turnaround (otherwise it's in _gridGenerator)
double triggerDistance = _cameraTriggerDistanceFact.rawValue().toDouble(); if (_triggerCamera()) {
if (triggerDistance > 0) { if (_imagesEverywhere()) {
if (_cameraTriggerInTurnaroundFact.rawValue().toBool()) { _setCameraShots((int)ceil(surveyDistance / _triggerDistance()));
_setCameraShots((int)ceil(surveyDistance / triggerDistance));
} }
} else { } else {
_setCameraShots(0); _setCameraShots(0);
} }
emit gridPointsChanged(); emit gridPointsChanged();
// Determine command count for lastSequenceNumber
_missionCommandCount= 0;
for (int i=0; i<_transectSegments.count(); i++) {
const QList<QGeoCoordinate>& transectSegment = _transectSegments[i];
_missionCommandCount += transectSegment.count(); // This accounts for all waypoints
if (_hoverAndCaptureEnabled()) {
// Internal camera trigger points are entry point, plus all points before exit point
_missionCommandCount += transectSegment.count() - (_hasTurnaround() ? 2 : 0) - 1;
} else if (_triggerCamera()) {
_missionCommandCount += 2; // Camera on/off at entry/exit
}
}
emit lastSequenceNumberChanged(lastSequenceNumber()); emit lastSequenceNumberChanged(lastSequenceNumber());
// Set exit coordinate
if (_simpleGridPoints.count()) { if (_simpleGridPoints.count()) {
QGeoCoordinate coordinate = _simpleGridPoints.first().value<QGeoCoordinate>(); QGeoCoordinate coordinate = _simpleGridPoints.first().value<QGeoCoordinate>();
coordinate.setAltitude(_gridAltitudeFact.rawValue().toDouble()); coordinate.setAltitude(_gridAltitudeFact.rawValue().toDouble());
...@@ -738,7 +764,7 @@ void SurveyMissionItem::_adjustLineDirection(const QList<QLineF>& lineList, QLis ...@@ -738,7 +764,7 @@ void SurveyMissionItem::_adjustLineDirection(const QList<QLineF>& lineList, QLis
} }
} }
void SurveyMissionItem::_gridGenerator(const QList<QPointF>& polygonPoints, QList<QPointF>& simpleGridPoints, QList<QList<QPointF>>& gridSegments) void SurveyMissionItem::_gridGenerator(const QList<QPointF>& polygonPoints, QList<QPointF>& simpleGridPoints, QList<QList<QPointF>>& transectSegments)
{ {
double gridAngle = _gridAngleFact.rawValue().toDouble(); double gridAngle = _gridAngleFact.rawValue().toDouble();
double gridSpacing = _gridSpacingFact.rawValue().toDouble(); double gridSpacing = _gridSpacingFact.rawValue().toDouble();
...@@ -746,7 +772,7 @@ void SurveyMissionItem::_gridGenerator(const QList<QPointF>& polygonPoints, QLi ...@@ -746,7 +772,7 @@ void SurveyMissionItem::_gridGenerator(const QList<QPointF>& polygonPoints, QLi
qCDebug(SurveyMissionItemLog) << "SurveyMissionItem::_gridGenerator gridSpacing:gridAngle" << gridSpacing << gridAngle; qCDebug(SurveyMissionItemLog) << "SurveyMissionItem::_gridGenerator gridSpacing:gridAngle" << gridSpacing << gridAngle;
simpleGridPoints.clear(); simpleGridPoints.clear();
gridSegments.clear(); transectSegments.clear();
// Convert polygon to bounding rect // Convert polygon to bounding rect
...@@ -799,131 +825,214 @@ void SurveyMissionItem::_gridGenerator(const QList<QPointF>& polygonPoints, QLi ...@@ -799,131 +825,214 @@ void SurveyMissionItem::_gridGenerator(const QList<QPointF>& polygonPoints, QLi
QList<QLineF> resultLines; QList<QLineF> resultLines;
_adjustLineDirection(intersectLines, resultLines); _adjustLineDirection(intersectLines, resultLines);
float turnaroundDist = _turnaroundDistFact.rawValue().toDouble();
// Calc camera shots here if there are no images in turnaround // Calc camera shots here if there are no images in turnaround
double triggerDistance = _cameraTriggerDistanceFact.rawValue().toDouble(); if (_triggerCamera() && !_imagesEverywhere()) {
if (triggerDistance > 0 && !_cameraTriggerInTurnaroundFact.rawValue().toBool()) {
int cameraShots = 0; int cameraShots = 0;
for (int i=0; i<resultLines.count(); i++) { for (int i=0; i<resultLines.count(); i++) {
cameraShots += (int)ceil(resultLines[i].length() / triggerDistance); cameraShots += (int)ceil(resultLines[i].length() / _triggerDistance());
} }
_setCameraShots(cameraShots); _setCameraShots(cameraShots);
} }
// Turn into a path // Turn into a path
for (int i=0; i<resultLines.count(); i++) { for (int i=0; i<resultLines.count(); i++) {
QList<QPointF> segmentPoints; QLineF transectLine;
const QLineF& line = resultLines[i]; QList<QPointF> transectPoints;
const QLineF& line = resultLines[i];
QPointF turnaroundOffset = line.p2() - line.p1(); float turnaroundPosition = _turnaroundDistance() / line.length();
turnaroundOffset = turnaroundOffset * turnaroundDist / sqrt(pow(turnaroundOffset.x(), 2) + pow(turnaroundOffset.y(), 2));
if (i & 1) { if (i & 1) {
if (turnaroundDist > 0.0) { transectLine = QLineF(line.p2(), line.p1());
simpleGridPoints << line.p2() + turnaroundOffset << line.p2() << line.p1() << line.p1() - turnaroundOffset;
segmentPoints << line.p2() + turnaroundOffset << line.p2() << line.p1() << line.p1() - turnaroundOffset;
} else {
simpleGridPoints << line.p2() << line.p1();
segmentPoints << line.p2() << line.p1();
}
} else { } else {
if (turnaroundDist > 0.0) { transectLine = QLineF(line.p1(), line.p2());
simpleGridPoints << line.p1() - turnaroundOffset << line.p1() << line.p2() << line.p2() + turnaroundOffset; }
segmentPoints << line.p1() - turnaroundOffset << line.p1() << line.p2() << line.p2() + turnaroundOffset;
} else { // Build the points along the transect
simpleGridPoints << line.p1() << line.p2();
segmentPoints << line.p1() << line.p2(); if (_hasTurnaround()) {
transectPoints.append(transectLine.pointAt(-turnaroundPosition));
}
// Polygon entry point
transectPoints.append(transectLine.p1());
// For hover and capture we need points for each camera location
if (_triggerCamera() && _hoverAndCaptureEnabled()) {
if (_triggerDistance() < transectLine.length()) {
int innerPoints = floor(transectLine.length() / _triggerDistance());
qCDebug(SurveyMissionItemLog) << "innerPoints" << innerPoints;
float transectPositionIncrement = _triggerDistance() / transectLine.length();
for (int i=0; i<innerPoints; i++) {
transectPoints.append(transectLine.pointAt(transectPositionIncrement * (i + 1)));
}
} }
} }
gridSegments.append(segmentPoints);
// Polygon exit point
transectPoints.append(transectLine.p2());
if (_hasTurnaround()) {
transectPoints.append(transectLine.pointAt(1 + turnaroundPosition));
}
simpleGridPoints.append(transectPoints[0]);
simpleGridPoints.append(transectPoints[transectPoints.count() - 1]);
transectSegments.append(transectPoints);
} }
} }
int SurveyMissionItem::_appendWaypointToMission(QList<MissionItem*>& items, int seqNum, QGeoCoordinate& coord, CameraTriggerCode cameraTrigger, QObject* missionItemParent) int SurveyMissionItem::_appendWaypointToMission(QList<MissionItem*>& items, int seqNum, QGeoCoordinate& coord, CameraTriggerCode cameraTrigger, QObject* missionItemParent)
{ {
double altitude = _gridAltitudeFact.rawValue().toDouble(); double altitude = _gridAltitudeFact.rawValue().toDouble();
bool altitudeRelative = _gridAltitudeRelativeFact.rawValue().toBool(); bool altitudeRelative = _gridAltitudeRelativeFact.rawValue().toBool();
double triggerDistance = _cameraTriggerDistanceFact.rawValue().toDouble();
qCDebug(SurveyMissionItemLog) << "_appendWaypointToMission seq:trigger" << seqNum << (cameraTrigger != CameraTriggerNone);
MissionItem* item = new MissionItem(seqNum++, MissionItem* item = new MissionItem(seqNum++,
MAV_CMD_NAV_WAYPOINT, MAV_CMD_NAV_WAYPOINT,
altitudeRelative ? MAV_FRAME_GLOBAL_RELATIVE_ALT : MAV_FRAME_GLOBAL, altitudeRelative ? MAV_FRAME_GLOBAL_RELATIVE_ALT : MAV_FRAME_GLOBAL,
0.0, 0.0, 0.0, 0.0, // param 1-4 unused cameraTrigger == CameraTriggerHoverAndCapture ? 1 : 0, // Hold time (1 second for hover and capture to settle vehicle before image is taken)
0.0, 0.0, 0.0, // param 2-4 unused
coord.latitude(), coord.latitude(),
coord.longitude(), coord.longitude(),
altitude, altitude,
true, // autoContinue true, // autoContinue
false, // isCurrentItem false, // isCurrentItem
missionItemParent); missionItemParent);
items.append(item); items.append(item);
if (cameraTrigger != CameraTriggerNone) { switch (cameraTrigger) {
MissionItem* item = new MissionItem(seqNum++, case CameraTriggerOff:
MAV_CMD_DO_SET_CAM_TRIGG_DIST, case CameraTriggerOn:
MAV_FRAME_MISSION, item = new MissionItem(seqNum++,
cameraTrigger == CameraTriggerOn ? triggerDistance : 0, MAV_CMD_DO_SET_CAM_TRIGG_DIST,
0, 0, 0, 0, 0, 0, // param 2-7 unused MAV_FRAME_MISSION,
true, // autoContinue cameraTrigger == CameraTriggerOn ? _triggerDistance() : 0,
false, // isCurrentItem 0, 0, 0, 0, 0, 0, // param 2-7 unused
missionItemParent); true, // autoContinue
false, // isCurrentItem
missionItemParent);
items.append(item); items.append(item);
break;
case CameraTriggerHoverAndCapture:
item = new MissionItem(seqNum++,
MAV_CMD_IMAGE_START_CAPTURE,
MAV_FRAME_MISSION,
0, // Interval
1, // Take 1 photo
-1, // Mav resolution
0, 0, // Param 4-5 unused
0, // Camera ID
7, // Param 7 unused
true, // autoContinue
false, // isCurrentItem
missionItemParent);
items.append(item);
#if 0
// Not yet supported by firmware
item = new MissionItem(seqNum++,
MAV_CMD_NAV_DELAY,
MAV_FRAME_MISSION,
0.5, // Delay in seconds, give some time for image to be taken
-1, -1, -1, // No time
0, 0, 0, // Param 5-7 unused
true, // autoContinue
false, // isCurrentItem
missionItemParent);
items.append(item);
#endif
default:
break;
} }
return seqNum; return seqNum;
} }
bool SurveyMissionItem::_nextTransectCoord(const QList<QGeoCoordinate>& transectPoints, int pointIndex, QGeoCoordinate& coord)
{
if (pointIndex > transectPoints.count()) {
qWarning() << "Bad grid generation";
return false;
}
coord = transectPoints[pointIndex];
return true;
}
void SurveyMissionItem::appendMissionItems(QList<MissionItem*>& items, QObject* missionItemParent) void SurveyMissionItem::appendMissionItems(QList<MissionItem*>& items, QObject* missionItemParent)
{ {
int seqNum = _sequenceNumber; int seqNum = _sequenceNumber;
bool hasTurnaround = _turnaroundDistFact.rawValue().toDouble() > 0;
bool triggerCamera = _cameraTriggerFact.rawValue().toBool();
bool imagesEverywhere = triggerCamera && _cameraTriggerInTurnaroundFact.rawValue().toBool();
int i = 0; qCDebug(SurveyMissionItemLog) << "hasTurnaround:triggerCamera:hoverAndCapture:imagesEverywhere" << _hasTurnaround() << _triggerCamera() << _hoverAndCaptureEnabled() << _imagesEverywhere();
while (i < _simpleGridPoints.count()) {
if (_imagesEverywhere()) {
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);
}
for (int segmentIndex=0; segmentIndex<_transectSegments.count(); segmentIndex++) {
int pointIndex = 0;
QGeoCoordinate coord;
CameraTriggerCode cameraTrigger; CameraTriggerCode cameraTrigger;
QGeoCoordinate coord = _simpleGridPoints[i].value<QGeoCoordinate>(); const QList<QGeoCoordinate>& transectSegment = _transectSegments[segmentIndex];
qCDebug(SurveyMissionItemLog) << "transectSegment.count" << transectSegment.count();
if (_hasTurnaround()) {
// Add entry turnaround point
if (!_nextTransectCoord(transectSegment, pointIndex++, coord)) {
return;
}
seqNum = _appendWaypointToMission(items, seqNum, coord, CameraTriggerNone, missionItemParent);
}
// Either waypoint entering polygon of turnaround point for start of new transect // Add polygon entry point
cameraTrigger = imagesEverywhere ? (i == 0 ? CameraTriggerOn : CameraTriggerNone) : (hasTurnaround ? CameraTriggerNone : CameraTriggerOn); if (!_nextTransectCoord(transectSegment, pointIndex++, coord)) {
return;
}
cameraTrigger = _imagesEverywhere() || !_triggerCamera() ? CameraTriggerNone : (_hoverAndCaptureEnabled() ? CameraTriggerHoverAndCapture : CameraTriggerOn);
seqNum = _appendWaypointToMission(items, seqNum, coord, cameraTrigger, missionItemParent); seqNum = _appendWaypointToMission(items, seqNum, coord, cameraTrigger, missionItemParent);
if (hasTurnaround) { // Add internal hover and capture points
// Waypoint entering the polygon if (_hoverAndCaptureEnabled()) {
if (++i >= _simpleGridPoints.count()) { int lastHoverAndCaptureIndex = transectSegment.count() - 1 - (_hasTurnaround() ? 1 : 0);
qWarning() << "Bad grid generation"; qCDebug(SurveyMissionItemLog) << "lastHoverAndCaptureIndex" << lastHoverAndCaptureIndex;
break; for (; pointIndex < lastHoverAndCaptureIndex; pointIndex++) {
if (!_nextTransectCoord(transectSegment, pointIndex, coord)) {
return;
}
seqNum = _appendWaypointToMission(items, seqNum, coord, CameraTriggerHoverAndCapture, missionItemParent);
} }
coord = _simpleGridPoints[i].value<QGeoCoordinate>();
cameraTrigger = imagesEverywhere ? CameraTriggerNone : CameraTriggerOn;
seqNum = _appendWaypointToMission(items, seqNum, coord, cameraTrigger, missionItemParent);
} }
// Waypoint exiting polygon // Add polygon exit point
if (++i >= _simpleGridPoints.count()) { if (!_nextTransectCoord(transectSegment, pointIndex++, coord)) {
qWarning() << "Bad grid generation"; return;
break;
} }
coord = _simpleGridPoints[i].value<QGeoCoordinate>(); cameraTrigger = _imagesEverywhere() || !_triggerCamera() ? CameraTriggerNone : (_hoverAndCaptureEnabled() ? CameraTriggerNone : CameraTriggerOff);
cameraTrigger = imagesEverywhere ? CameraTriggerNone : CameraTriggerOff;
seqNum = _appendWaypointToMission(items, seqNum, coord, cameraTrigger, missionItemParent); seqNum = _appendWaypointToMission(items, seqNum, coord, cameraTrigger, missionItemParent);
if (hasTurnaround) { if (_hasTurnaround()) {
// Waypoint at the end of transect // Add exit turnaround point
if (++i >= _simpleGridPoints.count()) { if (!_nextTransectCoord(transectSegment, pointIndex++, coord)) {
qWarning() << "Bad grid generation"; return;
break;
} }
coord = _simpleGridPoints[i].value<QGeoCoordinate>(); seqNum = _appendWaypointToMission(items, seqNum, coord, CameraTriggerNone, missionItemParent);
cameraTrigger = CameraTriggerNone;
seqNum = _appendWaypointToMission(items, seqNum, coord, cameraTrigger, missionItemParent);
} }
i++; qCDebug(SurveyMissionItemLog) << "last PointIndex" << pointIndex;
} }
if (imagesEverywhere) { if (_imagesEverywhere()) {
// Turn off camera at end of survey // Turn off camera at end of survey
MissionItem* item = new MissionItem(seqNum++, MissionItem* item = new MissionItem(seqNum++,
MAV_CMD_DO_SET_CAM_TRIGG_DIST, MAV_CMD_DO_SET_CAM_TRIGG_DIST,
...@@ -937,18 +1046,9 @@ void SurveyMissionItem::appendMissionItems(QList<MissionItem*>& items, QObject* ...@@ -937,18 +1046,9 @@ void SurveyMissionItem::appendMissionItems(QList<MissionItem*>& items, QObject*
} }
} }
void SurveyMissionItem::_cameraTriggerChanged(void)
{
setDirty(true);
// Camera trigger adds items
emit lastSequenceNumberChanged(lastSequenceNumber());
// We now have camera shot count
emit cameraShotsChanged(cameraShots());
}
int SurveyMissionItem::cameraShots(void) const int SurveyMissionItem::cameraShots(void) const
{ {
return _cameraTriggerFact.rawValue().toBool() ? _cameraShots : 0; return _triggerCamera() ? _cameraShots : 0;
} }
void SurveyMissionItem::_cameraValueChanged(void) void SurveyMissionItem::_cameraValueChanged(void)
...@@ -958,7 +1058,7 @@ void SurveyMissionItem::_cameraValueChanged(void) ...@@ -958,7 +1058,7 @@ void SurveyMissionItem::_cameraValueChanged(void)
double SurveyMissionItem::timeBetweenShots(void) const double SurveyMissionItem::timeBetweenShots(void) const
{ {
return _cruiseSpeed == 0 ? 0 : _cameraTriggerDistanceFact.rawValue().toDouble() / _cruiseSpeed; return _cruiseSpeed == 0 ? 0 : _triggerDistance() / _cruiseSpeed;
} }
void SurveyMissionItem::setMissionFlightStatus (MissionController::MissionFlightStatus_t& missionFlightStatus) void SurveyMissionItem::setMissionFlightStatus (MissionController::MissionFlightStatus_t& missionFlightStatus)
...@@ -974,3 +1074,37 @@ void SurveyMissionItem::_setDirty(void) ...@@ -974,3 +1074,37 @@ void SurveyMissionItem::_setDirty(void)
{ {
setDirty(true); setDirty(true);
} }
bool SurveyMissionItem::hoverAndCaptureAllowed(void) const
{
return _vehicle->multiRotor() || _vehicle->vtol();
}
double SurveyMissionItem::_triggerDistance(void) const {
return _cameraTriggerDistanceFact.rawValue().toDouble();
}
bool SurveyMissionItem::_triggerCamera(void) const
{
return _cameraTriggerFact.rawValue().toBool() && _triggerDistance() > 0;
}
bool SurveyMissionItem::_imagesEverywhere(void) const
{
return _triggerCamera() && _cameraTriggerInTurnaroundFact.rawValue().toBool();
}
bool SurveyMissionItem::_hoverAndCaptureEnabled(void) const
{
return hoverAndCaptureAllowed() && !_imagesEverywhere() && _triggerCamera() && _hoverAndCaptureFact.rawValue().toBool();
}
bool SurveyMissionItem::_hasTurnaround(void) const
{
return _turnaroundDistance() > 0;
}
double SurveyMissionItem::_turnaroundDistance(void) const
{
return _turnaroundDistFact.rawValue().toDouble();
}
...@@ -48,6 +48,7 @@ public: ...@@ -48,6 +48,7 @@ public:
Q_PROPERTY(Fact* camera READ camera CONSTANT) Q_PROPERTY(Fact* camera READ camera CONSTANT)
Q_PROPERTY(bool cameraOrientationFixed MEMBER _cameraOrientationFixed NOTIFY cameraOrientationFixedChanged) Q_PROPERTY(bool cameraOrientationFixed MEMBER _cameraOrientationFixed NOTIFY cameraOrientationFixedChanged)
Q_PROPERTY(bool hoverAndCaptureAllowed READ hoverAndCaptureAllowed CONSTANT)
Q_PROPERTY(double timeBetweenShots READ timeBetweenShots NOTIFY timeBetweenShotsChanged) Q_PROPERTY(double timeBetweenShots READ timeBetweenShots NOTIFY timeBetweenShotsChanged)
Q_PROPERTY(QVariantList polygonPath READ polygonPath NOTIFY polygonPathChanged) Q_PROPERTY(QVariantList polygonPath READ polygonPath NOTIFY polygonPathChanged)
...@@ -97,6 +98,7 @@ public: ...@@ -97,6 +98,7 @@ public:
int cameraShots(void) const; int cameraShots(void) const;
double coveredArea(void) const { return _coveredArea; } double coveredArea(void) const { return _coveredArea; }
double timeBetweenShots(void) const; double timeBetweenShots(void) const;
bool hoverAndCaptureAllowed(void) const;
// Overrides from ComplexMissionItem // Overrides from ComplexMissionItem
...@@ -171,14 +173,14 @@ signals: ...@@ -171,14 +173,14 @@ signals:
void cameraOrientationFixedChanged (bool cameraOrientationFixed); void cameraOrientationFixedChanged (bool cameraOrientationFixed);
private slots: private slots:
void _cameraTriggerChanged(void);
void _setDirty(void); void _setDirty(void);
private: private:
enum CameraTriggerCode { enum CameraTriggerCode {
CameraTriggerNone, CameraTriggerNone,
CameraTriggerOn, CameraTriggerOn,
CameraTriggerOff CameraTriggerOff,
CameraTriggerHoverAndCapture
}; };
void _clear(void); void _clear(void);
...@@ -186,7 +188,7 @@ private: ...@@ -186,7 +188,7 @@ private:
void _clearGrid(void); void _clearGrid(void);
void _generateGrid(void); void _generateGrid(void);
void _updateCoordinateAltitude(void); void _updateCoordinateAltitude(void);
void _gridGenerator(const QList<QPointF>& polygonPoints, QList<QPointF>& simpleGridPoints, QList<QList<QPointF>>& gridSegments); void _gridGenerator(const QList<QPointF>& polygonPoints, QList<QPointF>& simpleGridPoints, QList<QList<QPointF>>& transectSegments);
QPointF _rotatePoint(const QPointF& point, const QPointF& origin, double angle); QPointF _rotatePoint(const QPointF& point, const QPointF& origin, double angle);
void _intersectLinesWithRect(const QList<QLineF>& lineList, const QRectF& boundRect, QList<QLineF>& resultLines); void _intersectLinesWithRect(const QList<QLineF>& lineList, const QRectF& boundRect, QList<QLineF>& resultLines);
void _intersectLinesWithPolygon(const QList<QLineF>& lineList, const QPolygonF& polygon, QList<QLineF>& resultLines); void _intersectLinesWithPolygon(const QList<QLineF>& lineList, const QPolygonF& polygon, QList<QLineF>& resultLines);
...@@ -196,16 +198,24 @@ private: ...@@ -196,16 +198,24 @@ private:
void _setCoveredArea(double coveredArea); void _setCoveredArea(double coveredArea);
void _cameraValueChanged(void); void _cameraValueChanged(void);
int _appendWaypointToMission(QList<MissionItem*>& items, int seqNum, QGeoCoordinate& coord, CameraTriggerCode cameraTrigger, QObject* missionItemParent); int _appendWaypointToMission(QList<MissionItem*>& items, int seqNum, QGeoCoordinate& coord, CameraTriggerCode cameraTrigger, QObject* missionItemParent);
bool _nextTransectCoord(const QList<QGeoCoordinate>& transectPoints, int pointIndex, QGeoCoordinate& coord);
double _triggerDistance(void) const;
bool _triggerCamera(void) const;
bool _imagesEverywhere(void) const;
bool _hoverAndCaptureEnabled(void) const;
bool _hasTurnaround(void) const;
double _turnaroundDistance(void) const;
int _sequenceNumber; int _sequenceNumber;
bool _dirty; bool _dirty;
QVariantList _polygonPath; QVariantList _polygonPath;
QmlObjectListModel _polygonModel; QmlObjectListModel _polygonModel;
QVariantList _simpleGridPoints; ///< Grid points for drawing simple grid visuals QVariantList _simpleGridPoints; ///< Grid points for drawing simple grid visuals
QList<QList<QGeoCoordinate>> _gridSegments; ///< Internal grid line segments including grid exit and turnaround point QList<QList<QGeoCoordinate>> _transectSegments; ///< Internal transect segments including grid exit, turnaround and internal camera points
QGeoCoordinate _coordinate; QGeoCoordinate _coordinate;
QGeoCoordinate _exitCoordinate; QGeoCoordinate _exitCoordinate;
bool _cameraOrientationFixed; bool _cameraOrientationFixed;
int _missionCommandCount;
double _surveyDistance; double _surveyDistance;
int _cameraShots; int _cameraShots;
......
...@@ -244,8 +244,9 @@ Rectangle { ...@@ -244,8 +244,9 @@ Rectangle {
} }
FactCheckBox { FactCheckBox {
text: qsTr("Hover and capture image") text: qsTr("Hover and capture image")
fact: missionItem.hoverAndCapture fact: missionItem.hoverAndCapture
visible: missionItem.hoverAndCaptureAllowed
} }
} }
......
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