Unverified Commit bc17fe15 authored by Don Gagne's avatar Don Gagne Committed by GitHub

Merge pull request #6404 from DonLakeFlyer/TransectStyle

Convert Survey complex item to use TransectStyleComplexItem
parents 215d3049 c8dadd86
......@@ -121,8 +121,8 @@ bool CameraSpec::load(const QJsonObject& json, QString& errorString)
_sensorWidthFact.setRawValue (json[_sensorWidthName].toDouble());
_sensorHeightFact.setRawValue (json[_sensorHeightName].toDouble());
_imageWidthFact.setRawValue (json[_imageWidthName].toDouble());
_imageHeightFact.setRawValue (json[_imageHeightName].toDouble());
_imageWidthFact.setRawValue (json[_imageWidthName].toInt());
_imageHeightFact.setRawValue (json[_imageHeightName].toInt());
_focalLengthFact.setRawValue (json[_focalLengthName].toDouble());
_landscapeFact.setRawValue (json[_landscapeName].toBool());
_fixedOrientationFact.setRawValue (json[_fixedOrientationName].toBool());
......
......@@ -64,10 +64,6 @@ void CorridorScanComplexItem::save(QJsonArray& planItems)
saveObject[corridorWidthName] = _corridorWidthFact.rawValue().toDouble();
saveObject[_jsonEntryPointKey] = _entryPoint;
QJsonObject cameraCalcObject;
_cameraCalc.save(cameraCalcObject);
saveObject[_jsonCameraCalcKey] = cameraCalcObject;
_corridorPolyline.saveToJson(saveObject);
planItems.append(saveObject);
......
......@@ -15,7 +15,6 @@
#include "QGCLoggingCategory.h"
#include "QGCMapPolyline.h"
#include "QGCMapPolygon.h"
#include "CameraCalc.h"
Q_DECLARE_LOGGING_CATEGORY(CorridorScanComplexItemLog)
......@@ -26,7 +25,6 @@ class CorridorScanComplexItem : public TransectStyleComplexItem
public:
CorridorScanComplexItem(Vehicle* vehicle, QObject* parent = NULL);
Q_PROPERTY(CameraCalc* cameraCalc READ cameraCalc CONSTANT)
Q_PROPERTY(QGCMapPolyline* corridorPolyline READ corridorPolyline CONSTANT)
Q_PROPERTY(Fact* corridorWidth READ corridorWidth CONSTANT)
......@@ -46,6 +44,9 @@ public:
void applyNewAltitude (double newAltitude) final;
// Overrides from VisualMissionionItem
QString commandDescription (void) const final { return tr("Corridor Scan"); }
QString commandName (void) const final { return tr("Corridor Scan"); }
QString abbreviation (void) const final { return tr("C"); }
bool readyForSave (void) const;
static const char* jsonComplexItemTypeValue;
......
......@@ -265,25 +265,21 @@ bool MissionController::_convertToMissionItems(QmlObjectListModel* visualMission
void MissionController::convertToKMLDocument(QDomDocument& document)
{
QJsonObject missionJson;
QmlObjectListModel* visualItems = new QmlObjectListModel();
QList<MissionItem*> missionItems;
QString error;
save(missionJson);
_loadItemsFromJson(missionJson, visualItems, error);
_convertToMissionItems(visualItems, missionItems, this);
if (missionItems.count() == 0) {
QObject* deleteParent = new QObject();
QList<MissionItem*> rgMissionItems;
_convertToMissionItems(_visualItems, rgMissionItems, deleteParent);
if (rgMissionItems.count() == 0) {
return;
}
float homeAltitude = missionJson[_jsonPlannedHomePositionKey].toArray()[2].toDouble();
const double homePositionAltitude = _settingsItem->coordinate().altitude();
QString coord;
QStringList coords;
// Drop home position
bool dropPoint = true;
for(const auto& item : missionItems) {
for(const auto& item : rgMissionItems) {
if(dropPoint) {
dropPoint = false;
continue;
......@@ -292,7 +288,7 @@ void MissionController::convertToKMLDocument(QDomDocument& document)
qgcApp()->toolbox()->missionCommandTree()->getUIInfo(_controllerVehicle, item->command());
if (uiInfo && uiInfo->specifiesCoordinate() && !uiInfo->isStandaloneCoordinate()) {
double amslAltitude = item->param7() + (item->frame() == MAV_FRAME_GLOBAL ? 0 : homeAltitude);
double amslAltitude = item->param7() + (item->frame() == MAV_FRAME_GLOBAL ? 0 : homePositionAltitude);
coord = QString::number(item->param6(),'f',7) \
+ "," \
+ QString::number(item->param5(),'f',7) \
......@@ -301,6 +297,9 @@ void MissionController::convertToKMLDocument(QDomDocument& document)
coords.append(coord);
}
}
deleteParent->deleteLater();
Kml kml;
kml.points(coords);
kml.save(document);
......
......@@ -22,389 +22,288 @@
QGC_LOGGING_CATEGORY(SurveyComplexItemLog, "SurveyComplexItemLog")
const char* SurveyComplexItem::jsonComplexItemTypeValue = "survey";
const char* SurveyComplexItem::_jsonGridObjectKey = "grid";
const char* SurveyComplexItem::_jsonGridAltitudeKey = "altitude";
const char* SurveyComplexItem::_jsonGridAltitudeRelativeKey = "relativeAltitude";
const char* SurveyComplexItem::_jsonGridAngleKey = "angle";
const char* SurveyComplexItem::_jsonGridSpacingKey = "spacing";
const char* SurveyComplexItem::_jsonGridEntryLocationKey = "entryLocation";
const char* SurveyComplexItem::_jsonTurnaroundDistKey = "turnAroundDistance";
const char* SurveyComplexItem::_jsonCameraTriggerDistanceKey = "cameraTriggerDistance";
const char* SurveyComplexItem::_jsonCameraTriggerInTurnaroundKey = "cameraTriggerInTurnaround";
const char* SurveyComplexItem::_jsonHoverAndCaptureKey = "hoverAndCapture";
const char* SurveyComplexItem::_jsonGroundResolutionKey = "groundResolution";
const char* SurveyComplexItem::_jsonFrontalOverlapKey = "imageFrontalOverlap";
const char* SurveyComplexItem::_jsonSideOverlapKey = "imageSideOverlap";
const char* SurveyComplexItem::_jsonCameraSensorWidthKey = "sensorWidth";
const char* SurveyComplexItem::_jsonCameraSensorHeightKey = "sensorHeight";
const char* SurveyComplexItem::_jsonCameraResolutionWidthKey = "resolutionWidth";
const char* SurveyComplexItem::_jsonCameraResolutionHeightKey = "resolutionHeight";
const char* SurveyComplexItem::_jsonCameraFocalLengthKey = "focalLength";
const char* SurveyComplexItem::_jsonCameraMinTriggerIntervalKey = "minTriggerInterval";
const char* SurveyComplexItem::_jsonCameraObjectKey = "camera";
const char* SurveyComplexItem::_jsonCameraNameKey = "name";
const char* SurveyComplexItem::_jsonManualGridKey = "manualGrid";
const char* SurveyComplexItem::_jsonCameraOrientationLandscapeKey = "orientationLandscape";
const char* SurveyComplexItem::_jsonFixedValueIsAltitudeKey = "fixedValueIsAltitude";
const char* SurveyComplexItem::_jsonRefly90DegreesKey = "refly90Degrees";
const char* SurveyComplexItem::jsonV3ComplexItemTypeValue = "survey";
const char* SurveyComplexItem::settingsGroup = "Survey";
const char* SurveyComplexItem::manualGridName = "ManualGrid";
const char* SurveyComplexItem::gridAltitudeName = "GridAltitude";
const char* SurveyComplexItem::gridAltitudeRelativeName = "GridAltitudeRelative";
const char* SurveyComplexItem::gridAngleName = "GridAngle";
const char* SurveyComplexItem::gridSpacingName = "GridSpacing";
const char* SurveyComplexItem::gridEntryLocationName = "GridEntryLocation";
const char* SurveyComplexItem::turnaroundDistName = "TurnaroundDist";
const char* SurveyComplexItem::cameraTriggerDistanceName = "CameraTriggerDistance";
const char* SurveyComplexItem::cameraTriggerInTurnaroundName = "CameraTriggerInTurnaround";
const char* SurveyComplexItem::hoverAndCaptureName = "HoverAndCapture";
const char* SurveyComplexItem::groundResolutionName = "GroundResolution";
const char* SurveyComplexItem::frontalOverlapName = "FrontalOverlap";
const char* SurveyComplexItem::sideOverlapName = "SideOverlap";
const char* SurveyComplexItem::cameraSensorWidthName = "CameraSensorWidth";
const char* SurveyComplexItem::cameraSensorHeightName = "CameraSensorHeight";
const char* SurveyComplexItem::cameraResolutionWidthName = "CameraResolutionWidth";
const char* SurveyComplexItem::cameraResolutionHeightName = "CameraResolutionHeight";
const char* SurveyComplexItem::cameraFocalLengthName = "CameraFocalLength";
const char* SurveyComplexItem::cameraTriggerName = "CameraTrigger";
const char* SurveyComplexItem::cameraOrientationLandscapeName = "CameraOrientationLandscape";
const char* SurveyComplexItem::fixedValueIsAltitudeName = "FixedValueIsAltitude";
const char* SurveyComplexItem::cameraName = "Camera";
const char* SurveyComplexItem::_jsonGridAngleKey = "angle";
const char* SurveyComplexItem::_jsonGridEntryLocationKey = "entryLocation";
const char* SurveyComplexItem::_jsonV3GridObjectKey = "grid";
const char* SurveyComplexItem::_jsonV3GridAltitudeKey = "altitude";
const char* SurveyComplexItem::_jsonV3GridAltitudeRelativeKey = "relativeAltitude";
const char* SurveyComplexItem::_jsonV3GridAngleKey = "angle";
const char* SurveyComplexItem::_jsonV3GridSpacingKey = "spacing";
const char* SurveyComplexItem::_jsonV3GridEntryLocationKey = "entryLocation";
const char* SurveyComplexItem::_jsonV3TurnaroundDistKey = "turnAroundDistance";
const char* SurveyComplexItem::_jsonV3CameraTriggerDistanceKey = "cameraTriggerDistance";
const char* SurveyComplexItem::_jsonV3CameraTriggerInTurnaroundKey = "cameraTriggerInTurnaround";
const char* SurveyComplexItem::_jsonV3HoverAndCaptureKey = "hoverAndCapture";
const char* SurveyComplexItem::_jsonV3GroundResolutionKey = "groundResolution";
const char* SurveyComplexItem::_jsonV3FrontalOverlapKey = "imageFrontalOverlap";
const char* SurveyComplexItem::_jsonV3SideOverlapKey = "imageSideOverlap";
const char* SurveyComplexItem::_jsonV3CameraSensorWidthKey = "sensorWidth";
const char* SurveyComplexItem::_jsonV3CameraSensorHeightKey = "sensorHeight";
const char* SurveyComplexItem::_jsonV3CameraResolutionWidthKey = "resolutionWidth";
const char* SurveyComplexItem::_jsonV3CameraResolutionHeightKey = "resolutionHeight";
const char* SurveyComplexItem::_jsonV3CameraFocalLengthKey = "focalLength";
const char* SurveyComplexItem::_jsonV3CameraMinTriggerIntervalKey = "minTriggerInterval";
const char* SurveyComplexItem::_jsonV3CameraObjectKey = "camera";
const char* SurveyComplexItem::_jsonV3CameraNameKey = "name";
const char* SurveyComplexItem::_jsonV3ManualGridKey = "manualGrid";
const char* SurveyComplexItem::_jsonV3CameraOrientationLandscapeKey = "orientationLandscape";
const char* SurveyComplexItem::_jsonV3FixedValueIsAltitudeKey = "fixedValueIsAltitude";
const char* SurveyComplexItem::_jsonV3Refly90DegreesKey = "refly90Degrees";
SurveyComplexItem::SurveyComplexItem(Vehicle* vehicle, QObject* parent)
: ComplexMissionItem(vehicle, parent)
, _sequenceNumber(0)
, _dirty(false)
, _mapPolygon(this)
, _cameraOrientationFixed(false)
, _missionCommandCount(0)
, _refly90Degrees(false)
, _additionalFlightDelaySeconds(0)
, _cameraMinTriggerInterval(0)
, _ignoreRecalc(false)
, _surveyDistance(0.0)
, _cameraShots(0)
, _coveredArea(0.0)
, _timeBetweenShots(0.0)
, _metaDataMap(FactMetaData::createMapFromJsonFile(QStringLiteral(":/json/Survey.SettingsGroup.json"), this))
, _manualGridFact (settingsGroup, _metaDataMap[manualGridName])
, _gridAltitudeFact (settingsGroup, _metaDataMap[gridAltitudeName])
, _gridAltitudeRelativeFact (settingsGroup, _metaDataMap[gridAltitudeRelativeName])
: TransectStyleComplexItem (vehicle, settingsGroup, parent)
, _metaDataMap (FactMetaData::createMapFromJsonFile(QStringLiteral(":/json/Survey.SettingsGroup.json"), this))
, _gridAngleFact (settingsGroup, _metaDataMap[gridAngleName])
, _gridSpacingFact (settingsGroup, _metaDataMap[gridSpacingName])
, _gridEntryLocationFact (settingsGroup, _metaDataMap[gridEntryLocationName])
, _turnaroundDistFact (settingsGroup, _metaDataMap[turnaroundDistName])
, _cameraTriggerDistanceFact (settingsGroup, _metaDataMap[cameraTriggerDistanceName])
, _cameraTriggerInTurnaroundFact (settingsGroup, _metaDataMap[cameraTriggerInTurnaroundName])
, _hoverAndCaptureFact (settingsGroup, _metaDataMap[hoverAndCaptureName])
, _groundResolutionFact (settingsGroup, _metaDataMap[groundResolutionName])
, _frontalOverlapFact (settingsGroup, _metaDataMap[frontalOverlapName])
, _sideOverlapFact (settingsGroup, _metaDataMap[sideOverlapName])
, _cameraSensorWidthFact (settingsGroup, _metaDataMap[cameraSensorWidthName])
, _cameraSensorHeightFact (settingsGroup, _metaDataMap[cameraSensorHeightName])
, _cameraResolutionWidthFact (settingsGroup, _metaDataMap[cameraResolutionWidthName])
, _cameraResolutionHeightFact (settingsGroup, _metaDataMap[cameraResolutionHeightName])
, _cameraFocalLengthFact (settingsGroup, _metaDataMap[cameraFocalLengthName])
, _cameraOrientationLandscapeFact (settingsGroup, _metaDataMap[cameraOrientationLandscapeName])
, _fixedValueIsAltitudeFact (settingsGroup, _metaDataMap[fixedValueIsAltitudeName])
, _cameraFact (settingsGroup, _metaDataMap[cameraName])
{
_editorQml = "qrc:/qml/SurveyItemEditor.qml";
// If the user hasn't changed turnaround from the default (which is a fixed wing default) and we are multi-rotor set the multi-rotor default.
// NULL check since object creation during unit testing passes NULL for vehicle
if (_vehicle && _vehicle->multiRotor() && _turnaroundDistFact.rawValue().toDouble() == _turnaroundDistFact.rawDefaultValue().toDouble()) {
if (_vehicle && _vehicle->multiRotor() && _turnAroundDistanceFact.rawValue().toDouble() == _turnAroundDistanceFact.rawDefaultValue().toDouble()) {
// Note this is set to 10 meters to work around a problem with PX4 Pro turnaround behavior. Don't change unless firmware gets better as well.
_turnaroundDistFact.setRawValue(10);
_turnAroundDistanceFact.setRawValue(10);
}
// We override the grid altitude to the mission default
if (_manualGridFact.rawValue().toBool() || _fixedValueIsAltitudeFact.rawValue().toBool()) {
_gridAltitudeFact.setRawValue(qgcApp()->toolbox()->settingsManager()->appSettings()->defaultMissionItemAltitude()->rawValue());
// We override the altitude to the mission default
if (_cameraCalc.isManualCamera() || !_cameraCalc.valueSetIsDistance()->rawValue().toBool()) {
_cameraCalc.distanceToSurface()->setRawValue(qgcApp()->toolbox()->settingsManager()->appSettings()->defaultMissionItemAltitude()->rawValue());
}
connect(&_gridSpacingFact, &Fact::valueChanged, this, &SurveyComplexItem::_generateGrid);
connect(&_gridAngleFact, &Fact::valueChanged, this, &SurveyComplexItem::_generateGrid);
connect(&_gridEntryLocationFact, &Fact::valueChanged, this, &SurveyComplexItem::_generateGrid);
connect(&_turnaroundDistFact, &Fact::valueChanged, this, &SurveyComplexItem::_generateGrid);
connect(&_cameraTriggerDistanceFact, &Fact::valueChanged, this, &SurveyComplexItem::_generateGrid);
connect(&_cameraTriggerInTurnaroundFact, &Fact::valueChanged, this, &SurveyComplexItem::_generateGrid);
connect(&_hoverAndCaptureFact, &Fact::valueChanged, this, &SurveyComplexItem::_generateGrid);
connect(this, &SurveyComplexItem::refly90DegreesChanged, this, &SurveyComplexItem::_generateGrid);
connect(&_gridAltitudeFact, &Fact::valueChanged, this, &SurveyComplexItem::_updateCoordinateAltitude);
connect(&_gridAltitudeRelativeFact, &Fact::valueChanged, this, &SurveyComplexItem::_setDirty);
// Signal to Qml when camera value changes so it can recalc
connect(&_groundResolutionFact, &Fact::valueChanged, this, &SurveyComplexItem::_cameraValueChanged);
connect(&_frontalOverlapFact, &Fact::valueChanged, this, &SurveyComplexItem::_cameraValueChanged);
connect(&_sideOverlapFact, &Fact::valueChanged, this, &SurveyComplexItem::_cameraValueChanged);
connect(&_cameraSensorWidthFact, &Fact::valueChanged, this, &SurveyComplexItem::_cameraValueChanged);
connect(&_cameraSensorHeightFact, &Fact::valueChanged, this, &SurveyComplexItem::_cameraValueChanged);
connect(&_cameraResolutionWidthFact, &Fact::valueChanged, this, &SurveyComplexItem::_cameraValueChanged);
connect(&_cameraResolutionHeightFact, &Fact::valueChanged, this, &SurveyComplexItem::_cameraValueChanged);
connect(&_cameraFocalLengthFact, &Fact::valueChanged, this, &SurveyComplexItem::_cameraValueChanged);
connect(&_cameraOrientationLandscapeFact, &Fact::valueChanged, this, &SurveyComplexItem::_cameraValueChanged);
connect(&_cameraTriggerDistanceFact, &Fact::valueChanged, this, &SurveyComplexItem::timeBetweenShotsChanged);
connect(&_mapPolygon, &QGCMapPolygon::dirtyChanged, this, &SurveyComplexItem::_polygonDirtyChanged);
connect(&_mapPolygon, &QGCMapPolygon::pathChanged, this, &SurveyComplexItem::_generateGrid);
}
void SurveyComplexItem::_setSurveyDistance(double surveyDistance)
{
if (!qFuzzyCompare(_surveyDistance, surveyDistance)) {
_surveyDistance = surveyDistance;
emit complexDistanceChanged();
}
}
connect(&_gridAngleFact, &Fact::valueChanged, this, &SurveyComplexItem::_setDirty);
connect(&_gridEntryLocationFact, &Fact::valueChanged, this, &SurveyComplexItem::_setDirty);
connect(this, &SurveyComplexItem::refly90DegreesChanged, this, &SurveyComplexItem::_setDirty);
void SurveyComplexItem::_setCameraShots(int cameraShots)
{
if (_cameraShots != cameraShots) {
_cameraShots = cameraShots;
emit cameraShotsChanged(this->cameraShots());
}
}
connect(&_gridAngleFact, &Fact::valueChanged, this, &SurveyComplexItem::_rebuildTransects);
connect(&_gridEntryLocationFact, &Fact::valueChanged, this, &SurveyComplexItem::_rebuildTransects);
connect(this, &SurveyComplexItem::refly90DegreesChanged, this, &SurveyComplexItem::_rebuildTransects);
void SurveyComplexItem::_setCoveredArea(double coveredArea)
{
if (!qFuzzyCompare(_coveredArea, coveredArea)) {
_coveredArea = coveredArea;
emit coveredAreaChanged(_coveredArea);
}
// FIXME: Shouldn't these be in TransectStyleComplexItem? They are also in CorridorScanComplexItem constructur
connect(&_cameraCalc, &CameraCalc::distanceToSurfaceRelativeChanged, this, &SurveyComplexItem::coordinateHasRelativeAltitudeChanged);
connect(&_cameraCalc, &CameraCalc::distanceToSurfaceRelativeChanged, this, &SurveyComplexItem::exitCoordinateHasRelativeAltitudeChanged);
}
void SurveyComplexItem::_clearInternal(void)
void SurveyComplexItem::save(QJsonArray& planItems)
{
// Bug workaround
while (_simpleGridPoints.count() > 1) {
_simpleGridPoints.takeLast();
}
emit gridPointsChanged();
_simpleGridPoints.clear();
_transectSegments.clear();
QJsonObject saveObject;
_missionCommandCount = 0;
_save(saveObject);
setDirty(true);
saveObject[JsonHelper::jsonVersionKey] = 4;
saveObject[VisualMissionItem::jsonTypeKey] = VisualMissionItem::jsonTypeComplexItemValue;
saveObject[ComplexMissionItem::jsonComplexItemTypeKey] = jsonComplexItemTypeValue;
saveObject[_jsonGridAngleKey] = _gridAngleFact.rawValue().toDouble();
saveObject[_jsonGridEntryLocationKey] = _gridEntryLocationFact.rawValue().toInt();
emit specifiesCoordinateChanged();
emit lastSequenceNumberChanged(lastSequenceNumber());
}
// Polygon shape
_surveyAreaPolygon.saveToJson(saveObject);
int SurveyComplexItem::lastSequenceNumber(void) const
{
return _sequenceNumber + _missionCommandCount;
planItems.append(saveObject);
}
void SurveyComplexItem::setCoordinate(const QGeoCoordinate& coordinate)
bool SurveyComplexItem::load(const QJsonObject& complexObject, int sequenceNumber, QString& errorString)
{
if (_coordinate != coordinate) {
_coordinate = coordinate;
emit coordinateChanged(_coordinate);
// We need to pull version first to determine what validation/conversion needs to be performed
QList<JsonHelper::KeyValidateInfo> versionKeyInfoList = {
{ JsonHelper::jsonVersionKey, QJsonValue::Double, true },
};
if (!JsonHelper::validateKeys(complexObject, versionKeyInfoList, errorString)) {
return false;
}
}
void SurveyComplexItem::setDirty(bool dirty)
{
if (_dirty != dirty) {
_dirty = dirty;
emit dirtyChanged(_dirty);
int version = complexObject[JsonHelper::jsonVersionKey].toInt();
if (version < 2 || version > 4) {
errorString = tr("Survey items do not support version %1").arg(version);
return false;
}
}
void SurveyComplexItem::save(QJsonArray& missionItems)
{
QJsonObject saveObject;
saveObject[JsonHelper::jsonVersionKey] = 3;
saveObject[VisualMissionItem::jsonTypeKey] = VisualMissionItem::jsonTypeComplexItemValue;
saveObject[ComplexMissionItem::jsonComplexItemTypeKey] = jsonComplexItemTypeValue;
saveObject[_jsonManualGridKey] = _manualGridFact.rawValue().toBool();
saveObject[_jsonFixedValueIsAltitudeKey] = _fixedValueIsAltitudeFact.rawValue().toBool();
saveObject[_jsonHoverAndCaptureKey] = _hoverAndCaptureFact.rawValue().toBool();
saveObject[_jsonRefly90DegreesKey] = _refly90Degrees;
saveObject[_jsonCameraTriggerDistanceKey] = _cameraTriggerDistanceFact.rawValue().toDouble();
saveObject[_jsonCameraTriggerInTurnaroundKey] = _cameraTriggerInTurnaroundFact.rawValue().toBool();
QJsonObject gridObject;
gridObject[_jsonGridAltitudeKey] = _gridAltitudeFact.rawValue().toDouble();
gridObject[_jsonGridAltitudeRelativeKey] = _gridAltitudeRelativeFact.rawValue().toBool();
gridObject[_jsonGridAngleKey] = _gridAngleFact.rawValue().toDouble();
gridObject[_jsonGridSpacingKey] = _gridSpacingFact.rawValue().toDouble();
gridObject[_jsonGridEntryLocationKey] = _gridEntryLocationFact.rawValue().toDouble();
gridObject[_jsonTurnaroundDistKey] = _turnaroundDistFact.rawValue().toDouble();
saveObject[_jsonGridObjectKey] = gridObject;
if (!_manualGridFact.rawValue().toBool()) {
QJsonObject cameraObject;
cameraObject[_jsonCameraNameKey] = _cameraFact.rawValue().toString();
cameraObject[_jsonCameraOrientationLandscapeKey] = _cameraOrientationLandscapeFact.rawValue().toBool();
cameraObject[_jsonCameraSensorWidthKey] = _cameraSensorWidthFact.rawValue().toDouble();
cameraObject[_jsonCameraSensorHeightKey] = _cameraSensorHeightFact.rawValue().toDouble();
cameraObject[_jsonCameraResolutionWidthKey] = _cameraResolutionWidthFact.rawValue().toDouble();
cameraObject[_jsonCameraResolutionHeightKey] = _cameraResolutionHeightFact.rawValue().toDouble();
cameraObject[_jsonCameraFocalLengthKey] = _cameraFocalLengthFact.rawValue().toDouble();
cameraObject[_jsonCameraMinTriggerIntervalKey] = _cameraMinTriggerInterval;
cameraObject[_jsonGroundResolutionKey] = _groundResolutionFact.rawValue().toDouble();
cameraObject[_jsonFrontalOverlapKey] = _frontalOverlapFact.rawValue().toInt();
cameraObject[_jsonSideOverlapKey] = _sideOverlapFact.rawValue().toInt();
saveObject[_jsonCameraObjectKey] = cameraObject;
if (version == 4) {
if (!_loadV4(complexObject, sequenceNumber, errorString)) {
return false;
}
} else {
// Must be v2 or v3
QJsonObject v3ComplexObject = complexObject;
if (version == 2) {
// Convert to v3
if (v3ComplexObject.contains(VisualMissionItem::jsonTypeKey) && v3ComplexObject[VisualMissionItem::jsonTypeKey].toString() == QStringLiteral("survey")) {
v3ComplexObject[VisualMissionItem::jsonTypeKey] = VisualMissionItem::jsonTypeComplexItemValue;
v3ComplexObject[ComplexMissionItem::jsonComplexItemTypeKey] = jsonComplexItemTypeValue;
}
}
if (!_loadV3(complexObject, sequenceNumber, errorString)) {
return false;
}
}
// Polygon shape
_mapPolygon.saveToJson(saveObject);
missionItems.append(saveObject);
}
_rebuildTransects();
void SurveyComplexItem::setSequenceNumber(int sequenceNumber)
{
if (_sequenceNumber != sequenceNumber) {
_sequenceNumber = sequenceNumber;
emit sequenceNumberChanged(sequenceNumber);
emit lastSequenceNumberChanged(lastSequenceNumber());
}
return true;
}
bool SurveyComplexItem::load(const QJsonObject& complexObject, int sequenceNumber, QString& errorString)
bool SurveyComplexItem::_loadV4(const QJsonObject& complexObject, int sequenceNumber, QString& errorString)
{
QJsonObject v2Object = complexObject;
// We need to pull version first to determine what validation/conversion needs to be performed.
QList<JsonHelper::KeyValidateInfo> versionKeyInfoList = {
{ JsonHelper::jsonVersionKey, QJsonValue::Double, true },
QList<JsonHelper::KeyValidateInfo> keyInfoList = {
{ VisualMissionItem::jsonTypeKey, QJsonValue::String, true },
{ ComplexMissionItem::jsonComplexItemTypeKey, QJsonValue::String, true },
{ _jsonGridEntryLocationKey, QJsonValue::Double, true },
{ _jsonGridAngleKey, QJsonValue::Double, true },
};
if (!JsonHelper::validateKeys(v2Object, versionKeyInfoList, errorString)) {
if (!JsonHelper::validateKeys(complexObject, keyInfoList, errorString)) {
return false;
}
int version = v2Object[JsonHelper::jsonVersionKey].toInt();
if (version != 2 && version != 3) {
errorString = tr("%1 does not support this version of survey items").arg(qgcApp()->applicationName());
QString itemType = complexObject[VisualMissionItem::jsonTypeKey].toString();
QString complexType = complexObject[ComplexMissionItem::jsonComplexItemTypeKey].toString();
if (itemType != VisualMissionItem::jsonTypeComplexItemValue || complexType != jsonComplexItemTypeValue) {
errorString = tr("%1 does not support loading this complex mission item type: %2:%3").arg(qgcApp()->applicationName()).arg(itemType).arg(complexType);
return false;
}
if (version == 2) {
// Convert to v3
if (v2Object.contains(VisualMissionItem::jsonTypeKey) && v2Object[VisualMissionItem::jsonTypeKey].toString() == QStringLiteral("survey")) {
v2Object[VisualMissionItem::jsonTypeKey] = VisualMissionItem::jsonTypeComplexItemValue;
v2Object[ComplexMissionItem::jsonComplexItemTypeKey] = jsonComplexItemTypeValue;
_ignoreRecalc = true;
setSequenceNumber(sequenceNumber);
if (!_surveyAreaPolygon.loadFromJson(complexObject, true /* required */, errorString)) {
_surveyAreaPolygon.clear();
return false;
}
if (!_load(complexObject, errorString)) {
_ignoreRecalc = false;
return false;
}
_gridAngleFact.setRawValue(complexObject[_jsonGridAngleKey].toDouble());
_gridEntryLocationFact.setRawValue(complexObject[_jsonGridEntryLocationKey].toInt());
_ignoreRecalc = false;
return true;
}
bool SurveyComplexItem::_loadV3(const QJsonObject& complexObject, int sequenceNumber, QString& errorString)
{
QList<JsonHelper::KeyValidateInfo> mainKeyInfoList = {
{ JsonHelper::jsonVersionKey, QJsonValue::Double, true },
{ VisualMissionItem::jsonTypeKey, QJsonValue::String, true },
{ ComplexMissionItem::jsonComplexItemTypeKey, QJsonValue::String, true },
{ QGCMapPolygon::jsonPolygonKey, QJsonValue::Array, true },
{ _jsonGridObjectKey, QJsonValue::Object, true },
{ _jsonCameraObjectKey, QJsonValue::Object, false },
{ _jsonCameraTriggerDistanceKey, QJsonValue::Double, true },
{ _jsonManualGridKey, QJsonValue::Bool, true },
{ _jsonFixedValueIsAltitudeKey, QJsonValue::Bool, true },
{ _jsonHoverAndCaptureKey, QJsonValue::Bool, false },
{ _jsonRefly90DegreesKey, QJsonValue::Bool, false },
{ _jsonCameraTriggerInTurnaroundKey, QJsonValue::Bool, false }, // Should really be required, but it was missing from initial code due to bug
{ _jsonV3GridObjectKey, QJsonValue::Object, true },
{ _jsonV3CameraObjectKey, QJsonValue::Object, false },
{ _jsonV3CameraTriggerDistanceKey, QJsonValue::Double, true },
{ _jsonV3ManualGridKey, QJsonValue::Bool, true },
{ _jsonV3FixedValueIsAltitudeKey, QJsonValue::Bool, true },
{ _jsonV3HoverAndCaptureKey, QJsonValue::Bool, false },
{ _jsonV3Refly90DegreesKey, QJsonValue::Bool, false },
{ _jsonV3CameraTriggerInTurnaroundKey, QJsonValue::Bool, false }, // Should really be required, but it was missing from initial code due to bug
};
if (!JsonHelper::validateKeys(v2Object, mainKeyInfoList, errorString)) {
if (!JsonHelper::validateKeys(complexObject, mainKeyInfoList, errorString)) {
return false;
}
QString itemType = v2Object[VisualMissionItem::jsonTypeKey].toString();
QString complexType = v2Object[ComplexMissionItem::jsonComplexItemTypeKey].toString();
if (itemType != VisualMissionItem::jsonTypeComplexItemValue || complexType != jsonComplexItemTypeValue) {
QString itemType = complexObject[VisualMissionItem::jsonTypeKey].toString();
QString complexType = complexObject[ComplexMissionItem::jsonComplexItemTypeKey].toString();
if (itemType != VisualMissionItem::jsonTypeComplexItemValue || complexType != jsonV3ComplexItemTypeValue) {
errorString = tr("%1 does not support loading this complex mission item type: %2:%3").arg(qgcApp()->applicationName()).arg(itemType).arg(complexType);
return false;
}
_ignoreRecalc = true;
_mapPolygon.clear();
setSequenceNumber(sequenceNumber);
_manualGridFact.setRawValue (v2Object[_jsonManualGridKey].toBool(true));
_fixedValueIsAltitudeFact.setRawValue (v2Object[_jsonFixedValueIsAltitudeKey].toBool(true));
_gridAltitudeRelativeFact.setRawValue (v2Object[_jsonGridAltitudeRelativeKey].toBool(true));
_hoverAndCaptureFact.setRawValue (v2Object[_jsonHoverAndCaptureKey].toBool(false));
_cameraTriggerInTurnaroundFact.setRawValue (v2Object[_jsonCameraTriggerInTurnaroundKey].toBool(true));
_hoverAndCaptureFact.setRawValue (complexObject[_jsonV3HoverAndCaptureKey].toBool(false));
_refly90DegreesFact.setRawValue (complexObject[_jsonV3Refly90DegreesKey].toBool(false));
_cameraTriggerInTurnAroundFact.setRawValue (complexObject[_jsonV3CameraTriggerInTurnaroundKey].toBool(true));
_refly90Degrees = v2Object[_jsonRefly90DegreesKey].toBool(false);
_cameraCalc.valueSetIsDistance()->setRawValue (complexObject[_jsonV3FixedValueIsAltitudeKey].toBool(true));
_cameraCalc.setDistanceToSurfaceRelative (complexObject[_jsonV3GridAltitudeRelativeKey].toBool(true));
bool manualGrid = complexObject[_jsonV3ManualGridKey].toBool(true);
QList<JsonHelper::KeyValidateInfo> gridKeyInfoList = {
{ _jsonGridAltitudeKey, QJsonValue::Double, true },
{ _jsonGridAltitudeRelativeKey, QJsonValue::Bool, true },
{ _jsonGridAngleKey, QJsonValue::Double, true },
{ _jsonGridSpacingKey, QJsonValue::Double, true },
{ _jsonGridEntryLocationKey, QJsonValue::Double, false },
{ _jsonTurnaroundDistKey, QJsonValue::Double, true },
{ _jsonV3GridAltitudeKey, QJsonValue::Double, true },
{ _jsonV3GridAltitudeRelativeKey, QJsonValue::Bool, true },
{ _jsonV3GridAngleKey, QJsonValue::Double, true },
{ _jsonV3GridSpacingKey, QJsonValue::Double, true },
{ _jsonV3GridEntryLocationKey, QJsonValue::Double, false },
{ _jsonV3TurnaroundDistKey, QJsonValue::Double, true },
};
QJsonObject gridObject = v2Object[_jsonGridObjectKey].toObject();
QJsonObject gridObject = complexObject[_jsonV3GridObjectKey].toObject();
if (!JsonHelper::validateKeys(gridObject, gridKeyInfoList, errorString)) {
_ignoreRecalc = false;
return false;
}
_gridAltitudeFact.setRawValue (gridObject[_jsonGridAltitudeKey].toDouble());
_gridAngleFact.setRawValue (gridObject[_jsonGridAngleKey].toDouble());
_gridSpacingFact.setRawValue (gridObject[_jsonGridSpacingKey].toDouble());
_turnaroundDistFact.setRawValue (gridObject[_jsonTurnaroundDistKey].toDouble());
_cameraTriggerDistanceFact.setRawValue (v2Object[_jsonCameraTriggerDistanceKey].toDouble());
if (gridObject.contains(_jsonGridEntryLocationKey)) {
_gridEntryLocationFact.setRawValue(gridObject[_jsonGridEntryLocationKey].toDouble());
_gridAngleFact.setRawValue (gridObject[_jsonV3GridAngleKey].toDouble());
_turnAroundDistanceFact.setRawValue (gridObject[_jsonV3TurnaroundDistKey].toDouble());
if (gridObject.contains(_jsonV3GridEntryLocationKey)) {
_gridEntryLocationFact.setRawValue(gridObject[_jsonV3GridEntryLocationKey].toDouble());
} else {
_gridEntryLocationFact.setRawValue(_gridEntryLocationFact.rawDefaultValue());
}
if (!_manualGridFact.rawValue().toBool()) {
if (!v2Object.contains(_jsonCameraObjectKey)) {
_cameraCalc.distanceToSurface()->setRawValue (gridObject[_jsonV3GridAltitudeKey].toDouble());
_cameraCalc.adjustedFootprintSide()->setRawValue (gridObject[_jsonV3GridSpacingKey].toDouble());
_cameraCalc.adjustedFootprintFrontal()->setRawValue (complexObject[_jsonV3CameraTriggerDistanceKey].toDouble());
if (manualGrid) {
_cameraCalc.setCameraName(_cameraCalc.manualCameraName());
} else {
if (!complexObject.contains(_jsonV3CameraObjectKey)) {
errorString = tr("%1 but %2 object is missing").arg("manualGrid = false").arg("camera");
_ignoreRecalc = false;
return false;
}
QJsonObject cameraObject = v2Object[_jsonCameraObjectKey].toObject();
QJsonObject cameraObject = complexObject[_jsonV3CameraObjectKey].toObject();
// Older code had typo on "imageSideOverlap" incorrectly being "imageSizeOverlap"
QString incorrectImageSideOverlap = "imageSizeOverlap";
if (cameraObject.contains(incorrectImageSideOverlap)) {
cameraObject[_jsonSideOverlapKey] = cameraObject[incorrectImageSideOverlap];
cameraObject[_jsonV3SideOverlapKey] = cameraObject[incorrectImageSideOverlap];
cameraObject.remove(incorrectImageSideOverlap);
}
QList<JsonHelper::KeyValidateInfo> cameraKeyInfoList = {
{ _jsonGroundResolutionKey, QJsonValue::Double, true },
{ _jsonFrontalOverlapKey, QJsonValue::Double, true },
{ _jsonSideOverlapKey, QJsonValue::Double, true },
{ _jsonCameraSensorWidthKey, QJsonValue::Double, true },
{ _jsonCameraSensorHeightKey, QJsonValue::Double, true },
{ _jsonCameraResolutionWidthKey, QJsonValue::Double, true },
{ _jsonCameraResolutionHeightKey, QJsonValue::Double, true },
{ _jsonCameraFocalLengthKey, QJsonValue::Double, true },
{ _jsonCameraNameKey, QJsonValue::String, true },
{ _jsonCameraOrientationLandscapeKey, QJsonValue::Bool, true },
{ _jsonCameraMinTriggerIntervalKey, QJsonValue::Double, false },
{ _jsonV3GroundResolutionKey, QJsonValue::Double, true },
{ _jsonV3FrontalOverlapKey, QJsonValue::Double, true },
{ _jsonV3SideOverlapKey, QJsonValue::Double, true },
{ _jsonV3CameraSensorWidthKey, QJsonValue::Double, true },
{ _jsonV3CameraSensorHeightKey, QJsonValue::Double, true },
{ _jsonV3CameraResolutionWidthKey, QJsonValue::Double, true },
{ _jsonV3CameraResolutionHeightKey, QJsonValue::Double, true },
{ _jsonV3CameraFocalLengthKey, QJsonValue::Double, true },
{ _jsonV3CameraNameKey, QJsonValue::String, true },
{ _jsonV3CameraOrientationLandscapeKey, QJsonValue::Bool, true },
{ _jsonV3CameraMinTriggerIntervalKey, QJsonValue::Double, false },
};
if (!JsonHelper::validateKeys(cameraObject, cameraKeyInfoList, errorString)) {
_ignoreRecalc = false;
return false;
}
_cameraFact.setRawValue(cameraObject[_jsonCameraNameKey].toString());
_cameraOrientationLandscapeFact.setRawValue(cameraObject[_jsonCameraOrientationLandscapeKey].toBool(true));
_groundResolutionFact.setRawValue (cameraObject[_jsonGroundResolutionKey].toDouble());
_frontalOverlapFact.setRawValue (cameraObject[_jsonFrontalOverlapKey].toInt());
_sideOverlapFact.setRawValue (cameraObject[_jsonSideOverlapKey].toInt());
_cameraSensorWidthFact.setRawValue (cameraObject[_jsonCameraSensorWidthKey].toDouble());
_cameraSensorHeightFact.setRawValue (cameraObject[_jsonCameraSensorHeightKey].toDouble());
_cameraResolutionWidthFact.setRawValue (cameraObject[_jsonCameraResolutionWidthKey].toDouble());
_cameraResolutionHeightFact.setRawValue (cameraObject[_jsonCameraResolutionHeightKey].toDouble());
_cameraFocalLengthFact.setRawValue (cameraObject[_jsonCameraFocalLengthKey].toDouble());
_cameraMinTriggerInterval = cameraObject[_jsonCameraMinTriggerIntervalKey].toDouble(0);
_cameraCalc.setCameraName (cameraObject[_jsonV3CameraNameKey].toString());
_cameraCalc.landscape()->setRawValue (cameraObject[_jsonV3CameraOrientationLandscapeKey].toBool(true));
_cameraCalc.frontalOverlap()->setRawValue (cameraObject[_jsonV3FrontalOverlapKey].toInt());
_cameraCalc.sideOverlap()->setRawValue (cameraObject[_jsonV3SideOverlapKey].toInt());
_cameraCalc.sensorWidth()->setRawValue (cameraObject[_jsonV3CameraSensorWidthKey].toDouble());
_cameraCalc.sensorHeight()->setRawValue (cameraObject[_jsonV3CameraSensorHeightKey].toDouble());
_cameraCalc.focalLength()->setRawValue (cameraObject[_jsonV3CameraFocalLengthKey].toDouble());
_cameraCalc.imageWidth()->setRawValue (cameraObject[_jsonV3CameraResolutionWidthKey].toInt());
_cameraCalc.imageHeight()->setRawValue (cameraObject[_jsonV3CameraResolutionHeightKey].toInt());
_cameraCalc.minTriggerInterval()->setRawValue (cameraObject[_jsonV3CameraMinTriggerIntervalKey].toDouble(0));
_cameraCalc.imageDensity()->setRawValue (cameraObject[_jsonV3GroundResolutionKey].toDouble());
_cameraCalc.fixedOrientation()->setRawValue (false);
}
// Polygon shape
......@@ -413,66 +312,17 @@ bool SurveyComplexItem::load(const QJsonObject& complexObject, int sequenceNumbe
/// @param required true: no polygon in object will generate error
/// @param errorString Error string if return is false
/// @return true: success, false: failure (errorString set)
if (!_mapPolygon.loadFromJson(v2Object, true /* required */, errorString)) {
_mapPolygon.clear();
if (!_surveyAreaPolygon.loadFromJson(complexObject, true /* required */, errorString)) {
_surveyAreaPolygon.clear();
_ignoreRecalc = false;
return false;
}
_ignoreRecalc = false;
_generateGrid();
return true;
}
double SurveyComplexItem::greatestDistanceTo(const QGeoCoordinate &other) const
{
double greatestDistance = 0.0;
for (int i=0; i<_simpleGridPoints.count(); i++) {
QGeoCoordinate currentCoord = _simpleGridPoints[i].value<QGeoCoordinate>();
double distance = currentCoord.distanceTo(other);
if (distance > greatestDistance) {
greatestDistance = distance;
}
}
return greatestDistance;
}
void SurveyComplexItem::_setExitCoordinate(const QGeoCoordinate& coordinate)
{
if (_exitCoordinate != coordinate) {
_exitCoordinate = coordinate;
emit exitCoordinateChanged(coordinate);
}
}
bool SurveyComplexItem::specifiesCoordinate(void) const
{
return _mapPolygon.count() > 2;
}
void _calcCameraShots()
{
}
void SurveyComplexItem::_convertTransectToGeo(const QList<QList<QPointF>>& transectSegmentsNED, const QGeoCoordinate& tangentOrigin, QList<QList<QGeoCoordinate>>& transectSegmentsGeo)
{
transectSegmentsGeo.clear();
for (int i=0; i<transectSegmentsNED.count(); i++) {
QList<QGeoCoordinate> transectCoords;
const QList<QPointF>& transectPoints = transectSegmentsNED[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);
}
transectSegmentsGeo.append(transectCoords);
}
}
/// Reverse the order of the transects. First transect becomes last and so forth.
void SurveyComplexItem::_reverseTransectOrder(QList<QList<QGeoCoordinate>>& transects)
{
......@@ -527,16 +377,6 @@ void SurveyComplexItem::_optimizeTransectsForShortestDistance(const QGeoCoordina
}
}
void SurveyComplexItem::_appendGridPointsFromTransects(QList<QList<QGeoCoordinate>>& rgTransectSegments)
{
qCDebug(SurveyComplexItemLog) << "Entry point _appendGridPointsFromTransects" << rgTransectSegments.first().first();
for (int i=0; i<rgTransectSegments.count(); i++) {
_simpleGridPoints.append(QVariant::fromValue(rgTransectSegments[i].first()));
_simpleGridPoints.append(QVariant::fromValue(rgTransectSegments[i].last()));
}
}
qreal SurveyComplexItem::_ccw(QPointF pt1, QPointF pt2, QPointF pt3)
{
return (pt2.x()-pt1.x())*(pt3.y()-pt1.y()) - (pt2.y()-pt1.y())*(pt3.x()-pt1.x());
......@@ -580,39 +420,18 @@ void SurveyComplexItem::_adjustTransectsToEntryPointLocation(QList<QList<QGeoCoo
}
if (reversePoints) {
qCDebug(SurveyComplexItemLog) << "Reverse Points";
qCDebug(SurveyComplexItemLog) << "_adjustTransectsToEntryPointLocation Reverse Points";
_reverseInternalTransectPoints(transects);
}
if (reverseTransects) {
qCDebug(SurveyComplexItemLog) << "Reverse Transects";
qCDebug(SurveyComplexItemLog) << "_adjustTransectsToEntryPointLocation Reverse Transects";
_reverseTransectOrder(transects);
}
qCDebug(SurveyComplexItemLog) << "Modified entry point" << transects.first().first();
qCDebug(SurveyComplexItemLog) << "_adjustTransectsToEntryPointLocation Modified entry point:entryLocation" << transects.first().first() << entryLocation;
}
int SurveyComplexItem::_calcMissionCommandCount(QList<QList<QGeoCoordinate>>& transectSegments)
{
int 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() && !_imagesEverywhere()) {
// Camera on/off at entry/exit of each transect
missionCommandCount += 2;
}
}
if (transectSegments.count() && _triggerCamera() && _imagesEverywhere()) {
// Camera on/off for entire survey
missionCommandCount += 2;
}
return missionCommandCount;
}
#if 0
void SurveyComplexItem::_generateGrid(void)
{
if (_ignoreRecalc) {
......@@ -712,15 +531,7 @@ void SurveyComplexItem::_generateGrid(void)
setDirty(true);
}
void SurveyComplexItem::_updateCoordinateAltitude(void)
{
_coordinate.setAltitude(_gridAltitudeFact.rawValue().toDouble());
_exitCoordinate.setAltitude(_gridAltitudeFact.rawValue().toDouble());
emit coordinateChanged(_coordinate);
emit exitCoordinateChanged(_exitCoordinate);
setDirty(true);
}
#endif
QPointF SurveyComplexItem::_rotatePoint(const QPointF& point, const QPointF& origin, double angle)
{
......@@ -803,9 +614,11 @@ void SurveyComplexItem::_intersectLinesWithPolygon(const QList<QLineF>& lineList
QPointF intersectPoint;
QLineF polygonLine = QLineF(polygon[j], polygon[j+1]);
if (line.intersect(polygonLine, &intersectPoint) == QLineF::BoundedIntersection) {
if (!intersections.contains(intersectPoint)) {
intersections.append(intersectPoint);
}
}
}
// We now have one or more intersection points all along the same line. Find the two
// which are furthest away from each other to form the transect.
......@@ -817,7 +630,7 @@ void SurveyComplexItem::_intersectLinesWithPolygon(const QList<QLineF>& lineList
for (int i=0; i<intersections.count(); i++) {
for (int j=0; j<intersections.count(); j++) {
QLineF lineTest(intersections[i], intersections[j]);
\
\
double newMaxDistance = lineTest.length();
if (newMaxDistance > currentMaxDistance) {
firstPoint = intersections[i];
......@@ -866,6 +679,7 @@ double SurveyComplexItem::_clampGridAngle90(double gridAngle)
return gridAngle;
}
#if 0
int SurveyComplexItem::_gridGenerator(const QList<QPointF>& polygonPoints, QList<QList<QPointF>>& transectSegments, bool refly)
{
int cameraShots = 0;
......@@ -999,7 +813,9 @@ int SurveyComplexItem::_gridGenerator(const QList<QPointF>& polygonPoints, QLis
return cameraShots;
}
#endif
#if 0
int SurveyComplexItem::_appendWaypointToMission(QList<MissionItem*>& items, int seqNum, QGeoCoordinate& coord, CameraTriggerCode cameraTrigger, QObject* missionItemParent)
{
double altitude = _gridAltitudeFact.rawValue().toDouble();
......@@ -1067,6 +883,7 @@ int SurveyComplexItem::_appendWaypointToMission(QList<MissionItem*>& items, int
return seqNum;
}
#endif
bool SurveyComplexItem::_nextTransectCoord(const QList<QGeoCoordinate>& transectPoints, int pointIndex, QGeoCoordinate& coord)
{
......@@ -1079,32 +896,133 @@ bool SurveyComplexItem::_nextTransectCoord(const QList<QGeoCoordinate>& transect
return true;
}
/// Appends the mission items for the survey
/// @param items Mission items are appended to this list
/// @param missionItemParent Parent object for newly created MissionItem objects
/// @param seqNum[in,out] Sequence number to start from
/// @param hasRefly true: misison has a refly section
/// @param buildRefly: true: build the refly section, false: build the first section
/// @return false: Generation failed
bool SurveyComplexItem::_appendMissionItemsWorker(QList<MissionItem*>& items, QObject* missionItemParent, int& seqNum, bool hasRefly, bool buildRefly)
void SurveyComplexItem::_buildAndAppendMissionItems(QList<MissionItem*>& items, QObject* missionItemParent)
{
qCDebug(SurveyComplexItemLog) << "_buildAndAppendMissionItems";
// Now build the mission items from the transect points
MissionItem* item;
int seqNum = _sequenceNumber;
bool imagesEverywhere = _cameraTriggerInTurnAroundFact.rawValue().toBool();
bool addTriggerAtBeginning = imagesEverywhere;
bool firstOverallPoint = true;
MAV_FRAME mavFrame = followTerrain() || !_cameraCalc.distanceToSurfaceRelative() ? MAV_FRAME_GLOBAL : MAV_FRAME_GLOBAL_RELATIVE_ALT;
foreach (const QList<TransectStyleComplexItem::CoordInfo_t>& transect, _transects) {
bool entryPoint = true;
foreach (const CoordInfo_t& transectCoordInfo, transect) {
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
transectCoordInfo.coord.latitude(),
transectCoordInfo.coord.longitude(),
transectCoordInfo.coord.altitude(),
true, // autoContinue
false, // isCurrentItem
missionItemParent);
items.append(item);
if (firstOverallPoint && addTriggerAtBeginning) {
// Start triggering
addTriggerAtBeginning = false;
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
missionItemParent);
items.append(item);
}
firstOverallPoint = false;
if (transectCoordInfo.coordType == TransectStyleComplexItem::CoordTypeSurveyEdge && !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
missionItemParent);
items.append(item);
} else {
// End of transect, stop triggering
item = new MissionItem(seqNum++,
MAV_CMD_DO_SET_CAM_TRIGG_DIST,
MAV_FRAME_MISSION,
0, // stop triggering
0, // shutter integration (ignore)
0, // trigger immediately when starting
0, 0, 0, 0, // param 4-7 unused
true, // autoContinue
false, // isCurrentItem
missionItemParent);
items.append(item);
}
entryPoint = !entryPoint;
}
}
}
if (imagesEverywhere) {
// Stop triggering
MissionItem* item = new MissionItem(seqNum++,
MAV_CMD_DO_SET_CAM_TRIGG_DIST,
MAV_FRAME_MISSION,
0, // stop triggering
0, // shutter integration (ignore)
0, // trigger immediately when starting
0, 0, 0, 0, // param 4-7 unused
true, // autoContinue
false, // isCurrentItem
missionItemParent);
items.append(item);
}
}
#if 0
bool SurveyComplexItem::_buildAndAppendMissionItems(QList<MissionItem*>& items, QObject* missionItemParent)
{
int seqNum = _sequenceNumber;
bool firstWaypointTrigger = false;
#if 1
// FIXME: Hack
bool hasRefly = false;
bool buildRefly = false;
#endif
qCDebug(SurveyComplexItemLog) << QStringLiteral("hasTurnaround(%1) triggerCamera(%2) hoverAndCapture(%3) imagesEverywhere(%4) hasRefly(%5) buildRefly(%6) ").arg(_hasTurnaround()).arg(_triggerCamera()).arg(_hoverAndCaptureEnabled()).arg(_imagesEverywhere()).arg(hasRefly).arg(buildRefly);
#if 0
QList<QList<QGeoCoordinate>>& transectSegments = buildRefly ? _reflyTransectSegments : _transectSegments;
#endif
if (!buildRefly && _imagesEverywhere()) {
firstWaypointTrigger = true;
}
for (int segmentIndex=0; segmentIndex<transectSegments.count(); segmentIndex++) {
foreach (const QList<TransectStyleComplexItem::CoordInfo_t>& transect, _transects) {
int pointIndex = 0;
QGeoCoordinate coord;
CameraTriggerCode cameraTrigger;
const QList<QGeoCoordinate>& segment = transectSegments[segmentIndex];
qCDebug(SurveyComplexItemLog) << "segment.count" << segment.count();
qCDebug(SurveyComplexItemLog) << "transect.count" << transect.count();
if (_hasTurnaround()) {
// Add entry turnaround point
......@@ -1172,58 +1090,35 @@ bool SurveyComplexItem::_appendMissionItemsWorker(QList<MissionItem*>& items, QO
return true;
}
#endif
#if 0
void SurveyComplexItem::appendMissionItems(QList<MissionItem*>& items, QObject* missionItemParent)
{
int seqNum = _sequenceNumber;
bool refly = refly90Degrees()->rawValue().toBool();
if (!_appendMissionItemsWorker(items, missionItemParent, seqNum, _refly90Degrees, false /* buildRefly */)) {
if (!_appendMissionItemsWorker(items, missionItemParent, seqNum, refly, false /* buildRefly */)) {
return;
}
if (_refly90Degrees) {
_appendMissionItemsWorker(items, missionItemParent, seqNum, _refly90Degrees, true /* buildRefly */);
}
}
int SurveyComplexItem::cameraShots(void) const
{
return _triggerCamera() ? _cameraShots : 0;
}
void SurveyComplexItem::_cameraValueChanged(void)
{
emit cameraValueChanged();
}
double SurveyComplexItem::timeBetweenShots(void) const
{
return _cruiseSpeed == 0 ? 0 : _triggerDistance() / _cruiseSpeed;
}
void SurveyComplexItem::setMissionFlightStatus(MissionController::MissionFlightStatus_t& missionFlightStatus)
{
ComplexMissionItem::setMissionFlightStatus(missionFlightStatus);
if (!qFuzzyCompare(_cruiseSpeed, missionFlightStatus.vehicleSpeed)) {
_cruiseSpeed = missionFlightStatus.vehicleSpeed;
emit timeBetweenShotsChanged();
if (refly) {
_appendMissionItemsWorker(items, missionItemParent, seqNum, refly, true /* buildRefly */);
}
}
#endif
void SurveyComplexItem::_setDirty(void)
bool SurveyComplexItem::_hasTurnaround(void) const
{
setDirty(true);
return _turnaroundDistance() > 0;
}
bool SurveyComplexItem::hoverAndCaptureAllowed(void) const
double SurveyComplexItem::_turnaroundDistance(void) const
{
return _vehicle->multiRotor() || _vehicle->vtol();
}
double SurveyComplexItem::_triggerDistance(void) const {
return _cameraTriggerDistanceFact.rawValue().toDouble();
return _turnAroundDistanceFact.rawValue().toDouble();
}
#if 0
bool SurveyComplexItem::_triggerCamera(void) const
{
return _triggerDistance() > 0;
......@@ -1238,34 +1133,392 @@ bool SurveyComplexItem::_hoverAndCaptureEnabled(void) const
{
return hoverAndCaptureAllowed() && !_imagesEverywhere() && _triggerCamera() && _hoverAndCaptureFact.rawValue().toBool();
}
#endif
bool SurveyComplexItem::_hasTurnaround(void) const
void SurveyComplexItem::_rebuildTransectsPhase1(void)
{
return _turnaroundDistance() > 0;
if (_ignoreRecalc) {
return;
}
// If the transects are getting rebuilt then any previously loaded mission items are now invalid
if (_loadedMissionItemsParent) {
_loadedMissionItems.clear();
_loadedMissionItemsParent->deleteLater();
_loadedMissionItemsParent = NULL;
}
_transects.clear();
_transectsPathHeightInfo.clear();
if (_surveyAreaPolygon.count() < 3) {
return;
}
QList<QList<QPointF>> transectSegments;
// Convert polygon to NED
QList<QPointF> polygonPoints;
QGeoCoordinate tangentOrigin = _surveyAreaPolygon.pathModel().value<QGCQGeoCoordinate*>(0)->coordinate();
qCDebug(SurveyComplexItemLog) << "_rebuildTransectsPhase1 Convert polygon to NED - _surveyAreaPolygon.count():tangentOrigin" << _surveyAreaPolygon.count() << tangentOrigin;
for (int i=0; i<_surveyAreaPolygon.count(); i++) {
double y, x, down;
QGeoCoordinate vertex = _surveyAreaPolygon.pathModel().value<QGCQGeoCoordinate*>(i)->coordinate();
if (i == 0) {
// This avoids a nan calculation that comes out of convertGeoToNed
x = y = 0;
} else {
convertGeoToNed(vertex, tangentOrigin, &y, &x, &down);
}
polygonPoints += QPointF(x, y);
qCDebug(SurveyComplexItemLog) << "_rebuildTransectsPhase1 vertex:x:y" << vertex << polygonPoints.last().x() << polygonPoints.last().y();
}
// Generate transects
bool refly = _refly90DegreesFact.rawValue().toBool();
double gridAngle = _gridAngleFact.rawValue().toDouble();
double gridSpacing = _cameraCalc.adjustedFootprintSide()->rawValue().toDouble();
gridAngle = _clampGridAngle90(gridAngle);
//gridAngle += refly ? 90 : 0;
qCDebug(SurveyComplexItemLog) << "_rebuildTransectsPhase1 Clamped grid angle" << gridAngle;
qCDebug(SurveyComplexItemLog) << "_rebuildTransectsPhase1 gridSpacing:gridAngle:refly" << gridSpacing << gridAngle << refly;
// Convert polygon to bounding rect
qCDebug(SurveyComplexItemLog) << "_rebuildTransectsPhase1 Polygon";
QPolygonF polygon;
for (int i=0; i<polygonPoints.count(); i++) {
qCDebug(SurveyComplexItemLog) << "Vertex" << polygonPoints[i];
polygon << polygonPoints[i];
}
polygon << polygonPoints[0];
QRectF boundingRect = polygon.boundingRect();
QPointF boundingCenter = boundingRect.center();
qCDebug(SurveyComplexItemLog) << "Bounding rect" << boundingRect.topLeft().x() << boundingRect.topLeft().y() << boundingRect.bottomRight().x() << boundingRect.bottomRight().y();
// Create set of rotated parallel lines within the expanded bounding rect. Make the lines larger than the
// bounding box to guarantee intersection.
QList<QLineF> lineList;
// Transects are generated to be as long as the largest width/height of the bounding rect plus some fudge factor.
// This way they will always be guaranteed to intersect with a polygon edge no matter what angle they are rotated to.
// They are initially generated with the transects flowing from west to east and then points within the transect north to south.
double maxWidth = qMax(boundingRect.width(), boundingRect.height()) + 2000.0;
double halfWidth = maxWidth / 2.0;
double transectX = boundingCenter.x() - halfWidth;
double transectXMax = transectX + maxWidth;
while (transectX < transectXMax) {
double transectYTop = boundingCenter.y() - halfWidth;
double transectYBottom = boundingCenter.y() + halfWidth;
lineList += QLineF(_rotatePoint(QPointF(transectX, transectYTop), boundingCenter, gridAngle), _rotatePoint(QPointF(transectX, transectYBottom), boundingCenter, gridAngle));
transectX += gridSpacing;
}
// Now intersect the lines with the polygon
QList<QLineF> intersectLines;
#if 1
_intersectLinesWithPolygon(lineList, polygon, intersectLines);
#else
// This is handy for debugging grid problems, not for release
intersectLines = lineList;
#endif
// Less than two transects intersected with the polygon:
// Create a single transect which goes through the center of the polygon
// Intersect it with the polygon
if (intersectLines.count() < 2) {
_surveyAreaPolygon.center();
QLineF firstLine = lineList.first();
QPointF lineCenter = firstLine.pointAt(0.5);
QPointF centerOffset = boundingCenter - lineCenter;
firstLine.translate(centerOffset);
lineList.clear();
lineList.append(firstLine);
intersectLines = lineList;
_intersectLinesWithPolygon(lineList, polygon, intersectLines);
}
// Make sure all lines are going the same direction. Polygon intersection leads to lines which
// can be in varied directions depending on the order of the intesecting sides.
QList<QLineF> resultLines;
_adjustLineDirection(intersectLines, resultLines);
// Convert from NED to Geo
QList<QList<QGeoCoordinate>> transects;
foreach (const QLineF& line, resultLines) {
QGeoCoordinate coord;
QList<QGeoCoordinate> transect;
convertNedToGeo(line.p1().y(), line.p1().x(), 0, tangentOrigin, &coord);
transect.append(coord);
convertNedToGeo(line.p2().y(), line.p2().x(), 0, tangentOrigin, &coord);
transect.append(coord);
transects.append(transect);
}
_adjustTransectsToEntryPointLocation(transects);
// Convert to CoordInfo transects
foreach (const QList<QGeoCoordinate>& transect, transects) {
QGeoCoordinate coord;
QList<TransectStyleComplexItem::CoordInfo_t> coordInfoTransect;
TransectStyleComplexItem::CoordInfo_t coordInfo;
coordInfo = { transect[0], CoordTypeSurveyEdge };
coordInfoTransect.append(coordInfo);
coordInfo = { transect[1], CoordTypeSurveyEdge };
coordInfoTransect.append(coordInfo);
// Extend the transect ends for turnaround
if (_hasTurnaround()) {
QGeoCoordinate turnaroundCoord;
double turnAroundDistance = _turnAroundDistanceFact.rawValue().toDouble();
double azimuth = transect[0].azimuthTo(transect[1]);
turnaroundCoord = transect[0].atDistanceAndAzimuth(-turnAroundDistance, azimuth);
turnaroundCoord.setAltitude(qQNaN());
TransectStyleComplexItem::CoordInfo_t coordInfo = { turnaroundCoord, CoordTypeTurnaround };
coordInfoTransect.prepend(coordInfo);
azimuth = transect.last().azimuthTo(transect[transect.count() - 2]);
turnaroundCoord = transect.last().atDistanceAndAzimuth(-turnAroundDistance, azimuth);
turnaroundCoord.setAltitude(qQNaN());
coordInfo = { turnaroundCoord, CoordTypeTurnaround };
coordInfoTransect.append(coordInfo);
}
_transects.append(coordInfoTransect);
}
// Adjust to lawnmower pattern
bool reverseVertices = false;
for (int i=0; i<_transects.count(); i++) {
// We must reverse the vertices for every other transect in order to make a lawnmower pattern
QList<TransectStyleComplexItem::CoordInfo_t> transectVertices = _transects[i];
if (reverseVertices) {
reverseVertices = false;
QList<TransectStyleComplexItem::CoordInfo_t> reversedVertices;
for (int j=transectVertices.count()-1; j>=0; j--) {
reversedVertices.append(transectVertices[j]);
}
transectVertices = reversedVertices;
} else {
reverseVertices = true;
}
_transects[i] = transectVertices;
}
#if 0
CorridorScan code
if (_ignoreRecalc) {
return;
}
// If the transects are getting rebuilt then any previsouly loaded mission items are now invalid
if (_loadedMissionItemsParent) {
_loadedMissionItems.clear();
_loadedMissionItemsParent->deleteLater();
_loadedMissionItemsParent = NULL;
}
_transects.clear();
_transectsPathHeightInfo.clear();
double transectSpacing = _cameraCalc.adjustedFootprintSide()->rawValue().toDouble();
double fullWidth = _corridorWidthFact.rawValue().toDouble();
double halfWidth = fullWidth / 2.0;
int transectCount = _transectCount();
double normalizedTransectPosition = transectSpacing / 2.0;
if (_corridorPolyline.count() >= 2) {
// First build up the transects all going the same direction
//qDebug() << "_rebuildTransectsPhase1";
for (int i=0; i<transectCount; i++) {
//qDebug() << "start transect";
double offsetDistance;
if (transectCount == 1) {
// Single transect is flown over scan line
offsetDistance = 0;
} else {
// Convert from normalized to absolute transect offset distance
offsetDistance = halfWidth - normalizedTransectPosition;
}
// Turn transect into CoordInfo transect
QList<TransectStyleComplexItem::CoordInfo_t> transect;
QList<QGeoCoordinate> transectCoords = _corridorPolyline.offsetPolyline(offsetDistance);
for (int j=1; j<transectCoords.count() - 1; j++) {
TransectStyleComplexItem::CoordInfo_t coordInfo = { transectCoords[j], CoordTypeInterior };
transect.append(coordInfo);
}
TransectStyleComplexItem::CoordInfo_t coordInfo = { transectCoords.first(), CoordTypeSurveyEdge };
transect.prepend(coordInfo);
coordInfo = { transectCoords.last(), CoordTypeSurveyEdge };
transect.append(coordInfo);
// Extend the transect ends for turnaround
if (_hasTurnaround()) {
QGeoCoordinate turnaroundCoord;
double turnAroundDistance = _turnAroundDistanceFact.rawValue().toDouble();
double azimuth = transectCoords[0].azimuthTo(transectCoords[1]);
turnaroundCoord = transectCoords[0].atDistanceAndAzimuth(-turnAroundDistance, azimuth);
turnaroundCoord.setAltitude(qQNaN());
TransectStyleComplexItem::CoordInfo_t coordInfo = { turnaroundCoord, CoordTypeTurnaround };
transect.prepend(coordInfo);
azimuth = transectCoords.last().azimuthTo(transectCoords[transectCoords.count() - 2]);
turnaroundCoord = transectCoords.last().atDistanceAndAzimuth(-turnAroundDistance, azimuth);
turnaroundCoord.setAltitude(qQNaN());
coordInfo = { turnaroundCoord, CoordTypeTurnaround };
transect.append(coordInfo);
}
#if 0
qDebug() << "transect debug";
foreach (const TransectStyleComplexItem::CoordInfo_t& coordInfo, transect) {
qDebug() << coordInfo.coordType;
}
#endif
_transects.append(transect);
normalizedTransectPosition += transectSpacing;
}
// Now deal with fixing up the entry point:
// 0: Leave alone
// 1: Start at same end, opposite side of center
// 2: Start at opposite end, same side
// 3: Start at opposite end, opposite side
bool reverseTransects = false;
bool reverseVertices = false;
switch (_entryPoint) {
case 0:
reverseTransects = false;
reverseVertices = false;
break;
case 1:
reverseTransects = true;
reverseVertices = false;
break;
case 2:
reverseTransects = false;
reverseVertices = true;
break;
case 3:
reverseTransects = true;
reverseVertices = true;
break;
}
if (reverseTransects) {
QList<QList<TransectStyleComplexItem::CoordInfo_t>> reversedTransects;
foreach (const QList<TransectStyleComplexItem::CoordInfo_t>& transect, _transects) {
reversedTransects.prepend(transect);
}
_transects = reversedTransects;
}
if (reverseVertices) {
for (int i=0; i<_transects.count(); i++) {
QList<TransectStyleComplexItem::CoordInfo_t> reversedVertices;
foreach (const TransectStyleComplexItem::CoordInfo_t& vertex, _transects[i]) {
reversedVertices.prepend(vertex);
}
_transects[i] = reversedVertices;
}
}
// Adjust to lawnmower pattern
reverseVertices = false;
for (int i=0; i<_transects.count(); i++) {
// We must reverse the vertices for every other transect in order to make a lawnmower pattern
QList<TransectStyleComplexItem::CoordInfo_t> transectVertices = _transects[i];
if (reverseVertices) {
reverseVertices = false;
QList<TransectStyleComplexItem::CoordInfo_t> reversedVertices;
for (int j=transectVertices.count()-1; j>=0; j--) {
reversedVertices.append(transectVertices[j]);
}
transectVertices = reversedVertices;
} else {
reverseVertices = true;
}
_transects[i] = transectVertices;
}
}
#endif
}
double SurveyComplexItem::_turnaroundDistance(void) const
void SurveyComplexItem::_rebuildTransectsPhase2(void)
{
return _turnaroundDistFact.rawValue().toDouble();
// Calculate distance flown for complex item
_complexDistance = 0;
for (int i=0; i<_visualTransectPoints.count() - 2; i++) {
_complexDistance += _visualTransectPoints[i].value<QGeoCoordinate>().distanceTo(_visualTransectPoints[i+1].value<QGeoCoordinate>());
}
#if 0
if (_cameraTriggerInTurnAroundFact.rawValue().toBool()) {
_cameraShots = qCeil(_complexDistance / _cameraCalc.adjustedFootprintFrontal()->rawValue().toDouble());
} else {
int singleTransectImageCount = qCeil(_corridorPolyline.length() / _cameraCalc.adjustedFootprintFrontal()->rawValue().toDouble());
_cameraShots = singleTransectImageCount * _transectCount();
}
#endif
_coordinate = _visualTransectPoints.count() ? _visualTransectPoints.first().value<QGeoCoordinate>() : QGeoCoordinate();
_exitCoordinate = _visualTransectPoints.count() ? _visualTransectPoints.last().value<QGeoCoordinate>() : QGeoCoordinate();
emit cameraShotsChanged();
emit complexDistanceChanged();
emit coordinateChanged(_coordinate);
emit exitCoordinateChanged(_exitCoordinate);
}
// FIXME: This same exact code is in Corridor Scan. Move to TransectStyleComplex?
void SurveyComplexItem::applyNewAltitude(double newAltitude)
{
_fixedValueIsAltitudeFact.setRawValue(true);
_gridAltitudeFact.setRawValue(newAltitude);
_cameraCalc.valueSetIsDistance()->setRawValue(true);
_cameraCalc.distanceToSurface()->setRawValue(newAltitude);
_cameraCalc.setDistanceToSurfaceRelative(true);
}
void SurveyComplexItem::setRefly90Degrees(bool refly90Degrees)
bool SurveyComplexItem::readyForSave(void) const
{
if (refly90Degrees != _refly90Degrees) {
_refly90Degrees = refly90Degrees;
emit refly90DegreesChanged(refly90Degrees);
return TransectStyleComplexItem::readyForSave();
}
void SurveyComplexItem::appendMissionItems(QList<MissionItem*>& items, QObject* missionItemParent)
{
if (_loadedMissionItems.count()) {
// We have mission items from the loaded plan, use those
_appendLoadedMissionItems(items, missionItemParent);
} else {
// Build the mission items on the fly
_buildAndAppendMissionItems(items, missionItemParent);
}
}
void SurveyComplexItem::_polygonDirtyChanged(bool dirty)
void SurveyComplexItem::_appendLoadedMissionItems(QList<MissionItem*>& items, QObject* missionItemParent)
{
if (dirty) {
setDirty(true);
qCDebug(SurveyComplexItemLog) << "_appendLoadedMissionItems";
int seqNum = _sequenceNumber;
foreach (const MissionItem* loadedMissionItem, _loadedMissionItems) {
MissionItem* item = new MissionItem(*loadedMissionItem, missionItemParent);
item->setSequenceNumber(seqNum++);
items.append(item);
}
}
......@@ -9,126 +9,41 @@
#pragma once
#include "ComplexMissionItem.h"
#include "TransectStyleComplexItem.h"
#include "MissionItem.h"
#include "SettingsFact.h"
#include "QGCLoggingCategory.h"
#include "QGCMapPolygon.h"
Q_DECLARE_LOGGING_CATEGORY(SurveyComplexItemLog)
class SurveyComplexItem : public ComplexMissionItem
class SurveyComplexItem : public TransectStyleComplexItem
{
Q_OBJECT
public:
SurveyComplexItem(Vehicle* vehicle, QObject* parent = NULL);
Q_PROPERTY(Fact* gridAltitude READ gridAltitude CONSTANT)
Q_PROPERTY(Fact* gridAltitudeRelative READ gridAltitudeRelative CONSTANT)
Q_PROPERTY(Fact* gridAngle READ gridAngle CONSTANT)
Q_PROPERTY(Fact* gridSpacing READ gridSpacing CONSTANT)
Q_PROPERTY(Fact* gridEntryLocation READ gridEntryLocation CONSTANT)
Q_PROPERTY(Fact* turnaroundDist READ turnaroundDist 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* frontalOverlap READ frontalOverlap CONSTANT)
Q_PROPERTY(Fact* sideOverlap READ sideOverlap CONSTANT)
Q_PROPERTY(Fact* cameraSensorWidth READ cameraSensorWidth CONSTANT)
Q_PROPERTY(Fact* cameraSensorHeight READ cameraSensorHeight CONSTANT)
Q_PROPERTY(Fact* cameraResolutionWidth READ cameraResolutionWidth CONSTANT)
Q_PROPERTY(Fact* cameraResolutionHeight READ cameraResolutionHeight CONSTANT)
Q_PROPERTY(Fact* cameraFocalLength READ cameraFocalLength CONSTANT)
Q_PROPERTY(Fact* cameraOrientationLandscape READ cameraOrientationLandscape CONSTANT)
Q_PROPERTY(Fact* fixedValueIsAltitude READ fixedValueIsAltitude CONSTANT)
Q_PROPERTY(Fact* manualGrid READ manualGrid CONSTANT)
Q_PROPERTY(Fact* camera READ camera CONSTANT)
Q_PROPERTY(bool cameraOrientationFixed MEMBER _cameraOrientationFixed NOTIFY cameraOrientationFixedChanged)
Q_PROPERTY(bool hoverAndCaptureAllowed READ hoverAndCaptureAllowed CONSTANT)
Q_PROPERTY(bool refly90Degrees READ refly90Degrees WRITE setRefly90Degrees NOTIFY refly90DegreesChanged)
Q_PROPERTY(double cameraMinTriggerInterval MEMBER _cameraMinTriggerInterval NOTIFY cameraMinTriggerIntervalChanged)
Q_PROPERTY(double timeBetweenShots READ timeBetweenShots NOTIFY timeBetweenShotsChanged)
Q_PROPERTY(QVariantList gridPoints READ gridPoints NOTIFY gridPointsChanged)
Q_PROPERTY(int cameraShots READ cameraShots NOTIFY cameraShotsChanged)
Q_PROPERTY(double coveredArea READ coveredArea NOTIFY coveredAreaChanged)
Q_PROPERTY(QGCMapPolygon* mapPolygon READ mapPolygon CONSTANT)
QVariantList gridPoints (void) { return _simpleGridPoints; }
Fact* manualGrid (void) { return &_manualGridFact; }
Fact* gridAltitude (void) { return &_gridAltitudeFact; }
Fact* gridAltitudeRelative (void) { return &_gridAltitudeRelativeFact; }
Fact* gridAngle (void) { return &_gridAngleFact; }
Fact* gridSpacing (void) { return &_gridSpacingFact; }
Fact* gridEntryLocation (void) { return &_gridEntryLocationFact; }
Fact* turnaroundDist (void) { return &_turnaroundDistFact; }
Fact* cameraTriggerDistance (void) { return &_cameraTriggerDistanceFact; }
Fact* cameraTriggerInTurnaround (void) { return &_cameraTriggerInTurnaroundFact; }
Fact* hoverAndCapture (void) { return &_hoverAndCaptureFact; }
Fact* groundResolution (void) { return &_groundResolutionFact; }
Fact* frontalOverlap (void) { return &_frontalOverlapFact; }
Fact* sideOverlap (void) { return &_sideOverlapFact; }
Fact* cameraSensorWidth (void) { return &_cameraSensorWidthFact; }
Fact* cameraSensorHeight (void) { return &_cameraSensorHeightFact; }
Fact* cameraResolutionWidth (void) { return &_cameraResolutionWidthFact; }
Fact* cameraResolutionHeight (void) { return &_cameraResolutionHeightFact; }
Fact* cameraFocalLength (void) { return &_cameraFocalLengthFact; }
Fact* cameraOrientationLandscape(void) { return &_cameraOrientationLandscapeFact; }
Fact* fixedValueIsAltitude (void) { return &_fixedValueIsAltitudeFact; }
Fact* camera (void) { return &_cameraFact; }
int cameraShots (void) const;
double coveredArea (void) const { return _coveredArea; }
double timeBetweenShots (void) const;
bool hoverAndCaptureAllowed (void) const;
bool refly90Degrees (void) const { return _refly90Degrees; }
QGCMapPolygon* mapPolygon (void) { return &_mapPolygon; }
void setRefly90Degrees(bool refly90Degrees);
// Overrides from ComplexMissionItem
double complexDistance (void) const final { return _surveyDistance; }
double additionalTimeDelay (void) const final { return _additionalFlightDelaySeconds; }
int lastSequenceNumber (void) const final;
bool load (const QJsonObject& complexObject, int sequenceNumber, QString& errorString) final;
double greatestDistanceTo (const QGeoCoordinate &other) const final;
QString mapVisualQML (void) const final { return QStringLiteral("SurveyMapVisual.qml"); }
// Overrides from VisualMissionItem
bool dirty (void) const final { return _dirty; }
bool isSimpleItem (void) const final { return false; }
bool isStandaloneCoordinate (void) const final { return false; }
bool specifiesCoordinate (void) const final;
bool specifiesAltitudeOnly (void) const final { return false; }
QString commandDescription (void) const final { return "Survey"; }
QString commandName (void) const final { return "Survey"; }
QString abbreviation (void) const final { return "S"; }
QGeoCoordinate coordinate (void) const final { return _coordinate; }
QGeoCoordinate exitCoordinate (void) const final { return _exitCoordinate; }
int sequenceNumber (void) const final { return _sequenceNumber; }
double specifiedFlightSpeed (void) final { return std::numeric_limits<double>::quiet_NaN(); }
double specifiedGimbalYaw (void) final { return std::numeric_limits<double>::quiet_NaN(); }
double specifiedGimbalPitch (void) final { return std::numeric_limits<double>::quiet_NaN(); }
// Overrides from TransectStyleComplexItem
void save (QJsonArray& planItems) final;
bool specifiesCoordinate (void) const final { return true; }
void appendMissionItems (QList<MissionItem*>& items, QObject* missionItemParent) final;
void setMissionFlightStatus (MissionController::MissionFlightStatus_t& missionFlightStatus) final;
void applyNewAltitude (double newAltitude) final;
bool coordinateHasRelativeAltitude (void) const final { return _gridAltitudeRelativeFact.rawValue().toBool(); }
bool exitCoordinateHasRelativeAltitude (void) const final { return _gridAltitudeRelativeFact.rawValue().toBool(); }
bool exitCoordinateSameAsEntry (void) const final { return false; }
void setDirty (bool dirty) final;
void setCoordinate (const QGeoCoordinate& coordinate) final;
void setSequenceNumber (int sequenceNumber) final;
void setTurnaroundDist (double dist) { _turnaroundDistFact.setRawValue(dist); }
void save (QJsonArray& missionItems) final;
// Overrides from VisualMissionionItem
QString commandDescription (void) const final { return tr("Survey"); }
QString commandName (void) const final { return tr("Survey"); }
QString abbreviation (void) const final { return tr("S"); }
bool readyForSave (void) const final;
// Must match json spec for GridEntryLocation
enum EntryLocation {
......@@ -139,46 +54,19 @@ public:
};
static const char* jsonComplexItemTypeValue;
static const char* settingsGroup;
static const char* manualGridName;
static const char* gridAltitudeName;
static const char* gridAltitudeRelativeName;
static const char* gridAngleName;
static const char* gridSpacingName;
static const char* gridEntryLocationName;
static const char* turnaroundDistName;
static const char* cameraTriggerDistanceName;
static const char* cameraTriggerInTurnaroundName;
static const char* hoverAndCaptureName;
static const char* groundResolutionName;
static const char* frontalOverlapName;
static const char* sideOverlapName;
static const char* cameraSensorWidthName;
static const char* cameraSensorHeightName;
static const char* cameraResolutionWidthName;
static const char* cameraResolutionHeightName;
static const char* cameraFocalLengthName;
static const char* cameraTriggerName;
static const char* cameraOrientationLandscapeName;
static const char* fixedValueIsAltitudeName;
static const char* cameraName;
static const char* jsonV3ComplexItemTypeValue;
signals:
void gridPointsChanged (void);
void cameraShotsChanged (int cameraShots);
void coveredAreaChanged (double coveredArea);
void cameraValueChanged (void);
void gridTypeChanged (QString gridType);
void timeBetweenShotsChanged (void);
void cameraOrientationFixedChanged (bool cameraOrientationFixed);
void refly90DegreesChanged (bool refly90Degrees);
void cameraMinTriggerIntervalChanged (double cameraMinTriggerInterval);
void refly90DegreesChanged(bool refly90Degrees);
private slots:
void _setDirty(void);
void _polygonDirtyChanged(bool dirty);
void _clearInternal(void);
// Overrides from TransectStyleComplexItem
void _rebuildTransectsPhase1(void) final;
void _rebuildTransectsPhase2(void) final;
private:
enum CameraTriggerCode {
......@@ -188,30 +76,14 @@ private:
CameraTriggerHoverAndCapture
};
void _setExitCoordinate(const QGeoCoordinate& coordinate);
void _generateGrid(void);
void _updateCoordinateAltitude(void);
int _gridGenerator(const QList<QPointF>& polygonPoints, QList<QList<QPointF>>& transectSegments, bool refly);
QPointF _rotatePoint(const QPointF& point, const QPointF& origin, double angle);
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 _adjustLineDirection(const QList<QLineF>& lineList, QList<QLineF>& resultLines);
void _setSurveyDistance(double surveyDistance);
void _setCameraShots(int cameraShots);
void _setCoveredArea(double coveredArea);
void _cameraValueChanged(void);
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;
void _convertTransectToGeo(const QList<QList<QPointF>>& transectSegmentsNED, const QGeoCoordinate& tangentOrigin, QList<QList<QGeoCoordinate>>& transectSegmentsGeo);
bool _appendMissionItemsWorker(QList<MissionItem*>& items, QObject* missionItemParent, int& seqNum, bool hasRefly, bool buildRefly);
void _optimizeTransectsForShortestDistance(const QGeoCoordinate& distanceCoord, QList<QList<QGeoCoordinate>>& transects);
void _appendGridPointsFromTransects(QList<QList<QGeoCoordinate>>& rgTransectSegments);
qreal _ccw(QPointF pt1, QPointF pt2, QPointF pt3);
qreal _dp(QPointF pt1, QPointF pt2);
void _swapPoints(QList<QPointF>& points, int index1, int index2);
......@@ -220,78 +92,50 @@ private:
void _adjustTransectsToEntryPointLocation(QList<QList<QGeoCoordinate>>& transects);
bool _gridAngleIsNorthSouthTransects();
double _clampGridAngle90(double gridAngle);
int _calcMissionCommandCount(QList<QList<QGeoCoordinate>>& transectSegments);
int _sequenceNumber;
bool _dirty;
QGCMapPolygon _mapPolygon;
QVariantList _simpleGridPoints; ///< Grid points for drawing simple grid visuals
QList<QList<QGeoCoordinate>> _transectSegments; ///< Internal transect segments including grid exit, turnaround and internal camera points
QList<QList<QGeoCoordinate>> _reflyTransectSegments; ///< Refly segments
QGeoCoordinate _coordinate;
QGeoCoordinate _exitCoordinate;
bool _cameraOrientationFixed;
int _missionCommandCount;
bool _refly90Degrees;
double _additionalFlightDelaySeconds;
double _cameraMinTriggerInterval;
bool _ignoreRecalc;
double _surveyDistance;
int _cameraShots;
double _coveredArea;
double _timeBetweenShots;
double _cruiseSpeed;
void _buildAndAppendMissionItems(QList<MissionItem*>& items, QObject* missionItemParent);
void _appendLoadedMissionItems (QList<MissionItem*>& items, QObject* missionItemParent);
bool _imagesEverywhere(void) const;
bool _triggerCamera(void) const;
bool _hasTurnaround(void) const;
double _turnaroundDistance(void) const;
bool _hoverAndCaptureEnabled(void) const;
bool _loadV3(const QJsonObject& complexObject, int sequenceNumber, QString& errorString);
bool _loadV4(const QJsonObject& complexObject, int sequenceNumber, QString& errorString);
QMap<QString, FactMetaData*> _metaDataMap;
SettingsFact _manualGridFact;
SettingsFact _gridAltitudeFact;
SettingsFact _gridAltitudeRelativeFact;
SettingsFact _gridAngleFact;
SettingsFact _gridSpacingFact;
SettingsFact _gridEntryLocationFact;
SettingsFact _turnaroundDistFact;
SettingsFact _cameraTriggerDistanceFact;
SettingsFact _cameraTriggerInTurnaroundFact;
SettingsFact _hoverAndCaptureFact;
SettingsFact _groundResolutionFact;
SettingsFact _frontalOverlapFact;
SettingsFact _sideOverlapFact;
SettingsFact _cameraSensorWidthFact;
SettingsFact _cameraSensorHeightFact;
SettingsFact _cameraResolutionWidthFact;
SettingsFact _cameraResolutionHeightFact;
SettingsFact _cameraFocalLengthFact;
SettingsFact _cameraOrientationLandscapeFact;
SettingsFact _fixedValueIsAltitudeFact;
SettingsFact _cameraFact;
static const char* _jsonGridObjectKey;
static const char* _jsonGridAltitudeKey;
static const char* _jsonGridAltitudeRelativeKey;
static const char* _jsonGridAngleKey;
static const char* _jsonGridSpacingKey;
static const char* _jsonGridEntryLocationKey;
static const char* _jsonTurnaroundDistKey;
static const char* _jsonCameraTriggerDistanceKey;
static const char* _jsonCameraTriggerInTurnaroundKey;
static const char* _jsonHoverAndCaptureKey;
static const char* _jsonGroundResolutionKey;
static const char* _jsonFrontalOverlapKey;
static const char* _jsonSideOverlapKey;
static const char* _jsonCameraSensorWidthKey;
static const char* _jsonCameraSensorHeightKey;
static const char* _jsonCameraResolutionWidthKey;
static const char* _jsonCameraResolutionHeightKey;
static const char* _jsonCameraFocalLengthKey;
static const char* _jsonCameraMinTriggerIntervalKey;
static const char* _jsonManualGridKey;
static const char* _jsonCameraObjectKey;
static const char* _jsonCameraNameKey;
static const char* _jsonCameraOrientationLandscapeKey;
static const char* _jsonFixedValueIsAltitudeKey;
static const char* _jsonRefly90DegreesKey;
static const char* _jsonV3GridObjectKey;
static const char* _jsonV3GridAltitudeKey;
static const char* _jsonV3GridAltitudeRelativeKey;
static const char* _jsonV3GridAngleKey;
static const char* _jsonV3GridSpacingKey;
static const char* _jsonV3GridEntryLocationKey;
static const char* _jsonV3TurnaroundDistKey;
static const char* _jsonV3CameraTriggerDistanceKey;
static const char* _jsonV3CameraTriggerInTurnaroundKey;
static const char* _jsonV3HoverAndCaptureKey;
static const char* _jsonV3GroundResolutionKey;
static const char* _jsonV3FrontalOverlapKey;
static const char* _jsonV3SideOverlapKey;
static const char* _jsonV3CameraSensorWidthKey;
static const char* _jsonV3CameraSensorHeightKey;
static const char* _jsonV3CameraResolutionWidthKey;
static const char* _jsonV3CameraResolutionHeightKey;
static const char* _jsonV3CameraFocalLengthKey;
static const char* _jsonV3CameraMinTriggerIntervalKey;
static const char* _jsonV3ManualGridKey;
static const char* _jsonV3CameraObjectKey;
static const char* _jsonV3CameraNameKey;
static const char* _jsonV3CameraOrientationLandscapeKey;
static const char* _jsonV3FixedValueIsAltitudeKey;
static const char* _jsonV3Refly90DegreesKey;
static const int _hoverAndCaptureDelaySeconds = 4;
};
......@@ -21,21 +21,18 @@ void SurveyComplexItemTest::init(void)
{
UnitTest::init();
_rgSurveySignals[gridPointsChangedIndex] = SIGNAL(gridPointsChanged());
_rgSurveySignals[cameraShotsChangedIndex] = SIGNAL(cameraShotsChanged(int));
_rgSurveySignals[coveredAreaChangedIndex] = SIGNAL(coveredAreaChanged(double));
_rgSurveySignals[cameraValueChangedIndex] = SIGNAL(cameraValueChanged());
_rgSurveySignals[gridTypeChangedIndex] = SIGNAL(gridTypeChanged(QString));
_rgSurveySignals[timeBetweenShotsChangedIndex] = SIGNAL(timeBetweenShotsChanged());
_rgSurveySignals[cameraOrientationFixedChangedIndex] = SIGNAL(cameraOrientationFixedChanged(bool));
_rgSurveySignals[refly90DegreesChangedIndex] = SIGNAL(refly90DegreesChanged(bool));
_rgSurveySignals[dirtyChangedIndex] = SIGNAL(dirtyChanged(bool));
_rgSurveySignals[surveyVisualTransectPointsChangedIndex] = SIGNAL(visualTransectPointsChanged());
_rgSurveySignals[surveyCameraShotsChangedIndex] = SIGNAL(cameraShotsChanged());
_rgSurveySignals[surveyCoveredAreaChangedIndex] = SIGNAL(coveredAreaChanged());
_rgSurveySignals[surveyTimeBetweenShotsChangedIndex] = SIGNAL(timeBetweenShotsChanged());
_rgSurveySignals[surveyRefly90DegreesChangedIndex] = SIGNAL(refly90DegreesChanged(bool));
_rgSurveySignals[surveyDirtyChangedIndex] = SIGNAL(dirtyChanged(bool));
_offlineVehicle = new Vehicle(MAV_AUTOPILOT_PX4, MAV_TYPE_QUADROTOR, qgcApp()->toolbox()->firmwarePluginManager(), this);
_surveyItem = new SurveyComplexItem(_offlineVehicle, this);
_surveyItem->setTurnaroundDist(0); // Unit test written for no turnaround distance
_surveyItem->turnAroundDistance()->setRawValue(0); // Unit test written for no turnaround distance
_surveyItem->setDirty(false);
_mapPolygon = _surveyItem->mapPolygon();
_mapPolygon = _surveyItem->surveyAreaPolygon();
// It's important to check that the right signals are emitted at the right time since that drives ui change.
// It's also important to check that things are not being over-signalled when they should not be, since that can lead
......@@ -62,20 +59,19 @@ void SurveyComplexItemTest::_testDirty(void)
_surveyItem->setDirty(true);
QVERIFY(_surveyItem->dirty());
QVERIFY(_multiSpy->checkOnlySignalByMask(dirtyChangedMask));
QVERIFY(_multiSpy->pullBoolFromSignalIndex(dirtyChangedIndex));
QVERIFY(_multiSpy->checkOnlySignalByMask(surveyDirtyChangedMask));
QVERIFY(_multiSpy->pullBoolFromSignalIndex(surveyDirtyChangedIndex));
_multiSpy->clearAllSignals();
_surveyItem->setDirty(false);
QVERIFY(!_surveyItem->dirty());
QVERIFY(_multiSpy->checkOnlySignalByMask(dirtyChangedMask));
QVERIFY(!_multiSpy->pullBoolFromSignalIndex(dirtyChangedIndex));
QVERIFY(_multiSpy->checkOnlySignalByMask(surveyDirtyChangedMask));
QVERIFY(!_multiSpy->pullBoolFromSignalIndex(surveyDirtyChangedIndex));
_multiSpy->clearAllSignals();
// These facts should set dirty when changed
QList<Fact*> rgFacts;
rgFacts << _surveyItem->gridAltitude() << _surveyItem->gridAngle() << _surveyItem->gridSpacing() << _surveyItem->turnaroundDist() << _surveyItem->cameraTriggerDistance() <<
_surveyItem->gridAltitudeRelative() << _surveyItem->cameraTriggerInTurnaround() << _surveyItem->hoverAndCapture();
rgFacts << _surveyItem->gridAngle() << _surveyItem->gridEntryLocation();
foreach(Fact* fact, rgFacts) {
qDebug() << fact->name();
QVERIFY(!_surveyItem->dirty());
......@@ -84,101 +80,12 @@ void SurveyComplexItemTest::_testDirty(void)
} else {
fact->setRawValue(fact->rawValue().toDouble() + 1);
}
QVERIFY(_multiSpy->checkSignalByMask(dirtyChangedMask));
QVERIFY(_multiSpy->pullBoolFromSignalIndex(dirtyChangedIndex));
QVERIFY(_multiSpy->checkSignalByMask(surveyDirtyChangedMask));
QVERIFY(_multiSpy->pullBoolFromSignalIndex(surveyDirtyChangedIndex));
_surveyItem->setDirty(false);
_multiSpy->clearAllSignals();
}
rgFacts.clear();
// These facts should not change dirty bit
rgFacts << _surveyItem->groundResolution() << _surveyItem->frontalOverlap() << _surveyItem->sideOverlap() << _surveyItem->cameraSensorWidth() << _surveyItem->cameraSensorHeight() <<
_surveyItem->cameraResolutionWidth() << _surveyItem->cameraResolutionHeight() << _surveyItem->cameraFocalLength() << _surveyItem->cameraOrientationLandscape() <<
_surveyItem->fixedValueIsAltitude() << _surveyItem->camera() << _surveyItem->manualGrid();
foreach(Fact* fact, rgFacts) {
qDebug() << fact->name();
QVERIFY(!_surveyItem->dirty());
if (fact->typeIsBool()) {
fact->setRawValue(!fact->rawValue().toBool());
} else {
fact->setRawValue(fact->rawValue().toDouble() + 1);
}
QVERIFY(_multiSpy->checkNoSignalByMask(dirtyChangedMask));
QVERIFY(!_surveyItem->dirty());
_multiSpy->clearAllSignals();
}
rgFacts.clear();
}
void SurveyComplexItemTest::_testCameraValueChanged(void)
{
// These facts should trigger cameraValueChanged when changed
QList<Fact*> rgFacts;
rgFacts << _surveyItem->groundResolution() << _surveyItem->frontalOverlap() << _surveyItem->sideOverlap() << _surveyItem->cameraSensorWidth() << _surveyItem->cameraSensorHeight() <<
_surveyItem->cameraResolutionWidth() << _surveyItem->cameraResolutionHeight() << _surveyItem->cameraFocalLength() << _surveyItem->cameraOrientationLandscape();
foreach(Fact* fact, rgFacts) {
qDebug() << fact->name();
if (fact->typeIsBool()) {
fact->setRawValue(!fact->rawValue().toBool());
} else {
fact->setRawValue(fact->rawValue().toDouble() + 1);
}
QVERIFY(_multiSpy->checkSignalByMask(cameraValueChangedMask));
_multiSpy->clearAllSignals();
}
rgFacts.clear();
// These facts should not trigger cameraValueChanged
rgFacts << _surveyItem->gridAltitude() << _surveyItem->gridAngle() << _surveyItem->gridSpacing() << _surveyItem->turnaroundDist() << _surveyItem->cameraTriggerDistance() <<
_surveyItem->gridAltitudeRelative() << _surveyItem->cameraTriggerInTurnaround() << _surveyItem->hoverAndCapture() <<
_surveyItem->fixedValueIsAltitude() << _surveyItem->camera() << _surveyItem->manualGrid();
foreach(Fact* fact, rgFacts) {
qDebug() << fact->name();
if (fact->typeIsBool()) {
fact->setRawValue(!fact->rawValue().toBool());
} else {
fact->setRawValue(fact->rawValue().toDouble() + 1);
}
QVERIFY(_multiSpy->checkNoSignalByMask(cameraValueChangedMask));
_multiSpy->clearAllSignals();
}
rgFacts.clear();
}
void SurveyComplexItemTest::_testCameraTrigger(void)
{
#if 0
QCOMPARE(_surveyItem->property("cameraTrigger").toBool(), true);
// Set up a grid
for (int i=0; i<3; i++) {
_mapPolygon->appendVertex(_polyPoints[i]);
}
_surveyItem->setDirty(false);
_multiSpy->clearAllSignals();
int lastSeq = _surveyItem->lastSequenceNumber();
QVERIFY(lastSeq > 0);
// Turning off camera triggering should remove two camera trigger mission items, this should trigger:
// lastSequenceNumberChanged
// dirtyChanged
_surveyItem->setProperty("cameraTrigger", false);
QVERIFY(_multiSpy->checkOnlySignalByMask(lastSequenceNumberChangedMask | dirtyChangedMask | cameraTriggerChangedMask));
QCOMPARE(_multiSpy->pullIntFromSignalIndex(lastSequenceNumberChangedIndex), lastSeq - 2);
_surveyItem->setDirty(false);
_multiSpy->clearAllSignals();
// Turn on camera triggering and make sure things go back to previous count
_surveyItem->setProperty("cameraTrigger", true);
QVERIFY(_multiSpy->checkOnlySignalByMask(lastSequenceNumberChangedMask | dirtyChangedMask | cameraTriggerChangedMask));
QCOMPARE(_multiSpy->pullIntFromSignalIndex(lastSequenceNumberChangedIndex), lastSeq);
#endif
}
// Clamp expected grid angle from 0<->180. We don't care about opposite angles like 90/270
......@@ -215,7 +122,7 @@ void SurveyComplexItemTest::_testGridAngle(void)
for (double gridAngle=-360.0; gridAngle<=360.0; gridAngle++) {
_surveyItem->gridAngle()->setRawValue(gridAngle);
QVariantList gridPoints = _surveyItem->gridPoints();
QVariantList gridPoints = _surveyItem->visualTransectPoints();
QGeoCoordinate firstTransectEntry = gridPoints[0].value<QGeoCoordinate>();
QGeoCoordinate firstTransectExit = gridPoints[1].value<QGeoCoordinate>();
double azimuth = firstTransectEntry.azimuthTo(firstTransectExit);
......@@ -258,30 +165,30 @@ void SurveyComplexItemTest::_testItemCount(void)
_setPolygon();
_surveyItem->hoverAndCapture()->setRawValue(false);
_surveyItem->cameraTriggerInTurnaround()->setRawValue(false);
_surveyItem->setRefly90Degrees(false);
_surveyItem->cameraTriggerInTurnAround()->setRawValue(false);
_surveyItem->refly90Degrees()->setRawValue(false);
_surveyItem->appendMissionItems(items, this);
QCOMPARE(items.count(), _surveyItem->lastSequenceNumber());
QCOMPARE(items.count() - 1, _surveyItem->lastSequenceNumber());
items.clear();
_surveyItem->hoverAndCapture()->setRawValue(false);
_surveyItem->cameraTriggerInTurnaround()->setRawValue(true);
_surveyItem->setRefly90Degrees(false);
_surveyItem->cameraTriggerInTurnAround()->setRawValue(true);
_surveyItem->refly90Degrees()->setRawValue(false);
_surveyItem->appendMissionItems(items, this);
QCOMPARE(items.count(), _surveyItem->lastSequenceNumber());
QCOMPARE(items.count() - 1, _surveyItem->lastSequenceNumber());
items.clear();
_surveyItem->hoverAndCapture()->setRawValue(true);
_surveyItem->cameraTriggerInTurnaround()->setRawValue(false);
_surveyItem->setRefly90Degrees(false);
_surveyItem->cameraTriggerInTurnAround()->setRawValue(false);
_surveyItem->refly90Degrees()->setRawValue(false);
_surveyItem->appendMissionItems(items, this);
QCOMPARE(items.count(), _surveyItem->lastSequenceNumber());
QCOMPARE(items.count() - 1, _surveyItem->lastSequenceNumber());
items.clear();
_surveyItem->hoverAndCapture()->setRawValue(true);
_surveyItem->cameraTriggerInTurnaround()->setRawValue(false);
_surveyItem->setRefly90Degrees(true);
_surveyItem->cameraTriggerInTurnAround()->setRawValue(false);
_surveyItem->refly90Degrees()->setRawValue(true);
_surveyItem->appendMissionItems(items, this);
QCOMPARE(items.count(), _surveyItem->lastSequenceNumber());
QCOMPARE(items.count() - 1, _surveyItem->lastSequenceNumber());
items.clear();
}
......@@ -30,42 +30,37 @@ protected:
private slots:
void _testDirty(void);
void _testCameraValueChanged(void);
void _testCameraTrigger(void);
void _testGridAngle(void);
void _testEntryLocation(void);
void _testItemCount(void);
private:
double _clampGridAngle180(double gridAngle);
void _setPolygon(void);
// SurveyComplexItem signals
enum {
gridPointsChangedIndex = 0,
cameraShotsChangedIndex,
coveredAreaChangedIndex,
cameraValueChangedIndex,
gridTypeChangedIndex,
timeBetweenShotsChangedIndex,
cameraOrientationFixedChangedIndex,
refly90DegreesChangedIndex,
dirtyChangedIndex,
maxSignalIndex
surveyVisualTransectPointsChangedIndex = 0,
surveyCameraShotsChangedIndex,
surveyCoveredAreaChangedIndex,
surveyTimeBetweenShotsChangedIndex,
surveyRefly90DegreesChangedIndex,
surveyDirtyChangedIndex,
surveyMaxSignalIndex
};
enum {
gridPointsChangedMask = 1 << gridPointsChangedIndex,
cameraShotsChangedMask = 1 << cameraShotsChangedIndex,
coveredAreaChangedMask = 1 << coveredAreaChangedIndex,
cameraValueChangedMask = 1 << cameraValueChangedIndex,
gridTypeChangedMask = 1 << gridTypeChangedIndex,
timeBetweenShotsChangedMask = 1 << timeBetweenShotsChangedIndex,
cameraOrientationFixedChangedMask = 1 << cameraOrientationFixedChangedIndex,
refly90DegreesChangedMask = 1 << refly90DegreesChangedIndex,
dirtyChangedMask = 1 << dirtyChangedIndex
surveyVisualTransectPointsChangedMask = 1 << surveyVisualTransectPointsChangedIndex,
surveyCameraShotsChangedMask = 1 << surveyCameraShotsChangedIndex,
surveyCoveredAreaChangedMask = 1 << surveyCoveredAreaChangedIndex,
surveyTimeBetweenShotsChangedMask = 1 << surveyTimeBetweenShotsChangedIndex,
surveyRefly90DegreesChangedMask = 1 << surveyRefly90DegreesChangedIndex,
surveyDirtyChangedMask = 1 << surveyDirtyChangedIndex
};
static const size_t _cSurveySignals = maxSignalIndex;
static const size_t _cSurveySignals = surveyMaxSignalIndex;
const char* _rgSurveySignals[_cSurveySignals];
Vehicle* _offlineVehicle;
......
......@@ -101,8 +101,13 @@ TransectStyleComplexItem::TransectStyleComplexItem(Vehicle* vehicle, QString set
connect(&_surveyAreaPolygon, &QGCMapPolygon::pathChanged, this, &TransectStyleComplexItem::coveredAreaChanged);
connect(&_cameraCalc, &CameraCalc::distanceToSurfaceRelativeChanged, this, &TransectStyleComplexItem::coordinateHasRelativeAltitudeChanged);
connect(&_cameraCalc, &CameraCalc::distanceToSurfaceRelativeChanged, this, &TransectStyleComplexItem::exitCoordinateHasRelativeAltitudeChanged);
connect(this, &TransectStyleComplexItem::visualTransectPointsChanged, this, &TransectStyleComplexItem::complexDistanceChanged);
connect(this, &TransectStyleComplexItem::visualTransectPointsChanged, this, &TransectStyleComplexItem::greatestDistanceToChanged);
connect(this, &TransectStyleComplexItem::followTerrainChanged, this, &TransectStyleComplexItem::_followTerrainChanged);
}
void TransectStyleComplexItem::_setCameraShots(int cameraShots)
......@@ -693,3 +698,21 @@ int TransectStyleComplexItem::lastSequenceNumber(void) const
}
}
bool TransectStyleComplexItem::coordinateHasRelativeAltitude(void) const
{
return _cameraCalc.distanceToSurfaceRelative();
}
bool TransectStyleComplexItem::exitCoordinateHasRelativeAltitude(void) const
{
return coordinateHasRelativeAltitude();
}
void TransectStyleComplexItem::_followTerrainChanged(bool followTerrain)
{
if (followTerrain) {
_cameraCalc.setDistanceToSurfaceRelative(false);
_refly90DegreesFact.setRawValue(false);
_hoverAndCaptureFact.setRawValue(false);
}
}
......@@ -87,9 +87,6 @@ public:
bool isSimpleItem (void) const final { return false; }
bool isStandaloneCoordinate (void) const final { return false; }
bool specifiesAltitudeOnly (void) const final { return false; }
QString commandDescription (void) const final { return tr("Corridor Scan"); }
QString commandName (void) const final { return tr("Corridor Scan"); }
QString abbreviation (void) const final { return "S"; }
QGeoCoordinate coordinate (void) const final { return _coordinate; }
QGeoCoordinate exitCoordinate (void) const final { return _exitCoordinate; }
int sequenceNumber (void) const final { return _sequenceNumber; }
......@@ -98,9 +95,12 @@ public:
double specifiedGimbalPitch (void) final { return std::numeric_limits<double>::quiet_NaN(); }
void setMissionFlightStatus (MissionController::MissionFlightStatus_t& missionFlightStatus) final;
bool readyForSave (void) const override;
QString commandDescription (void) const override { return tr("Transect"); }
QString commandName (void) const override { return tr("Transect"); }
QString abbreviation (void) const override { return tr("T"); }
bool coordinateHasRelativeAltitude (void) const final { return true /*_altitudeRelative*/; }
bool exitCoordinateHasRelativeAltitude (void) const final { return true /*_altitudeRelative*/; }
bool coordinateHasRelativeAltitude (void) const final;
bool exitCoordinateHasRelativeAltitude (void) const final;
bool exitCoordinateSameAsEntry (void) const final { return false; }
void setDirty (bool dirty) final;
......@@ -200,6 +200,7 @@ protected:
private slots:
void _reallyQueryTransectsPathHeightInfo(void);
void _followTerrainChanged (bool followTerrain);
private:
void _queryTransectsPathHeightInfo (void);
......
......@@ -13,7 +13,6 @@ import QGroundControl.FactControls 1.0
import QGroundControl.Palette 1.0
import QGroundControl.FlightMap 1.0
// Editor for Survery mission items
Rectangle {
id: _root
height: visible ? (editorColumn.height + (_margin * 2)) : 0
......@@ -56,11 +55,6 @@ Rectangle {
anchors.right: parent.right
spacing: _margin
QGCLabel {
text: "WIP: Careful!"
color: qgcPal.warningText
}
QGCLabel {
anchors.left: parent.left
anchors.right: parent.right
......@@ -115,7 +109,7 @@ Rectangle {
anchors.left: parent.left
text: qsTr("Relative altitude")
checked: missionItem.cameraCalc.distanceToSurfaceRelative
enabled: missionItem.cameraCalc.isManualCamera
enabled: missionItem.cameraCalc.isManualCamera && !missionItem.followTerrain
Layout.columnSpan: 2
onClicked: missionItem.cameraCalc.distanceToSurfaceRelative = checked
......@@ -158,12 +152,6 @@ Rectangle {
columns: 2
visible: followsTerrainCheckBox.checked
QGCLabel {
text: "WIP: Careful!"
color: qgcPal.warningText
Layout.columnSpan: 2
}
QGCLabel { text: qsTr("Tolerance") }
FactTextField {
fact: missionItem.terrainAdjustTolerance
......
......@@ -13,7 +13,6 @@ import QGroundControl.FactControls 1.0
import QGroundControl.Palette 1.0
import QGroundControl.FlightMap 1.0
// Editor for Survery mission items
Rectangle {
id: _root
height: visible ? (editorColumn.height + (_margin * 2)) : 0
......@@ -26,92 +25,8 @@ Rectangle {
//property var missionItem ///< Mission Item for editor
property real _margin: ScreenTools.defaultFontPixelWidth / 2
property int _cameraIndex: 1
property real _fieldWidth: ScreenTools.defaultFontPixelWidth * 10.5
property var _cameraList: [ qsTr("Manual Grid (no camera specs)"), qsTr("Custom Camera Grid") ]
property var _vehicle: QGroundControl.multiVehicleManager.activeVehicle ? QGroundControl.multiVehicleManager.activeVehicle : QGroundControl.multiVehicleManager.offlineEditingVehicle
property var _vehicleCameraList: _vehicle ? _vehicle.staticCameraList : []
readonly property int _gridTypeManual: 0
readonly property int _gridTypeCustomCamera: 1
readonly property int _gridTypeCamera: 2
Component.onCompleted: {
for (var i=0; i<_vehicle.staticCameraList.length; i++) {
_cameraList.push(_vehicle.staticCameraList[i].name)
}
gridTypeCombo.model = _cameraList
if (missionItem.manualGrid.value) {
gridTypeCombo.currentIndex = _gridTypeManual
} else {
var index = -1
for (index=0; index<_cameraList.length; index++) {
if (_cameraList[index] === missionItem.camera.value) {
break;
}
}
missionItem.cameraOrientationFixed = false
if (index == _cameraList.length) {
gridTypeCombo.currentIndex = _gridTypeCustomCamera
} else {
gridTypeCombo.currentIndex = index
if (index != 1) {
// Specific camera is selected
var camera = _vehicleCameraList[index - _gridTypeCamera]
missionItem.cameraOrientationFixed = camera.fixedOrientation
missionItem.cameraMinTriggerInterval = camera.minTriggerInterval
}
}
}
recalcFromCameraValues()
}
function recalcFromCameraValues() {
var focalLength = missionItem.cameraFocalLength.rawValue
var sensorWidth = missionItem.cameraSensorWidth.rawValue
var sensorHeight = missionItem.cameraSensorHeight.rawValue
var imageWidth = missionItem.cameraResolutionWidth.rawValue
var imageHeight = missionItem.cameraResolutionHeight.rawValue
var altitude = missionItem.gridAltitude.rawValue
var groundResolution= missionItem.groundResolution.rawValue
var frontalOverlap = missionItem.frontalOverlap.rawValue
var sideOverlap = missionItem.sideOverlap.rawValue
if (focalLength <= 0 || sensorWidth <= 0 || sensorHeight <= 0 || imageWidth <= 0 || imageHeight <= 0 || groundResolution <= 0) {
return
}
var imageSizeSideGround //size in side (non flying) direction of the image on the ground
var imageSizeFrontGround //size in front (flying) direction of the image on the ground
var gridSpacing
var cameraTriggerDistance
if (missionItem.fixedValueIsAltitude.value) {
groundResolution = (altitude * sensorWidth * 100) / (imageWidth * focalLength)
} else {
altitude = (imageWidth * groundResolution * focalLength) / (sensorWidth * 100)
}
if (missionItem.cameraOrientationLandscape.value) {
imageSizeSideGround = (imageWidth * groundResolution) / 100
imageSizeFrontGround = (imageHeight * groundResolution) / 100
} else {
imageSizeSideGround = (imageHeight * groundResolution) / 100
imageSizeFrontGround = (imageWidth * groundResolution) / 100
}
gridSpacing = imageSizeSideGround * ( (100-sideOverlap) / 100 )
cameraTriggerDistance = imageSizeFrontGround * ( (100-frontalOverlap) / 100 )
if (missionItem.fixedValueIsAltitude.value) {
missionItem.groundResolution.rawValue = groundResolution
} else {
missionItem.gridAltitude.rawValue = altitude
}
missionItem.gridSpacing.rawValue = gridSpacing
missionItem.cameraTriggerDistance.rawValue = cameraTriggerDistance
}
function polygonCaptureStarted() {
missionItem.clearPolygon()
......@@ -130,52 +45,8 @@ Rectangle {
function polygonAdjustStarted() { }
function polygonAdjustFinished() { }
property bool _noCameraValueRecalc: false ///< Prevents uneeded recalcs
Connections {
target: missionItem.camera
onValueChanged: {
if (gridTypeCombo.currentIndex >= _gridTypeCustomCamera && !_noCameraValueRecalc) {
recalcFromCameraValues()
}
}
}
Connections {
target: missionItem.gridAltitude
onValueChanged: {
if (gridTypeCombo.currentIndex >= _gridTypeCustomCamera && missionItem.fixedValueIsAltitude.value && !_noCameraValueRecalc) {
recalcFromCameraValues()
}
}
}
Connections {
target: missionItem
onCameraValueChanged: {
if (gridTypeCombo.currentIndex >= _gridTypeCustomCamera && !_noCameraValueRecalc) {
recalcFromCameraValues()
}
}
}
QGCPalette { id: qgcPal; colorGroupEnabled: true }
ExclusiveGroup {
id: cameraOrientationGroup
onCurrentChanged: {
if (gridTypeCombo.currentIndex >= _gridTypeCustomCamera) {
recalcFromCameraValues()
}
}
}
ExclusiveGroup { id: fixedValueGroup }
Column {
id: editorColumn
anchors.margins: _margin
......@@ -190,232 +61,20 @@ Rectangle {
text: qsTr("WARNING: Photo interval is below minimum interval (%1 secs) supported by camera.").arg(missionItem.cameraMinTriggerInterval.toFixed(1))
wrapMode: Text.WordWrap
color: qgcPal.warningText
visible: missionItem.manualGrid.value !== true && missionItem.cameraShots > 0 && missionItem.cameraMinTriggerInterval !== 0 && missionItem.cameraMinTriggerInterval > missionItem.timeBetweenShots
}
SectionHeader {
id: cameraHeader
text: qsTr("Camera")
showSpacer: false
}
Column {
anchors.left: parent.left
anchors.right: parent.right
spacing: _margin
visible: cameraHeader.checked
QGCComboBox {
id: gridTypeCombo
anchors.left: parent.left
anchors.right: parent.right
model: _cameraList
currentIndex: -1
onActivated: {
if (index == _gridTypeManual) {
missionItem.manualGrid.value = true
missionItem.fixedValueIsAltitude.value = true
} else if (index == _gridTypeCustomCamera) {
missionItem.manualGrid.value = false
missionItem.camera.value = gridTypeCombo.textAt(index)
missionItem.cameraOrientationFixed = false
missionItem.cameraMinTriggerInterval = 0
} else {
missionItem.manualGrid.value = false
missionItem.camera.value = gridTypeCombo.textAt(index)
_noCameraValueRecalc = true
var listIndex = index - _gridTypeCamera
missionItem.cameraSensorWidth.rawValue = _vehicleCameraList[listIndex].sensorWidth
missionItem.cameraSensorHeight.rawValue = _vehicleCameraList[listIndex].sensorHeight
missionItem.cameraResolutionWidth.rawValue = _vehicleCameraList[listIndex].imageWidth
missionItem.cameraResolutionHeight.rawValue = _vehicleCameraList[listIndex].imageHeight
missionItem.cameraFocalLength.rawValue = _vehicleCameraList[listIndex].focalLength
missionItem.cameraOrientationLandscape.rawValue = _vehicleCameraList[listIndex].landscape ? 1 : 0
missionItem.cameraOrientationFixed = _vehicleCameraList[listIndex].fixedOrientation
missionItem.cameraMinTriggerInterval = _vehicleCameraList[listIndex].minTriggerInterval
_noCameraValueRecalc = false
recalcFromCameraValues()
}
}
}
RowLayout {
anchors.left: parent.left
anchors.right: parent.right
spacing: _margin
visible: missionItem.manualGrid.value
QGCCheckBox {
id: cameraTriggerDistanceCheckBox
anchors.baseline: cameraTriggerDistanceField.baseline
text: qsTr("Trigger Distance")
checked: missionItem.cameraTriggerDistance.rawValue > 0
onClicked: {
if (checked) {
missionItem.cameraTriggerDistance.value = missionItem.cameraTriggerDistance.defaultValue
} else {
missionItem.cameraTriggerDistance.value = 0
}
}
}
FactTextField {
id: cameraTriggerDistanceField
Layout.fillWidth: true
fact: missionItem.cameraTriggerDistance
enabled: cameraTriggerDistanceCheckBox.checked
}
}
}
// Camera based grid ui
Column {
anchors.left: parent.left
anchors.right: parent.right
spacing: _margin
visible: gridTypeCombo.currentIndex !== _gridTypeManual
Row {
spacing: _margin
anchors.horizontalCenter: parent.horizontalCenter
visible: !missionItem.cameraOrientationFixed
QGCRadioButton {
width: _editFieldWidth
text: "Landscape"
checked: !!missionItem.cameraOrientationLandscape.value
exclusiveGroup: cameraOrientationGroup
onClicked: missionItem.cameraOrientationLandscape.value = 1
}
QGCRadioButton {
id: cameraOrientationPortrait
text: "Portrait"
checked: !missionItem.cameraOrientationLandscape.value
exclusiveGroup: cameraOrientationGroup
onClicked: missionItem.cameraOrientationLandscape.value = 0
}
}
Column {
id: custCameraCol
anchors.left: parent.left
anchors.right: parent.right
spacing: _margin
visible: gridTypeCombo.currentIndex === _gridTypeCustomCamera
RowLayout {
anchors.left: parent.left
anchors.right: parent.right
spacing: _margin
Item { Layout.fillWidth: true }
QGCLabel {
Layout.preferredWidth: _root._fieldWidth
text: qsTr("Width")
}
QGCLabel {
Layout.preferredWidth: _root._fieldWidth
text: qsTr("Height")
}
}
RowLayout {
anchors.left: parent.left
anchors.right: parent.right
spacing: _margin
QGCLabel { text: qsTr("Sensor"); Layout.fillWidth: true }
FactTextField {
Layout.preferredWidth: _root._fieldWidth
fact: missionItem.cameraSensorWidth
}
FactTextField {
Layout.preferredWidth: _root._fieldWidth
fact: missionItem.cameraSensorHeight
}
}
RowLayout {
anchors.left: parent.left
anchors.right: parent.right
spacing: _margin
QGCLabel { text: qsTr("Image"); Layout.fillWidth: true }
FactTextField {
Layout.preferredWidth: _root._fieldWidth
fact: missionItem.cameraResolutionWidth
}
FactTextField {
Layout.preferredWidth: _root._fieldWidth
fact: missionItem.cameraResolutionHeight
}
}
RowLayout {
anchors.left: parent.left
anchors.right: parent.right
spacing: _margin
QGCLabel {
text: qsTr("Focal length")
Layout.fillWidth: true
}
FactTextField {
Layout.preferredWidth: _root._fieldWidth
fact: missionItem.cameraFocalLength
}
}
} // Column - custom camera
RowLayout {
anchors.left: parent.left
anchors.right: parent.right
spacing: _margin
Item { Layout.fillWidth: true }
QGCLabel {
Layout.preferredWidth: _root._fieldWidth
text: qsTr("Front Lap")
}
QGCLabel {
Layout.preferredWidth: _root._fieldWidth
text: qsTr("Side Lap")
}
visible: missionItem.cameraShots > 0 && missionItem.cameraMinTriggerInterval !== 0 && missionItem.cameraMinTriggerInterval > missionItem.timeBetweenShots
}
RowLayout {
anchors.left: parent.left
anchors.right: parent.right
spacing: _margin
QGCLabel { text: qsTr("Overlap"); Layout.fillWidth: true }
FactTextField {
Layout.preferredWidth: _root._fieldWidth
fact: missionItem.frontalOverlap
}
FactTextField {
Layout.preferredWidth: _root._fieldWidth
fact: missionItem.sideOverlap
}
}
FactCheckBox {
text: qsTr("Hover and capture image")
fact: missionItem.hoverAndCapture
visible: missionItem.hoverAndCaptureAllowed
onClicked: {
if (checked) {
missionItem.cameraTriggerInTurnaround.rawValue = false
}
}
}
FactCheckBox {
text: qsTr("Take images in turnarounds")
fact: missionItem.cameraTriggerInTurnaround
enabled: missionItem.hoverAndCaptureAllowed ? !missionItem.hoverAndCapture.rawValue : true
CameraCalc {
cameraCalc: missionItem.cameraCalc
vehicleFlightIsFrontal: true
distanceToSurfaceLabel: qsTr("Altitude")
frontalDistanceLabel: qsTr("Trigger Distance")
sideDistanceLabel: qsTr("Spacing")
}
SectionHeader {
id: gridHeader
text: qsTr("Grid")
id: corridorHeader
text: qsTr("Transects")
}
GridLayout {
......@@ -424,57 +83,17 @@ Rectangle {
columnSpacing: _margin
rowSpacing: _margin
columns: 2
visible: gridHeader.checked
GridLayout {
anchors.left: parent.left
anchors.right: parent.right
columnSpacing: _margin
rowSpacing: _margin
columns: 2
visible: gridHeader.checked
QGCLabel {
id: angleText
text: qsTr("Angle")
Layout.fillWidth: true
}
Rectangle {
id: windRoseButton
width: ScreenTools.implicitTextFieldHeight
height: width
color: qgcPal.button
visible: _vehicle ? _vehicle.fixedWing : false
QGCColoredImage {
anchors.fill: parent
source: "/res/wind-rose.svg"
smooth: true
color: qgcPal.buttonText
}
QGCMouseArea {
fillItem: parent
onClicked: {
windRosePie.angle = Number(gridAngleText.text)
var cords = windRoseButton.mapToItem(_root, 0, 0)
windRosePie.popup(cords.x + windRoseButton.width / 2, cords.y + windRoseButton.height / 2)
}
}
}
}
visible: corridorHeader.checked
QGCLabel { text: qsTr("Angle") }
FactTextField {
id: gridAngleText
fact: missionItem.gridAngle
Layout.fillWidth: true
}
QGCLabel { text: qsTr("Turnaround dist") }
FactTextField {
fact: missionItem.turnaroundDist
fact: missionItem.turnAroundDistance
Layout.fillWidth: true
}
......@@ -487,138 +106,11 @@ Rectangle {
Layout.fillWidth: true
}
QGCCheckBox {
text: qsTr("Refly at 90 degree offset")
checked: missionItem.refly90Degrees
onClicked: missionItem.refly90Degrees = checked
Layout.columnSpan: 2
}
QGCLabel {
wrapMode: Text.WordWrap
text: qsTr("Select one:")
Layout.preferredWidth: parent.width
Layout.columnSpan: 2
}
QGCRadioButton {
id: fixedAltitudeRadio
text: qsTr("Altitude")
checked: !!missionItem.fixedValueIsAltitude.value
exclusiveGroup: fixedValueGroup
onClicked: missionItem.fixedValueIsAltitude.value = 1
}
FactTextField {
fact: missionItem.gridAltitude
enabled: fixedAltitudeRadio.checked
Layout.fillWidth: true
}
QGCRadioButton {
id: fixedGroundResolutionRadio
text: qsTr("Ground res")
checked: !missionItem.fixedValueIsAltitude.value
exclusiveGroup: fixedValueGroup
onClicked: missionItem.fixedValueIsAltitude.value = 0
}
FactTextField {
fact: missionItem.groundResolution
enabled: fixedGroundResolutionRadio.checked
Layout.fillWidth: true
}
}
}
// Manual grid ui
SectionHeader {
id: manualGridHeader
text: qsTr("Grid")
visible: gridTypeCombo.currentIndex === _gridTypeManual
}
GridLayout {
anchors.left: parent.left
anchors.right: parent.right
columnSpacing: _margin
rowSpacing: _margin
columns: 2
visible: manualGridHeader.visible && manualGridHeader.checked
RowLayout {
spacing: _margin
QGCLabel {
id: manualAngleText
text: qsTr("Angle")
Layout.fillWidth: true
}
Rectangle {
id: manualWindRoseButton
width: ScreenTools.implicitTextFieldHeight
height: width
color: qgcPal.button
visible: _vehicle ? _vehicle.fixedWing : false
QGCColoredImage {
anchors.fill: parent
source: "/res/wind-rose.svg"
smooth: true
color: qgcPal.buttonText
}
QGCMouseArea {
fillItem: parent
onClicked: {
windRosePie.angle = Number(gridAngleText.text)
var cords = manualWindRoseButton.mapToItem(_root, 0, 0)
windRosePie.popup(cords.x + manualWindRoseButton.width / 2, cords.y + manualWindRoseButton.height / 2)
}
}
}
}
FactTextField {
id: manualGridAngleText
fact: missionItem.gridAngle
Layout.fillWidth: true
}
QGCLabel { text: qsTr("Spacing") }
FactTextField {
fact: missionItem.gridSpacing
Layout.fillWidth: true
}
QGCLabel { text: qsTr("Altitude") }
FactTextField {
fact: missionItem.gridAltitude
Layout.fillWidth: true
}
QGCLabel { text: qsTr("Turnaround dist") }
FactTextField {
fact: missionItem.turnaroundDist
Layout.fillWidth: true
}
QGCLabel {
text: qsTr("Entry")
visible: !windRoseButton.visible
}
FactComboBox {
id: gridAngleBox
fact: missionItem.gridEntryLocation
visible: !windRoseButton.visible
indexModel: false
Layout.fillWidth: true
}
FactCheckBox {
text: qsTr("Hover and capture image")
fact: missionItem.hoverAndCapture
visible: missionItem.hoverAndCaptureAllowed
enabled: !missionItem.followTerrain
Layout.columnSpan: 2
onClicked: {
if (checked) {
......@@ -628,174 +120,87 @@ Rectangle {
}
FactCheckBox {
text: qsTr("Take images in turnarounds")
fact: missionItem.cameraTriggerInTurnaround
enabled: missionItem.hoverAndCaptureAllowed ? !missionItem.hoverAndCapture.rawValue : true
text: qsTr("Refly at 90 degree offset")
fact: missionItem.refly90Degrees
enabled: !missionItem.followTerrain
Layout.columnSpan: 2
}
QGCCheckBox {
text: qsTr("Refly at 90 degree offset")
checked: missionItem.refly90Degrees
onClicked: missionItem.refly90Degrees = checked
FactCheckBox {
text: qsTr("Take images in turnarounds")
fact: missionItem.cameraTriggerInTurnAround
enabled: missionItem.hoverAndCaptureAllowed ? !missionItem.hoverAndCapture.rawValue : true
Layout.columnSpan: 2
}
FactCheckBox {
QGCCheckBox {
id: relAlt
anchors.left: parent.left
text: qsTr("Relative altitude")
fact: missionItem.gridAltitudeRelative
checked: missionItem.cameraCalc.distanceToSurfaceRelative
enabled: missionItem.cameraCalc.isManualCamera && !missionItem.followTerrain
Layout.columnSpan: 2
}
}
SectionHeader {
id: statsHeader
text: qsTr("Statistics") }
Grid {
columns: 2
columnSpacing: ScreenTools.defaultFontPixelWidth
visible: statsHeader.checked
QGCLabel { text: qsTr("Survey Area") }
QGCLabel { text: QGroundControl.squareMetersToAppSettingsAreaUnits(missionItem.coveredArea).toFixed(2) + " " + QGroundControl.appSettingsAreaUnitsString }
onClicked: missionItem.cameraCalc.distanceToSurfaceRelative = checked
QGCLabel { text: qsTr("Photo Count") }
QGCLabel { text: missionItem.cameraShots }
QGCLabel { text: qsTr("Photo Interval") }
QGCLabel {
text: {
var timeVal = missionItem.timeBetweenShots
if(!isFinite(timeVal) || missionItem.cameraShots === 0) {
return qsTr("N/A")
Connections {
target: missionItem.cameraCalc
onDistanceToSurfaceRelativeChanged: relAlt.checked = missionItem.cameraCalc.distanceToSurfaceRelative
}
return timeVal.toFixed(1) + " " + qsTr("secs")
}
}
QGCLabel { text: qsTr("Trigger Distance") }
QGCLabel { text: missionItem.cameraTriggerDistance.valueString + " " + QGroundControl.appSettingsDistanceUnitsString }
}
SectionHeader {
id: terrainHeader
text: qsTr("Terrain")
checked: missionItem.followTerrain
}
QGCColoredImage {
id: windRoseArrow
source: "/res/wind-rose-arrow.svg"
visible: windRosePie.visible
width: windRosePie.width / 5
height: width * 1.454
smooth: true
color: qgcPal.colorGrey
transform: Rotation {
origin.x: windRoseArrow.width / 2
origin.y: windRoseArrow.height / 2
axis { x: 0; y: 0; z: 1 } angle: windRosePie.angle
}
x: windRosePie.x + Math.sin(- windRosePie.angle*Math.PI/180 - Math.PI/2)*(windRosePie.width/2 - windRoseArrow.width/2) + windRosePie.width / 2 - windRoseArrow.width / 2
y: windRosePie.y + Math.cos(- windRosePie.angle*Math.PI/180 - Math.PI/2)*(windRosePie.width/2 - windRoseArrow.width/2) + windRosePie.height / 2 - windRoseArrow.height / 2
z: windRosePie.z + 1
}
ColumnLayout {
anchors.left: parent.left
anchors.right: parent.right
spacing: _margin
visible: terrainHeader.checked
QGCColoredImage {
id: windGuru
source: "/res/wind-guru.svg"
visible: windRosePie.visible
width: windRosePie.width / 3
height: width * 4.28e-1
smooth: true
color: qgcPal.colorGrey
transform: Rotation {
origin.x: windGuru.width / 2
origin.y: windGuru.height / 2
axis { x: 0; y: 0; z: 1 } angle: windRosePie.angle + 180
}
x: windRosePie.x + Math.sin(- windRosePie.angle*Math.PI/180 - 3*Math.PI/2)*(windRosePie.width/2) + windRosePie.width / 2 - windGuru.width / 2
y: windRosePie.y + Math.cos(- windRosePie.angle*Math.PI/180 - 3*Math.PI/2)*(windRosePie.height/2) + windRosePie.height / 2 - windGuru.height / 2
z: windRosePie.z + 1
QGCCheckBox {
id: followsTerrainCheckBox
text: qsTr("Vehicle follows terrain")
checked: missionItem.followTerrain
onClicked: missionItem.followTerrain = checked
}
Item {
id: windRosePie
height: 2.6*windRoseButton.height
width: 2.6*windRoseButton.width
visible: false
focus: true
property string colorCircle: qgcPal.windowShade
property string colorBackground: qgcPal.colorGrey
property real lineWidth: windRoseButton.width / 3
property real angle: Number(gridAngleText.text)
Canvas {
id: windRoseCanvas
anchors.fill: parent
onPaint: {
var ctx = getContext("2d")
var x = width / 2
var y = height / 2
var angleWidth = 0.03 * Math.PI
var start = windRosePie.angle*Math.PI/180 - angleWidth
var end = windRosePie.angle*Math.PI/180 + angleWidth
ctx.reset()
ctx.beginPath()
ctx.arc(x, y, (width / 3) - windRosePie.lineWidth / 2, 0, 2*Math.PI, false)
ctx.lineWidth = windRosePie.lineWidth
ctx.strokeStyle = windRosePie.colorBackground
ctx.stroke()
ctx.beginPath()
ctx.arc(x, y, (width / 3) - windRosePie.lineWidth / 2, start, end, false)
ctx.lineWidth = windRosePie.lineWidth
ctx.strokeStyle = windRosePie.colorCircle
ctx.stroke()
}
}
GridLayout {
anchors.left: parent.left
anchors.right: parent.right
columnSpacing: _margin
rowSpacing: _margin
columns: 2
visible: followsTerrainCheckBox.checked
onFocusChanged: {
visible = focus
QGCLabel { text: qsTr("Tolerance") }
FactTextField {
fact: missionItem.terrainAdjustTolerance
Layout.fillWidth: true
}
function popup(x, y) {
if (x !== undefined)
windRosePie.x = x - windRosePie.width / 2
if (y !== undefined)
windRosePie.y = y - windRosePie.height / 2
windRosePie.visible = true
windRosePie.focus = true
missionItemEditorListView.interactive = false
QGCLabel { text: qsTr("Max Climb Rate") }
FactTextField {
fact: missionItem.terrainAdjustMaxClimbRate
Layout.fillWidth: true
}
MouseArea {
id: mouseArea
anchors.fill: parent
acceptedButtons: Qt.LeftButton | Qt.RightButton
onClicked: {
windRosePie.visible = false
missionItemEditorListView.interactive = true
}
onPositionChanged: {
var point = Qt.point(mouseX - parent.width / 2, mouseY - parent.height / 2)
var angle = Math.round(Math.atan2(point.y, point.x) * 180 / Math.PI)
windRoseCanvas.requestPaint()
windRosePie.angle = angle
gridAngleText.text = angle
gridAngleText.editingFinished()
if(angle > -135 && angle <= -45) {
gridAngleBox.activated(2) // or 3
} else if(angle > -45 && angle <= 45) {
gridAngleBox.activated(2) // or 0
} else if(angle > 45 && angle <= 135) {
gridAngleBox.activated(1) // or 0
} else if(angle > 135 || angle <= -135) {
gridAngleBox.activated(1) // or 3
QGCLabel { text: qsTr("Max Descent Rate") }
FactTextField {
fact: missionItem.terrainAdjustMaxDescentRate
Layout.fillWidth: true
}
}
}
SectionHeader {
id: statsHeader
text: qsTr("Statistics")
}
}
TransectStyleComplexItemStats { }
} // Column
} // Rectangle
......@@ -26,24 +26,24 @@ Item {
property var qgcView ///< QGCView to use for popping dialogs
property var _missionItem: object
property var _mapPolygon: object.mapPolygon
property var _gridComponent
property var _mapPolygon: object.surveyAreaPolygon
property var _visualTransectsComponent
property var _entryCoordinate
property var _exitCoordinate
signal clicked(int sequenceNumber)
function _addVisualElements() {
_gridComponent = gridComponent.createObject(map)
_visualTransectsComponent = visualTransectsComponent.createObject(map)
_entryCoordinate = entryPointComponent.createObject(map)
_exitCoordinate = exitPointComponent.createObject(map)
map.addMapItem(_gridComponent)
map.addMapItem(_visualTransectsComponent)
map.addMapItem(_entryCoordinate)
map.addMapItem(_exitCoordinate)
}
function _destroyVisualElements() {
_gridComponent.destroy()
_visualTransectsComponent.destroy()
_entryCoordinate.destroy()
_exitCoordinate.destroy()
}
......@@ -100,14 +100,14 @@ Item {
interiorOpacity: 0.5
}
// Survey grid lines
// Transect lines
Component {
id: gridComponent
id: visualTransectsComponent
MapPolyline {
line.color: "white"
line.width: 2
path: _missionItem.gridPoints
path: _missionItem.visualTransectPoints
}
}
......
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