Browse Source

Merge pull request #4895 from DonLakeFlyer/NoImageInTurnaround

Plan: Support for images in turnaround on/off
QGC4.4
Gus Grubba 8 years ago committed by GitHub
parent
commit
296a43cefd
  1. 2
      src/MissionManager/CameraSection.FactMetaData.json
  2. 24
      src/MissionManager/CameraSection.cc
  3. 6
      src/MissionManager/MissionController.cc
  4. 11
      src/MissionManager/SimpleMissionItem.cc
  5. 3
      src/MissionManager/SimpleMissionItem.h
  6. 14
      src/MissionManager/Survey.SettingsGroup.json
  7. 183
      src/MissionManager/SurveyMissionItem.cc
  8. 25
      src/MissionManager/SurveyMissionItem.h
  9. 86
      src/PlanView/SurveyItemEditor.qml

2
src/MissionManager/CameraSection.FactMetaData.json

@ -12,7 +12,7 @@
"shortDescription": "Specify the distance between each photo", "shortDescription": "Specify the distance between each photo",
"type": "double", "type": "double",
"units": "m", "units": "m",
"min": 0, "min": 0.1,
"decimalPlaces": 1, "decimalPlaces": 1,
"defaultValue": 1 "defaultValue": 1
}, },

24
src/MissionManager/CameraSection.cc

@ -229,37 +229,41 @@ bool CameraSection::scanForCameraSection(QmlObjectListModel* visualItems, int sc
cameraAction()->setRawValue(TakePhotosIntervalTime); cameraAction()->setRawValue(TakePhotosIntervalTime);
cameraPhotoIntervalTime()->setRawValue(missionItem.param1()); cameraPhotoIntervalTime()->setRawValue(missionItem.param1());
visualItems->removeAt(scanIndex)->deleteLater(); visualItems->removeAt(scanIndex)->deleteLater();
} else {
stopLooking = true;
} }
stopLooking = true;
break; break;
case MAV_CMD_DO_SET_CAM_TRIGG_DIST: case MAV_CMD_DO_SET_CAM_TRIGG_DIST:
if (!foundCameraAction && missionItem.param1() >= 0 && missionItem.param2() == 0 && missionItem.param3() == 0 && missionItem.param4() == 0 && missionItem.param5() == 0 && missionItem.param6() == 0 && missionItem.param7() == 0) { if (!foundCameraAction && missionItem.param1() >= 0 && missionItem.param2() == 0 && missionItem.param3() == 0 && missionItem.param4() == 0 && missionItem.param5() == 0 && missionItem.param6() == 0 && missionItem.param7() == 0) {
// At this point we don't know if we have a stop taking photos pair, or a single distance trigger where the user specified 0 // At this point we don't know if we have a stop taking photos pair, or just a distance trigger
// We need to look at the next item to check for the stop taking photos pari
if (missionItem.param1() == 0 && scanIndex < visualItems->count() - 1) { if (missionItem.param1() == 0 && scanIndex < visualItems->count() - 1) {
// Possible stop taking photos pair
SimpleMissionItem* nextItem = visualItems->value<SimpleMissionItem*>(scanIndex + 1); SimpleMissionItem* nextItem = visualItems->value<SimpleMissionItem*>(scanIndex + 1);
if (nextItem) { if (nextItem) {
missionItem = nextItem->missionItem(); MissionItem& nextMissionItem = nextItem->missionItem();
if ((MAV_CMD)item->command() == MAV_CMD_IMAGE_STOP_CAPTURE && missionItem.param1() == 0 && missionItem.param2() == 0 && missionItem.param3() == 0 && missionItem.param4() == 0 && missionItem.param5() == 0 && missionItem.param6() == 0 && missionItem.param7() == 0) { if (nextMissionItem.command() == MAV_CMD_IMAGE_STOP_CAPTURE && nextMissionItem.param1() == 0 && nextMissionItem.param2() == 0 && nextMissionItem.param3() == 0 && nextMissionItem.param4() == 0 && nextMissionItem.param5() == 0 && nextMissionItem.param6() == 0 && nextMissionItem.param7() == 0) {
// We found a stop taking photos pair
foundCameraAction = true; foundCameraAction = true;
cameraAction()->setRawValue(StopTakingPhotos); cameraAction()->setRawValue(StopTakingPhotos);
visualItems->removeAt(scanIndex)->deleteLater(); visualItems->removeAt(scanIndex)->deleteLater();
visualItems->removeAt(scanIndex)->deleteLater(); visualItems->removeAt(scanIndex)->deleteLater();
stopLooking = true;
break; break;
} }
} }
} }
// We didn't find a stop taking photos pair, so this is a regular trigger distance item // We didn't find a stop taking photos pair, check for trigger distance
if (missionItem.param1() > 0) {
foundCameraAction = true; foundCameraAction = true;
cameraAction()->setRawValue(TakePhotoIntervalDistance); cameraAction()->setRawValue(TakePhotoIntervalDistance);
cameraPhotoIntervalDistance()->setRawValue(missionItem.param1()); cameraPhotoIntervalDistance()->setRawValue(missionItem.param1());
visualItems->removeAt(scanIndex)->deleteLater(); visualItems->removeAt(scanIndex)->deleteLater();
stopLooking = true;
break; break;
} }
}
stopLooking = true; stopLooking = true;
break; break;
@ -268,9 +272,8 @@ bool CameraSection::scanForCameraSection(QmlObjectListModel* visualItems, int sc
foundCameraAction = true; foundCameraAction = true;
cameraAction()->setRawValue(TakeVideo); cameraAction()->setRawValue(TakeVideo);
visualItems->removeAt(scanIndex)->deleteLater(); visualItems->removeAt(scanIndex)->deleteLater();
} else {
stopLooking = true;
} }
stopLooking = true;
break; break;
case MAV_CMD_VIDEO_STOP_CAPTURE: case MAV_CMD_VIDEO_STOP_CAPTURE:
@ -278,9 +281,8 @@ bool CameraSection::scanForCameraSection(QmlObjectListModel* visualItems, int sc
foundCameraAction = true; foundCameraAction = true;
cameraAction()->setRawValue(StopTakingVideo); cameraAction()->setRawValue(StopTakingVideo);
visualItems->removeAt(scanIndex)->deleteLater(); visualItems->removeAt(scanIndex)->deleteLater();
} else {
stopLooking = true;
} }
stopLooking = true;
break; break;
default: default:

6
src/MissionManager/MissionController.cc

@ -1555,10 +1555,8 @@ void MissionController::_scanForAdditionalSettings(QmlObjectListModel* visualIte
} }
SimpleMissionItem* simpleItem = qobject_cast<SimpleMissionItem*>(visualItem); SimpleMissionItem* simpleItem = qobject_cast<SimpleMissionItem*>(visualItem);
if (simpleItem && simpleItem->cameraSection()->available()) { if (simpleItem) {
scanIndex++; simpleItem->scanForSections(visualItems, scanIndex + 1, vehicle);
simpleItem->scanForSections(visualItems, scanIndex, vehicle);
continue;
} }
scanIndex++; scanIndex++;

11
src/MissionManager/SimpleMissionItem.cc

@ -655,16 +655,17 @@ double SimpleMissionItem::specifiedGimbalYaw(void)
return _cameraSection->available() ? _cameraSection->specifiedGimbalYaw() : missionItem().specifiedGimbalYaw(); return _cameraSection->available() ? _cameraSection->specifiedGimbalYaw() : missionItem().specifiedGimbalYaw();
} }
void SimpleMissionItem::scanForSections(QmlObjectListModel* visualItems, int scanIndex, Vehicle* vehicle) bool SimpleMissionItem::scanForSections(QmlObjectListModel* visualItems, int scanIndex, Vehicle* vehicle)
{ {
Q_UNUSED(vehicle); bool sectionFound = false;
qDebug() << "SimpleMissionItem::scanForSections" << scanIndex << _cameraSection->available(); Q_UNUSED(vehicle);
if (_cameraSection->available()) { if (_cameraSection->available()) {
bool sectionFound = _cameraSection->scanForCameraSection(visualItems, scanIndex); sectionFound = _cameraSection->scanForCameraSection(visualItems, scanIndex);
qDebug() << sectionFound;
} }
return sectionFound;
} }
void SimpleMissionItem::_updateCameraSection(void) void SimpleMissionItem::_updateCameraSection(void)

3
src/MissionManager/SimpleMissionItem.h

@ -48,7 +48,8 @@ public:
/// @param visualItems List of all visual items /// @param visualItems List of all visual items
/// @param scanIndex Index to start scanning from /// @param scanIndex Index to start scanning from
/// @param vehicle Vehicle associated with this mission /// @param vehicle Vehicle associated with this mission
void scanForSections(QmlObjectListModel* visualItems, int scanIndex, Vehicle* vehicle); /// @return true: section found
bool scanForSections(QmlObjectListModel* visualItems, int scanIndex, Vehicle* vehicle);
// Property accesors // Property accesors

14
src/MissionManager/Survey.SettingsGroup.json

@ -131,6 +131,18 @@
"defaultValue": 25 "defaultValue": 25
}, },
{ {
"name": "CameraTriggerInTurnaround",
"shortDescription": "Camera continues taking images in turnarounds.",
"type": "bool",
"defaultValue": false
},
{
"name": "HoverAndCapture",
"shortDescription": "Hover at each image point and take image",
"type": "bool",
"defaultValue": false
},
{
"name": "CameraOrientationLandscape", "name": "CameraOrientationLandscape",
"shortDescription": "Camera on vehicle is in landscape orientation.", "shortDescription": "Camera on vehicle is in landscape orientation.",
"type": "bool", "type": "bool",
@ -140,7 +152,7 @@
"name": "FixedValueIsAltitude", "name": "FixedValueIsAltitude",
"shortDescription": "The altitude is kep constant while ground resolution changes.", "shortDescription": "The altitude is kep constant while ground resolution changes.",
"type": "bool", "type": "bool",
"defaultValue": 0 "defaultValue": false
}, },
{ {
"name": "Camera", "name": "Camera",

183
src/MissionManager/SurveyMissionItem.cc

@ -30,6 +30,8 @@ const char* SurveyMissionItem::_jsonGridSpacingKey = "spacing";
const char* SurveyMissionItem::_jsonTurnaroundDistKey = "turnAroundDistance"; const char* SurveyMissionItem::_jsonTurnaroundDistKey = "turnAroundDistance";
const char* SurveyMissionItem::_jsonCameraTriggerKey = "cameraTrigger"; const char* SurveyMissionItem::_jsonCameraTriggerKey = "cameraTrigger";
const char* SurveyMissionItem::_jsonCameraTriggerDistanceKey = "cameraTriggerDistance"; const char* SurveyMissionItem::_jsonCameraTriggerDistanceKey = "cameraTriggerDistance";
const char* SurveyMissionItem::_jsonCameraTriggerInTurnaroundKey = "cameraTriggerInTurnaround";
const char* SurveyMissionItem::_jsonHoverAndCaptureKey = "hoverAndCapture";
const char* SurveyMissionItem::_jsonGroundResolutionKey = "groundResolution"; const char* SurveyMissionItem::_jsonGroundResolutionKey = "groundResolution";
const char* SurveyMissionItem::_jsonFrontalOverlapKey = "imageFrontalOverlap"; const char* SurveyMissionItem::_jsonFrontalOverlapKey = "imageFrontalOverlap";
const char* SurveyMissionItem::_jsonSideOverlapKey = "imageSideOverlap"; const char* SurveyMissionItem::_jsonSideOverlapKey = "imageSideOverlap";
@ -52,6 +54,8 @@ const char* SurveyMissionItem::gridAngleName = "GridAngle";
const char* SurveyMissionItem::gridSpacingName = "GridSpacing"; const char* SurveyMissionItem::gridSpacingName = "GridSpacing";
const char* SurveyMissionItem::turnaroundDistName = "TurnaroundDist"; const char* SurveyMissionItem::turnaroundDistName = "TurnaroundDist";
const char* SurveyMissionItem::cameraTriggerDistanceName = "CameraTriggerDistance"; const char* SurveyMissionItem::cameraTriggerDistanceName = "CameraTriggerDistance";
const char* SurveyMissionItem::cameraTriggerInTurnaroundName = "CameraTriggerInTurnaround";
const char* SurveyMissionItem::hoverAndCaptureName = "HoverAndCapture";
const char* SurveyMissionItem::groundResolutionName = "GroundResolution"; const char* SurveyMissionItem::groundResolutionName = "GroundResolution";
const char* SurveyMissionItem::frontalOverlapName = "FrontalOverlap"; const char* SurveyMissionItem::frontalOverlapName = "FrontalOverlap";
const char* SurveyMissionItem::sideOverlapName = "SideOverlap"; const char* SurveyMissionItem::sideOverlapName = "SideOverlap";
@ -83,6 +87,8 @@ SurveyMissionItem::SurveyMissionItem(Vehicle* vehicle, QObject* parent)
, _turnaroundDistFact (settingsGroup, _metaDataMap[turnaroundDistName]) , _turnaroundDistFact (settingsGroup, _metaDataMap[turnaroundDistName])
, _cameraTriggerFact (settingsGroup, _metaDataMap[cameraTriggerName]) , _cameraTriggerFact (settingsGroup, _metaDataMap[cameraTriggerName])
, _cameraTriggerDistanceFact (settingsGroup, _metaDataMap[cameraTriggerDistanceName]) , _cameraTriggerDistanceFact (settingsGroup, _metaDataMap[cameraTriggerDistanceName])
, _cameraTriggerInTurnaroundFact (settingsGroup, _metaDataMap[cameraTriggerInTurnaroundName])
, _hoverAndCaptureFact (settingsGroup, _metaDataMap[hoverAndCaptureName])
, _groundResolutionFact (settingsGroup, _metaDataMap[groundResolutionName]) , _groundResolutionFact (settingsGroup, _metaDataMap[groundResolutionName])
, _frontalOverlapFact (settingsGroup, _metaDataMap[frontalOverlapName]) , _frontalOverlapFact (settingsGroup, _metaDataMap[frontalOverlapName])
, _sideOverlapFact (settingsGroup, _metaDataMap[sideOverlapName]) , _sideOverlapFact (settingsGroup, _metaDataMap[sideOverlapName])
@ -106,6 +112,9 @@ SurveyMissionItem::SurveyMissionItem(Vehicle* vehicle, QObject* parent)
connect(&_gridAngleFact, &Fact::valueChanged, this, &SurveyMissionItem::_generateGrid); connect(&_gridAngleFact, &Fact::valueChanged, this, &SurveyMissionItem::_generateGrid);
connect(&_turnaroundDistFact, &Fact::valueChanged, this, &SurveyMissionItem::_generateGrid); connect(&_turnaroundDistFact, &Fact::valueChanged, this, &SurveyMissionItem::_generateGrid);
connect(&_cameraTriggerDistanceFact, &Fact::valueChanged, this, &SurveyMissionItem::_generateGrid); connect(&_cameraTriggerDistanceFact, &Fact::valueChanged, this, &SurveyMissionItem::_generateGrid);
connect(&_cameraTriggerInTurnaroundFact, &Fact::valueChanged, this, &SurveyMissionItem::_generateGrid);
connect(&_hoverAndCaptureFact, &Fact::valueChanged, this, &SurveyMissionItem::_generateGrid);
connect(&_gridAltitudeFact, &Fact::valueChanged, this, &SurveyMissionItem::_updateCoordinateAltitude); connect(&_gridAltitudeFact, &Fact::valueChanged, this, &SurveyMissionItem::_updateCoordinateAltitude);
// Signal to Qml when camera value changes so it can recalc // Signal to Qml when camera value changes so it can recalc
@ -261,8 +270,8 @@ int SurveyMissionItem::lastSequenceNumber(void) const
{ {
int lastSeq = _sequenceNumber; int lastSeq = _sequenceNumber;
if (_gridPoints.count()) { if (_simpleGridPoints.count()) {
lastSeq += _gridPoints.count() - 1; lastSeq += _simpleGridPoints.count() - 1;
if (_cameraTriggerFact.rawValue().toBool()) { if (_cameraTriggerFact.rawValue().toBool()) {
// Account for two trigger messages // Account for two trigger messages
lastSeq += 2; lastSeq += 2;
@ -495,8 +504,8 @@ bool SurveyMissionItem::load(const QJsonObject& complexObject, int sequenceNumbe
double SurveyMissionItem::greatestDistanceTo(const QGeoCoordinate &other) const double SurveyMissionItem::greatestDistanceTo(const QGeoCoordinate &other) const
{ {
double greatestDistance = 0.0; double greatestDistance = 0.0;
for (int i=0; i<_gridPoints.count(); i++) { for (int i=0; i<_simpleGridPoints.count(); i++) {
QGeoCoordinate currentCoord = _gridPoints[i].value<QGeoCoordinate>(); QGeoCoordinate currentCoord = _simpleGridPoints[i].value<QGeoCoordinate>();
double distance = currentCoord.distanceTo(other); double distance = currentCoord.distanceTo(other);
if (distance > greatestDistance) { if (distance > greatestDistance) {
greatestDistance = distance; greatestDistance = distance;
@ -521,11 +530,16 @@ bool SurveyMissionItem::specifiesCoordinate(void) const
void SurveyMissionItem::_clearGrid(void) void SurveyMissionItem::_clearGrid(void)
{ {
// Bug workaround // Bug workaround
while (_gridPoints.count() > 1) { while (_simpleGridPoints.count() > 1) {
_gridPoints.takeLast(); _simpleGridPoints.takeLast();
} }
emit gridPointsChanged(); emit gridPointsChanged();
_gridPoints.clear(); _simpleGridPoints.clear();
}
void _calcCameraShots()
{
} }
void SurveyMissionItem::_generateGrid(void) void SurveyMissionItem::_generateGrid(void)
@ -535,10 +549,11 @@ void SurveyMissionItem::_generateGrid(void)
return; return;
} }
_gridPoints.clear(); _simpleGridPoints.clear();
QList<QPointF> polygonPoints; QList<QPointF> polygonPoints;
QList<QPointF> gridPoints; QList<QPointF> gridPoints;
QList<QList<QPointF>> gridSegments;
// 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";
@ -561,7 +576,7 @@ void SurveyMissionItem::_generateGrid(void)
_setCoveredArea(0.5 * fabs(coveredArea)); _setCoveredArea(0.5 * fabs(coveredArea));
// Generate grid // Generate grid
_gridGenerator(polygonPoints, gridPoints); _gridGenerator(polygonPoints, gridPoints, gridSegments);
double surveyDistance = 0.0; double surveyDistance = 0.0;
// Convert to Geo and set altitude // Convert to Geo and set altitude
@ -574,11 +589,16 @@ void SurveyMissionItem::_generateGrid(void)
QGeoCoordinate geoCoord; QGeoCoordinate geoCoord;
convertNedToGeo(-point.y(), point.x(), 0, tangentOrigin, &geoCoord); convertNedToGeo(-point.y(), point.x(), 0, tangentOrigin, &geoCoord);
_gridPoints += QVariant::fromValue(geoCoord); _simpleGridPoints += QVariant::fromValue(geoCoord);
} }
_setSurveyDistance(surveyDistance); _setSurveyDistance(surveyDistance);
if (_cameraTriggerDistanceFact.rawValue().toDouble() > 0) {
_setCameraShots((int)floor(surveyDistance / _cameraTriggerDistanceFact.rawValue().toDouble())); // Set camera shots here if taking images in turnaround (otherwise it's in _gridGenerator)
double triggerDistance = _cameraTriggerDistanceFact.rawValue().toDouble();
if (triggerDistance > 0) {
if (_cameraTriggerInTurnaroundFact.rawValue().toBool()) {
_setCameraShots((int)ceil(surveyDistance / triggerDistance));
}
} else { } else {
_setCameraShots(0); _setCameraShots(0);
} }
@ -586,11 +606,11 @@ void SurveyMissionItem::_generateGrid(void)
emit gridPointsChanged(); emit gridPointsChanged();
emit lastSequenceNumberChanged(lastSequenceNumber()); emit lastSequenceNumberChanged(lastSequenceNumber());
if (_gridPoints.count()) { if (_simpleGridPoints.count()) {
QGeoCoordinate coordinate = _gridPoints.first().value<QGeoCoordinate>(); QGeoCoordinate coordinate = _simpleGridPoints.first().value<QGeoCoordinate>();
coordinate.setAltitude(_gridAltitudeFact.rawValue().toDouble()); coordinate.setAltitude(_gridAltitudeFact.rawValue().toDouble());
setCoordinate(coordinate); setCoordinate(coordinate);
QGeoCoordinate exitCoordinate = _gridPoints.last().value<QGeoCoordinate>(); QGeoCoordinate exitCoordinate = _simpleGridPoints.last().value<QGeoCoordinate>();
exitCoordinate.setAltitude(_gridAltitudeFact.rawValue().toDouble()); exitCoordinate.setAltitude(_gridAltitudeFact.rawValue().toDouble());
_setExitCoordinate(exitCoordinate); _setExitCoordinate(exitCoordinate);
} }
@ -718,14 +738,15 @@ void SurveyMissionItem::_adjustLineDirection(const QList<QLineF>& lineList, QLis
} }
} }
void SurveyMissionItem::_gridGenerator(const QList<QPointF>& polygonPoints, QList<QPointF>& gridPoints) void SurveyMissionItem::_gridGenerator(const QList<QPointF>& polygonPoints, QList<QPointF>& simpleGridPoints, QList<QList<QPointF>>& gridSegments)
{ {
double gridAngle = _gridAngleFact.rawValue().toDouble(); double gridAngle = _gridAngleFact.rawValue().toDouble();
double gridSpacing = _gridSpacingFact.rawValue().toDouble(); double gridSpacing = _gridSpacingFact.rawValue().toDouble();
qCDebug(SurveyMissionItemLog) << "SurveyMissionItem::_gridGenerator gridSpacing:gridAngle" << gridSpacing << gridAngle; qCDebug(SurveyMissionItemLog) << "SurveyMissionItem::_gridGenerator gridSpacing:gridAngle" << gridSpacing << gridAngle;
gridPoints.clear(); simpleGridPoints.clear();
gridSegments.clear();
// Convert polygon to bounding rect // Convert polygon to bounding rect
@ -778,43 +799,57 @@ void SurveyMissionItem::_gridGenerator(const QList<QPointF>& polygonPoints, QLi
QList<QLineF> resultLines; QList<QLineF> resultLines;
_adjustLineDirection(intersectLines, resultLines); _adjustLineDirection(intersectLines, resultLines);
// Turn into a path
float turnaroundDist = _turnaroundDistFact.rawValue().toDouble(); float turnaroundDist = _turnaroundDistFact.rawValue().toDouble();
// Calc camera shots here if there are no images in turnaround
double triggerDistance = _cameraTriggerDistanceFact.rawValue().toDouble();
if (triggerDistance > 0 && !_cameraTriggerInTurnaroundFact.rawValue().toBool()) {
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);
}
_setCameraShots(cameraShots);
}
// Turn into a path
for (int i=0; i<resultLines.count(); i++) {
QList<QPointF> segmentPoints;
const QLineF& line = resultLines[i]; const QLineF& line = resultLines[i];
QPointF turnaroundOffset = line.p2() - line.p1(); QPointF turnaroundOffset = line.p2() - line.p1();
turnaroundOffset = turnaroundOffset * turnaroundDist / sqrt(pow(turnaroundOffset.x(),2.0) + pow(turnaroundOffset.y(),2.0)); turnaroundOffset = turnaroundOffset * turnaroundDist / sqrt(pow(turnaroundOffset.x(), 2) + pow(turnaroundOffset.y(), 2));
if (i & 1) { if (i & 1) {
if (turnaroundDist > 0.0) { if (turnaroundDist > 0.0) {
gridPoints << line.p2() + turnaroundOffset << line.p2() << line.p1() << line.p1() - turnaroundOffset; simpleGridPoints << line.p2() + turnaroundOffset << line.p2() << line.p1() << line.p1() - turnaroundOffset;
segmentPoints << line.p2() + turnaroundOffset << line.p2() << line.p1() << line.p1() - turnaroundOffset;
} else { } else {
gridPoints << line.p2() << line.p1(); simpleGridPoints << line.p2() << line.p1();
segmentPoints << line.p2() << line.p1();
} }
} else { } else {
if (turnaroundDist > 0.0) { if (turnaroundDist > 0.0) {
gridPoints << line.p1() - turnaroundOffset << line.p1() << line.p2() << line.p2() + turnaroundOffset; simpleGridPoints << line.p1() - turnaroundOffset << line.p1() << line.p2() << line.p2() + turnaroundOffset;
segmentPoints << line.p1() - turnaroundOffset << line.p1() << line.p2() << line.p2() + turnaroundOffset;
} else { } else {
gridPoints << line.p1() << line.p2(); simpleGridPoints << line.p1() << line.p2();
segmentPoints << line.p1() << line.p2();
} }
} }
gridSegments.append(segmentPoints);
} }
} }
void SurveyMissionItem::appendMissionItems(QList<MissionItem*>& items, QObject* missionItemParent) int SurveyMissionItem::_appendWaypointToMission(QList<MissionItem*>& items, int seqNum, QGeoCoordinate& coord, CameraTriggerCode cameraTrigger, QObject* missionItemParent)
{ {
int seqNum = _sequenceNumber;
for (int i=0; i<_gridPoints.count(); i++) {
QGeoCoordinate coord = _gridPoints[i].value<QGeoCoordinate>();
double altitude = _gridAltitudeFact.rawValue().toDouble(); double altitude = _gridAltitudeFact.rawValue().toDouble();
bool altitudeRelative = _gridAltitudeRelativeFact.rawValue().toBool();
double triggerDistance = _cameraTriggerDistanceFact.rawValue().toDouble();
MissionItem* item = new MissionItem(seqNum++, // sequence number MissionItem* item = new MissionItem(seqNum++,
MAV_CMD_NAV_WAYPOINT, // MAV_CMD MAV_CMD_NAV_WAYPOINT,
_gridAltitudeRelativeFact.rawValue().toBool() ? MAV_FRAME_GLOBAL_RELATIVE_ALT : MAV_FRAME_GLOBAL, // MAV_FRAME altitudeRelative ? MAV_FRAME_GLOBAL_RELATIVE_ALT : MAV_FRAME_GLOBAL,
0.0, 0.0, 0.0, 0.0, // param 1-4 0.0, 0.0, 0.0, 0.0, // param 1-4 unused
coord.latitude(), coord.latitude(),
coord.longitude(), coord.longitude(),
altitude, altitude,
@ -823,27 +858,78 @@ void SurveyMissionItem::appendMissionItems(QList<MissionItem*>& items, QObject*
missionItemParent); missionItemParent);
items.append(item); items.append(item);
if (_cameraTriggerFact.rawValue().toBool() && i == 0) { if (cameraTrigger != CameraTriggerNone) {
// Turn on camera MissionItem* item = new MissionItem(seqNum++,
MissionItem* item = new MissionItem(seqNum++, // sequence number MAV_CMD_DO_SET_CAM_TRIGG_DIST,
MAV_CMD_DO_SET_CAM_TRIGG_DIST, // MAV_CMD MAV_FRAME_MISSION,
MAV_FRAME_MISSION, // MAV_FRAME cameraTrigger == CameraTriggerOn ? triggerDistance : 0,
_cameraTriggerDistanceFact.rawValue().toDouble(), // trigger distance 0, 0, 0, 0, 0, 0, // param 2-7 unused
0.0, 0.0, 0.0, 0.0, 0.0, 0.0, // param 2-7
true, // autoContinue true, // autoContinue
false, // isCurrentItem false, // isCurrentItem
missionItemParent); missionItemParent);
items.append(item); items.append(item);
} }
return seqNum;
} }
if (_cameraTriggerFact.rawValue().toBool()) { void SurveyMissionItem::appendMissionItems(QList<MissionItem*>& items, QObject* missionItemParent)
// Turn off camera {
MissionItem* item = new MissionItem(seqNum++, // sequence number int seqNum = _sequenceNumber;
MAV_CMD_DO_SET_CAM_TRIGG_DIST, // MAV_CMD bool hasTurnaround = _turnaroundDistFact.rawValue().toDouble() > 0;
MAV_FRAME_MISSION, // MAV_FRAME bool triggerCamera = _cameraTriggerFact.rawValue().toBool();
0.0, // trigger distance bool imagesEverywhere = triggerCamera && _cameraTriggerInTurnaroundFact.rawValue().toBool();
0.0, 0.0, 0.0, 0.0, 0.0, 0.0, // param 2-7
int i = 0;
while (i < _simpleGridPoints.count()) {
CameraTriggerCode cameraTrigger;
QGeoCoordinate coord = _simpleGridPoints[i].value<QGeoCoordinate>();
// Either waypoint entering polygon of turnaround point for start of new transect
cameraTrigger = imagesEverywhere ? (i == 0 ? CameraTriggerOn : CameraTriggerNone) : (hasTurnaround ? CameraTriggerNone : CameraTriggerOn);
seqNum = _appendWaypointToMission(items, seqNum, coord, cameraTrigger, missionItemParent);
if (hasTurnaround) {
// Waypoint entering the polygon
if (++i >= _simpleGridPoints.count()) {
qWarning() << "Bad grid generation";
break;
}
coord = _simpleGridPoints[i].value<QGeoCoordinate>();
cameraTrigger = imagesEverywhere ? CameraTriggerNone : CameraTriggerOn;
seqNum = _appendWaypointToMission(items, seqNum, coord, cameraTrigger, missionItemParent);
}
// Waypoint exiting polygon
if (++i >= _simpleGridPoints.count()) {
qWarning() << "Bad grid generation";
break;
}
coord = _simpleGridPoints[i].value<QGeoCoordinate>();
cameraTrigger = imagesEverywhere ? CameraTriggerNone : CameraTriggerOff;
seqNum = _appendWaypointToMission(items, seqNum, coord, cameraTrigger, missionItemParent);
if (hasTurnaround) {
// Waypoint at the end of transect
if (++i >= _simpleGridPoints.count()) {
qWarning() << "Bad grid generation";
break;
}
coord = _simpleGridPoints[i].value<QGeoCoordinate>();
cameraTrigger = CameraTriggerNone;
seqNum = _appendWaypointToMission(items, seqNum, coord, cameraTrigger, missionItemParent);
}
i++;
}
if (imagesEverywhere) {
// Turn off camera at end of survey
MissionItem* item = new MissionItem(seqNum++,
MAV_CMD_DO_SET_CAM_TRIGG_DIST,
MAV_FRAME_MISSION,
0.0, // trigger distance (off)
0, 0, 0, 0, 0, 0, // param 2-7 unused
true, // autoContinue true, // autoContinue
false, // isCurrentItem false, // isCurrentItem
missionItemParent); missionItemParent);
@ -883,3 +969,8 @@ void SurveyMissionItem::setMissionFlightStatus (MissionController::MissionFligh
emit timeBetweenShotsChanged(); emit timeBetweenShotsChanged();
} }
} }
void SurveyMissionItem::_setDirty(void)
{
setDirty(true);
}

25
src/MissionManager/SurveyMissionItem.h

@ -32,6 +32,8 @@ public:
Q_PROPERTY(Fact* turnaroundDist READ turnaroundDist CONSTANT) Q_PROPERTY(Fact* turnaroundDist READ turnaroundDist CONSTANT)
Q_PROPERTY(Fact* cameraTrigger READ cameraTrigger CONSTANT) Q_PROPERTY(Fact* cameraTrigger READ cameraTrigger CONSTANT)
Q_PROPERTY(Fact* cameraTriggerDistance READ cameraTriggerDistance CONSTANT) Q_PROPERTY(Fact* cameraTriggerDistance READ cameraTriggerDistance CONSTANT)
Q_PROPERTY(Fact* cameraTriggerInTurnaround READ cameraTriggerInTurnaround CONSTANT)
Q_PROPERTY(Fact* hoverAndCapture READ hoverAndCapture CONSTANT)
Q_PROPERTY(Fact* groundResolution READ groundResolution CONSTANT) Q_PROPERTY(Fact* groundResolution READ groundResolution CONSTANT)
Q_PROPERTY(Fact* frontalOverlap READ frontalOverlap CONSTANT) Q_PROPERTY(Fact* frontalOverlap READ frontalOverlap CONSTANT)
Q_PROPERTY(Fact* sideOverlap READ sideOverlap CONSTANT) Q_PROPERTY(Fact* sideOverlap READ sideOverlap CONSTANT)
@ -68,7 +70,7 @@ public:
QVariantList polygonPath (void) { return _polygonPath; } QVariantList polygonPath (void) { return _polygonPath; }
QmlObjectListModel* polygonModel(void) { return &_polygonModel; } QmlObjectListModel* polygonModel(void) { return &_polygonModel; }
QVariantList gridPoints (void) { return _gridPoints; } QVariantList gridPoints (void) { return _simpleGridPoints; }
Fact* manualGrid (void) { return &_manualGridFact; } Fact* manualGrid (void) { return &_manualGridFact; }
Fact* gridAltitude (void) { return &_gridAltitudeFact; } Fact* gridAltitude (void) { return &_gridAltitudeFact; }
@ -78,6 +80,8 @@ public:
Fact* turnaroundDist (void) { return &_turnaroundDistFact; } Fact* turnaroundDist (void) { return &_turnaroundDistFact; }
Fact* cameraTrigger (void) { return &_cameraTriggerFact; } Fact* cameraTrigger (void) { return &_cameraTriggerFact; }
Fact* cameraTriggerDistance (void) { return &_cameraTriggerDistanceFact; } Fact* cameraTriggerDistance (void) { return &_cameraTriggerDistanceFact; }
Fact* cameraTriggerInTurnaround (void) { return &_cameraTriggerInTurnaroundFact; }
Fact* hoverAndCapture (void) { return &_hoverAndCaptureFact; }
Fact* groundResolution (void) { return &_groundResolutionFact; } Fact* groundResolution (void) { return &_groundResolutionFact; }
Fact* frontalOverlap (void) { return &_frontalOverlapFact; } Fact* frontalOverlap (void) { return &_frontalOverlapFact; }
Fact* sideOverlap (void) { return &_sideOverlapFact; } Fact* sideOverlap (void) { return &_sideOverlapFact; }
@ -141,6 +145,8 @@ public:
static const char* gridSpacingName; static const char* gridSpacingName;
static const char* turnaroundDistName; static const char* turnaroundDistName;
static const char* cameraTriggerDistanceName; static const char* cameraTriggerDistanceName;
static const char* cameraTriggerInTurnaroundName;
static const char* hoverAndCaptureName;
static const char* groundResolutionName; static const char* groundResolutionName;
static const char* frontalOverlapName; static const char* frontalOverlapName;
static const char* sideOverlapName; static const char* sideOverlapName;
@ -166,14 +172,21 @@ signals:
private slots: private slots:
void _cameraTriggerChanged(void); void _cameraTriggerChanged(void);
void _setDirty(void);
private: private:
enum CameraTriggerCode {
CameraTriggerNone,
CameraTriggerOn,
CameraTriggerOff
};
void _clear(void); void _clear(void);
void _setExitCoordinate(const QGeoCoordinate& coordinate); void _setExitCoordinate(const QGeoCoordinate& coordinate);
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>& gridPoints); void _gridGenerator(const QList<QPointF>& polygonPoints, QList<QPointF>& simpleGridPoints, QList<QList<QPointF>>& gridSegments);
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);
@ -182,12 +195,14 @@ private:
void _setCameraShots(int cameraShots); void _setCameraShots(int cameraShots);
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 _sequenceNumber; int _sequenceNumber;
bool _dirty; bool _dirty;
QVariantList _polygonPath; QVariantList _polygonPath;
QmlObjectListModel _polygonModel; QmlObjectListModel _polygonModel;
QVariantList _gridPoints; QVariantList _simpleGridPoints; ///< Grid points for drawing simple grid visuals
QList<QList<QGeoCoordinate>> _gridSegments; ///< Internal grid line segments including grid exit and turnaround point
QGeoCoordinate _coordinate; QGeoCoordinate _coordinate;
QGeoCoordinate _exitCoordinate; QGeoCoordinate _exitCoordinate;
bool _cameraOrientationFixed; bool _cameraOrientationFixed;
@ -208,6 +223,8 @@ private:
SettingsFact _turnaroundDistFact; SettingsFact _turnaroundDistFact;
SettingsFact _cameraTriggerFact; SettingsFact _cameraTriggerFact;
SettingsFact _cameraTriggerDistanceFact; SettingsFact _cameraTriggerDistanceFact;
SettingsFact _cameraTriggerInTurnaroundFact;
SettingsFact _hoverAndCaptureFact;
SettingsFact _groundResolutionFact; SettingsFact _groundResolutionFact;
SettingsFact _frontalOverlapFact; SettingsFact _frontalOverlapFact;
SettingsFact _sideOverlapFact; SettingsFact _sideOverlapFact;
@ -229,6 +246,8 @@ private:
static const char* _jsonTurnaroundDistKey; static const char* _jsonTurnaroundDistKey;
static const char* _jsonCameraTriggerKey; static const char* _jsonCameraTriggerKey;
static const char* _jsonCameraTriggerDistanceKey; static const char* _jsonCameraTriggerDistanceKey;
static const char* _jsonCameraTriggerInTurnaroundKey;
static const char* _jsonHoverAndCaptureKey;
static const char* _jsonGroundResolutionKey; static const char* _jsonGroundResolutionKey;
static const char* _jsonFrontalOverlapKey; static const char* _jsonFrontalOverlapKey;
static const char* _jsonSideOverlapKey; static const char* _jsonSideOverlapKey;

86
src/PlanView/SurveyItemEditor.qml

@ -180,10 +180,17 @@ Rectangle {
spacing: _margin spacing: _margin
SectionHeader { SectionHeader {
id: cameraHeader
text: qsTr("Camera") text: qsTr("Camera")
showSpacer: false showSpacer: false
} }
Column {
anchors.left: parent.left
anchors.right: parent.right
spacing: _margin
visible: cameraHeader.checked
QGCComboBox { QGCComboBox {
id: gridTypeCombo id: gridTypeCombo
anchors.left: parent.left anchors.left: parent.left
@ -216,6 +223,32 @@ Rectangle {
} }
} }
RowLayout {
anchors.left: parent.left
anchors.right: parent.right
spacing: _margin
visible: missionItem.manualGrid.value == true
FactCheckBox {
anchors.baseline: cameraTriggerDistanceField.baseline
text: qsTr("Trigger Distance")
fact: missionItem.cameraTrigger
}
FactTextField {
id: cameraTriggerDistanceField
Layout.fillWidth: true
fact: missionItem.cameraTriggerDistance
enabled: missionItem.cameraTrigger.value
}
}
FactCheckBox {
text: qsTr("Hover and capture image")
fact: missionItem.hoverAndCapture
}
}
// Camera based grid ui // Camera based grid ui
Column { Column {
anchors.left: parent.left anchors.left: parent.left
@ -343,7 +376,10 @@ Rectangle {
} }
} }
SectionHeader { text: qsTr("Grid") } SectionHeader {
id: gridHeader
text: qsTr("Grid")
}
GridLayout { GridLayout {
anchors.left: parent.left anchors.left: parent.left
@ -351,6 +387,7 @@ Rectangle {
columnSpacing: _margin columnSpacing: _margin
rowSpacing: _margin rowSpacing: _margin
columns: 2 columns: 2
visible: gridHeader.checked
QGCLabel { text: qsTr("Angle") } QGCLabel { text: qsTr("Angle") }
FactTextField { FactTextField {
@ -403,13 +440,17 @@ Rectangle {
} }
// Manual grid ui // Manual grid ui
SectionHeader {
id: manualGridHeader
text: qsTr("Grid")
visible: gridTypeCombo.currentIndex == _gridTypeManual
}
Column { Column {
anchors.left: parent.left anchors.left: parent.left
anchors.right: parent.right anchors.right: parent.right
spacing: _margin spacing: _margin
visible: gridTypeCombo.currentIndex == _gridTypeManual visible: manualGridHeader.visible && manualGridHeader.checked
SectionHeader { text: qsTr("Grid") }
FactTextFieldGrid { FactTextFieldGrid {
anchors.left: parent.left anchors.left: parent.left
@ -420,50 +461,21 @@ Rectangle {
factLabels: [ qsTr("Angle"), qsTr("Spacing"), qsTr("Altitude"), qsTr("Turnaround dist")] factLabels: [ qsTr("Angle"), qsTr("Spacing"), qsTr("Altitude"), qsTr("Turnaround dist")]
} }
Item { height: _margin; width: 1; visible: !ScreenTools.isTinyScreen }
FactCheckBox { FactCheckBox {
anchors.left: parent.left anchors.left: parent.left
text: qsTr("Relative altitude") text: qsTr("Relative altitude")
fact: missionItem.gridAltitudeRelative fact: missionItem.gridAltitudeRelative
} }
Item { height: _sectionSpacer; width: 1; visible: !ScreenTools.isTinyScreen }
QGCLabel { text: qsTr("Camera") }
Rectangle {
anchors.left: parent.left
anchors.right: parent.right
height: 1
color: qgcPal.text
}
RowLayout {
anchors.left: parent.left
anchors.right: parent.right
spacing: _margin
FactCheckBox {
anchors.baseline: cameraTriggerDistanceField.baseline
text: qsTr("Trigger Distance")
fact: missionItem.cameraTrigger
}
FactTextField {
id: cameraTriggerDistanceField
Layout.fillWidth: true
fact: missionItem.cameraTriggerDistance
enabled: missionItem.cameraTrigger.value
}
}
} }
SectionHeader { text: qsTr("Statistics") } SectionHeader {
id: statsHeader
text: qsTr("Statistics") }
Grid { Grid {
columns: 2 columns: 2
columnSpacing: ScreenTools.defaultFontPixelWidth columnSpacing: ScreenTools.defaultFontPixelWidth
visible: statsHeader.checked
QGCLabel { text: qsTr("Survey area") } QGCLabel { text: qsTr("Survey area") }
QGCLabel { text: QGroundControl.squareMetersToAppSettingsAreaUnits(missionItem.coveredArea).toFixed(2) + " " + QGroundControl.appSettingsAreaUnitsString } QGCLabel { text: QGroundControl.squareMetersToAppSettingsAreaUnits(missionItem.coveredArea).toFixed(2) + " " + QGroundControl.appSettingsAreaUnitsString }

Loading…
Cancel
Save