Commit c8dadd86 authored by DonLakeFlyer's avatar DonLakeFlyer

Convert Survey complex item to use TransectStyleComplexItem

parent 07fba793
......@@ -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);
......
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
......@@ -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(this, &TransectStyleComplexItem::visualTransectPointsChanged, this, &TransectStyleComplexItem::complexDistanceChanged);
connect(this, &TransectStyleComplexItem::visualTransectPointsChanged, this, &TransectStyleComplexItem::greatestDistanceToChanged);
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)
......@@ -611,7 +616,7 @@ void TransectStyleComplexItem::_addInterstitialTerrainPoints(QList<CoordInfo_t>&
{
QList<CoordInfo_t> adjustedTransect;
adjustedTransect.append(transect.first());
double requestedAltitude = _cameraCalc.distanceToSurface()->rawValue().toDouble();
for (int i=0; i<transect.count() - 1; i++) {
CoordInfo_t fromCoordInfo = transect[i];
......@@ -621,11 +626,14 @@ void TransectStyleComplexItem::_addInterstitialTerrainPoints(QList<CoordInfo_t>&
double distance = fromCoordInfo.coord.distanceTo(toCoordInfo.coord);
const TerrainPathQuery::PathHeightInfo_t& pathHeightInfo = transectPathHeightInfo[i];
double requestedAltitude = _cameraCalc.distanceToSurface()->rawValue().toDouble();
fromCoordInfo.coord.setAltitude(pathHeightInfo.heights.first() + requestedAltitude);
toCoordInfo.coord.setAltitude(pathHeightInfo.heights.last() + requestedAltitude);
if (i == 0) {
adjustedTransect.append(fromCoordInfo);
}
int cHeights = pathHeightInfo.heights.count();
for (int pathHeightIndex=1; pathHeightIndex<cHeights - 1; pathHeightIndex++) {
double interstitialTerrainHeight = pathHeightInfo.heights[pathHeightIndex];
......@@ -642,6 +650,11 @@ void TransectStyleComplexItem::_addInterstitialTerrainPoints(QList<CoordInfo_t>&
adjustedTransect.append(toCoordInfo);
}
CoordInfo_t lastCoordInfo = transect.last();
const TerrainPathQuery::PathHeightInfo_t& pathHeightInfo = transectPathHeightInfo.last();
lastCoordInfo.coord.setAltitude(pathHeightInfo.heights.last() + requestedAltitude);
adjustedTransect.append(lastCoordInfo);
#if 0
qDebug() << "_addInterstitialTerrainPoints";
foreach (const TransectStyleComplexItem::CoordInfo_t& coordInfo, adjustedTransect) {
......@@ -685,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
......
This diff is collapsed.
......@@ -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