Browse Source

Initial support for CorridorScan terrain follow

Only adjust existing waypoints. Does not add waypoints.
QGC4.4
DonLakeFlyer 7 years ago
parent
commit
65369153b1
  1. 95
      src/MissionManager/CorridorScanComplexItem.cc
  2. 5
      src/MissionManager/CorridorScanComplexItem.h
  3. 27
      src/MissionManager/TransectStyle.SettingsGroup.json
  4. 102
      src/MissionManager/TransectStyleComplexItem.cc
  5. 37
      src/MissionManager/TransectStyleComplexItem.h
  6. 58
      src/PlanView/CorridorScanEditor.qml
  7. 72
      src/Terrain/TerrainQuery.cc
  8. 41
      src/Terrain/TerrainQuery.h

95
src/MissionManager/CorridorScanComplexItem.cc

@ -183,28 +183,41 @@ void CorridorScanComplexItem::_buildAndAppendMissionItems(QList<MissionItem*>& i
{ {
qCDebug(CorridorScanComplexItemLog) << "_buildAndAppendMissionItems"; qCDebug(CorridorScanComplexItemLog) << "_buildAndAppendMissionItems";
// First adjust for terrain (this will set altitudes into _transectionPoints in all cases
_adjustTransectPointsForTerrain();
// Now build the mission items from the transect points
MissionItem* item;
int seqNum = _sequenceNumber; int seqNum = _sequenceNumber;
int pointIndex = 0;
bool imagesEverywhere = _cameraTriggerInTurnAroundFact.rawValue().toBool(); bool imagesEverywhere = _cameraTriggerInTurnAroundFact.rawValue().toBool();
bool addTriggerAtBeginning = imagesEverywhere;
bool firstPoint = true;
bool entryPoint = true;
while (pointIndex < _transectPoints.count()) { MAV_FRAME mavFrame = followTerrain() || !_cameraCalc.distanceToSurfaceRelative() ? MAV_FRAME_GLOBAL : MAV_FRAME_GLOBAL_RELATIVE_ALT;
if (_hasTurnaround()) {
QGeoCoordinate vertexCoord = _transectPoints[pointIndex++].value<QGeoCoordinate>(); foreach (const QVariant& transectPointVar, _transectPoints) {
MissionItem* item = new MissionItem(seqNum++, QGeoCoordinate transectPoint = transectPointVar.value<QGeoCoordinate>();
item = new MissionItem(seqNum++,
MAV_CMD_NAV_WAYPOINT, MAV_CMD_NAV_WAYPOINT,
_cameraCalc.distanceToSurfaceRelative() ? MAV_FRAME_GLOBAL_RELATIVE_ALT : MAV_FRAME_GLOBAL, mavFrame,
0, // No hold time 0, // No hold time
0.0, // No acceptance radius specified 0.0, // No acceptance radius specified
0.0, // Pass through waypoint 0.0, // Pass through waypoint
std::numeric_limits<double>::quiet_NaN(), // Yaw unchanged std::numeric_limits<double>::quiet_NaN(), // Yaw unchanged
vertexCoord.latitude(), transectPoint.latitude(),
vertexCoord.longitude(), transectPoint.longitude(),
_cameraCalc.distanceToSurface()->rawValue().toDouble(), // Altitude qAbs(transectPoint.altitude()), // qAbs since negative value indicates survey edge
true, // autoContinue true, // autoContinue
false, // isCurrentItem false, // isCurrentItem
missionItemParent); missionItemParent);
items.append(item); items.append(item);
if (imagesEverywhere && pointIndex == 1) {
if (firstPoint && addTriggerAtBeginning) {
// Start triggering
addTriggerAtBeginning = false;
item = new MissionItem(seqNum++, item = new MissionItem(seqNum++,
MAV_CMD_DO_SET_CAM_TRIGG_DIST, MAV_CMD_DO_SET_CAM_TRIGG_DIST,
MAV_FRAME_MISSION, MAV_FRAME_MISSION,
@ -217,28 +230,11 @@ void CorridorScanComplexItem::_buildAndAppendMissionItems(QList<MissionItem*>& i
missionItemParent); missionItemParent);
items.append(item); items.append(item);
} }
} firstPoint = false;
bool addTrigger = imagesEverywhere ? false : true; if (transectPoint.altitude() < 0 && !imagesEverywhere) {
for (int i=0; i<_corridorPolyline.count(); i++) { if (entryPoint) {
QGeoCoordinate vertexCoord = _transectPoints[pointIndex++].value<QGeoCoordinate>(); // Start triggering
MissionItem* item = new MissionItem(seqNum++,
MAV_CMD_NAV_WAYPOINT,
_cameraCalc.distanceToSurfaceRelative() ? MAV_FRAME_GLOBAL_RELATIVE_ALT : MAV_FRAME_GLOBAL,
0, // No hold time
0.0, // No acceptance radius specified
0.0, // Pass through waypoint
std::numeric_limits<double>::quiet_NaN(), // Yaw unchanged
vertexCoord.latitude(),
vertexCoord.longitude(),
_cameraCalc.distanceToSurface()->rawValue().toDouble(), // Altitude
true, // autoContinue
false, // isCurrentItem
missionItemParent);
items.append(item);
if (addTrigger) {
addTrigger = false;
item = new MissionItem(seqNum++, item = new MissionItem(seqNum++,
MAV_CMD_DO_SET_CAM_TRIGG_DIST, MAV_CMD_DO_SET_CAM_TRIGG_DIST,
MAV_FRAME_MISSION, MAV_FRAME_MISSION,
@ -250,11 +246,9 @@ void CorridorScanComplexItem::_buildAndAppendMissionItems(QList<MissionItem*>& i
false, // isCurrentItem false, // isCurrentItem
missionItemParent); missionItemParent);
items.append(item); items.append(item);
} } else {
} // Stop triggering
item = new MissionItem(seqNum++,
if (!imagesEverywhere) {
MissionItem* item = new MissionItem(seqNum++,
MAV_CMD_DO_SET_CAM_TRIGG_DIST, MAV_CMD_DO_SET_CAM_TRIGG_DIST,
MAV_FRAME_MISSION, MAV_FRAME_MISSION,
0, // stop triggering 0, // stop triggering
@ -266,27 +260,12 @@ void CorridorScanComplexItem::_buildAndAppendMissionItems(QList<MissionItem*>& i
missionItemParent); missionItemParent);
items.append(item); items.append(item);
} }
entryPoint = !entryPoint;
if (_hasTurnaround()) {
QGeoCoordinate vertexCoord = _transectPoints[pointIndex++].value<QGeoCoordinate>();
MissionItem* item = new MissionItem(seqNum++,
MAV_CMD_NAV_WAYPOINT,
_cameraCalc.distanceToSurfaceRelative() ? MAV_FRAME_GLOBAL_RELATIVE_ALT : MAV_FRAME_GLOBAL,
0, // No hold time
0.0, // No acceptance radius specified
0.0, // Pass through waypoint
std::numeric_limits<double>::quiet_NaN(), // Yaw unchanged
vertexCoord.latitude(),
vertexCoord.longitude(),
_cameraCalc.distanceToSurface()->rawValue().toDouble(), // Altitude
true, // autoContinue
false, // isCurrentItem
missionItemParent);
items.append(item);
} }
} }
if (imagesEverywhere) { if (imagesEverywhere) {
// Stop triggering
MissionItem* item = new MissionItem(seqNum++, MissionItem* item = new MissionItem(seqNum++,
MAV_CMD_DO_SET_CAM_TRIGG_DIST, MAV_CMD_DO_SET_CAM_TRIGG_DIST,
MAV_FRAME_MISSION, MAV_FRAME_MISSION,
@ -371,6 +350,7 @@ void CorridorScanComplexItem::_rebuildTransectsPhase1(void)
} }
_transectPoints.clear(); _transectPoints.clear();
_transectsPathHeightInfo.clear();
double transectSpacing = _cameraCalc.adjustedFootprintSide()->rawValue().toDouble(); double transectSpacing = _cameraCalc.adjustedFootprintSide()->rawValue().toDouble();
double fullWidth = _corridorWidthFact.rawValue().toDouble(); double fullWidth = _corridorWidthFact.rawValue().toDouble();
@ -392,6 +372,8 @@ void CorridorScanComplexItem::_rebuildTransectsPhase1(void)
} }
QList<QGeoCoordinate> transect = _corridorPolyline.offsetPolyline(offsetDistance); QList<QGeoCoordinate> transect = _corridorPolyline.offsetPolyline(offsetDistance);
transect[0].setAltitude(_surveyEdgeIndicator);
transect[1].setAltitude(_surveyEdgeIndicator);
if (_hasTurnaround()) { if (_hasTurnaround()) {
QGeoCoordinate extensionCoord; QGeoCoordinate extensionCoord;
@ -473,6 +455,8 @@ void CorridorScanComplexItem::_rebuildTransectsPhase1(void)
normalizedTransectPosition += transectSpacing; normalizedTransectPosition += transectSpacing;
} }
} }
_queryTransectsPathHeightInfo();
} }
void CorridorScanComplexItem::_rebuildTransectsPhase2(void) void CorridorScanComplexItem::_rebuildTransectsPhase2(void)
@ -506,3 +490,8 @@ void CorridorScanComplexItem::_rebuildCorridor(void)
_rebuildTransectsPhase1(); _rebuildTransectsPhase1();
_rebuildTransectsPhase2(); _rebuildTransectsPhase2();
} }
bool CorridorScanComplexItem::readyForSave(void) const
{
return TransectStyleComplexItem::readyForSave();
}

5
src/MissionManager/CorridorScanComplexItem.h

@ -36,18 +36,19 @@ public:
Q_INVOKABLE void rotateEntryPoint(void); Q_INVOKABLE void rotateEntryPoint(void);
// Overrides from ComplexMissionItem // Overrides from ComplexMissionItem
int lastSequenceNumber (void) const final; int lastSequenceNumber (void) const final;
bool load (const QJsonObject& complexObject, int sequenceNumber, QString& errorString) final; bool load (const QJsonObject& complexObject, int sequenceNumber, QString& errorString) final;
QString mapVisualQML (void) const final { return QStringLiteral("CorridorScanMapVisual.qml"); } QString mapVisualQML (void) const final { return QStringLiteral("CorridorScanMapVisual.qml"); }
// Overrides from TransectStyleComplexItem // Overrides from TransectStyleComplexItem
void save (QJsonArray& planItems) final; void save (QJsonArray& planItems) final;
bool specifiesCoordinate (void) const final; bool specifiesCoordinate (void) const final;
void appendMissionItems (QList<MissionItem*>& items, QObject* missionItemParent) final; void appendMissionItems (QList<MissionItem*>& items, QObject* missionItemParent) final;
void applyNewAltitude (double newAltitude) final; void applyNewAltitude (double newAltitude) final;
// Overrides from VisualMissionionItem
bool readyForSave (void) const;
static const char* jsonComplexItemTypeValue; static const char* jsonComplexItemTypeValue;
static const char* settingsGroup; static const char* settingsGroup;

27
src/MissionManager/TransectStyle.SettingsGroup.json

@ -34,5 +34,32 @@
"shortDescription": "Refly the pattern at a 90 degree angle", "shortDescription": "Refly the pattern at a 90 degree angle",
"type": "bool", "type": "bool",
"defaultValue": false "defaultValue": false
},
{
"name": "TerrainAdjustTolerance",
"shortDescription": "TerrainAdjustTolerance",
"type": "double",
"decimalPlaces": 2,
"min": 0,
"units": "m",
"defaultValue": 10
},
{
"name": "TerrainAdjustMaxClimbRate",
"shortDescription": "TerrainAdjustMaxClimbRate",
"type": "double",
"decimalPlaces": 2,
"min": 0,
"units": "m/s",
"defaultValue": 0
},
{
"name": "TerrainAdjustMaxDescentRate",
"shortDescription": "TerrainAdjustMaxDescentRate",
"type": "double",
"decimalPlaces": 2,
"min": 0,
"units": "m/s",
"defaultValue": 0
} }
] ]

102
src/MissionManager/TransectStyleComplexItem.cc

@ -26,29 +26,44 @@ const char* TransectStyleComplexItem::turnAroundDistanceMultiRotorName = "Tur
const char* TransectStyleComplexItem::cameraTriggerInTurnAroundName = "CameraTriggerInTurnAround"; const char* TransectStyleComplexItem::cameraTriggerInTurnAroundName = "CameraTriggerInTurnAround";
const char* TransectStyleComplexItem::hoverAndCaptureName = "HoverAndCapture"; const char* TransectStyleComplexItem::hoverAndCaptureName = "HoverAndCapture";
const char* TransectStyleComplexItem::refly90DegreesName = "Refly90Degrees"; const char* TransectStyleComplexItem::refly90DegreesName = "Refly90Degrees";
const char* TransectStyleComplexItem::terrainAdjustToleranceName = "TerrainAdjustTolerance";
const char* TransectStyleComplexItem::terrainAdjustMaxClimbRateName = "TerrainAdjustMaxClimbRate";
const char* TransectStyleComplexItem::terrainAdjustMaxDescentRateName = "TerrainAdjustMaxDescentRate";
const char* TransectStyleComplexItem::_jsonTransectStyleComplexItemKey = "TransectStyleComplexItem"; const char* TransectStyleComplexItem::_jsonTransectStyleComplexItemKey = "TransectStyleComplexItem";
const char* TransectStyleComplexItem::_jsonCameraCalcKey = "CameraCalc"; const char* TransectStyleComplexItem::_jsonCameraCalcKey = "CameraCalc";
const char* TransectStyleComplexItem::_jsonTransectPointsKey = "TransectPoints"; const char* TransectStyleComplexItem::_jsonTransectPointsKey = "TransectPoints";
const char* TransectStyleComplexItem::_jsonItemsKey = "Items"; const char* TransectStyleComplexItem::_jsonItemsKey = "Items";
const int TransectStyleComplexItem::_terrainQueryTimeoutMsecs = 500;
const double TransectStyleComplexItem::_surveyEdgeIndicator = -10;
TransectStyleComplexItem::TransectStyleComplexItem(Vehicle* vehicle, QString settingsGroup, QObject* parent) TransectStyleComplexItem::TransectStyleComplexItem(Vehicle* vehicle, QString settingsGroup, QObject* parent)
: ComplexMissionItem (vehicle, parent) : ComplexMissionItem (vehicle, parent)
, _settingsGroup (settingsGroup) , _settingsGroup (settingsGroup)
, _sequenceNumber (0) , _sequenceNumber (0)
, _dirty (false) , _dirty (false)
, _terrainPolyPathQuery (NULL)
, _ignoreRecalc (false) , _ignoreRecalc (false)
, _complexDistance (0) , _complexDistance (0)
, _cameraShots (0) , _cameraShots (0)
, _cameraMinTriggerInterval (0) , _cameraMinTriggerInterval (0)
, _cameraCalc (vehicle) , _cameraCalc (vehicle)
, _followTerrain (false)
, _loadedMissionItemsParent (NULL) , _loadedMissionItemsParent (NULL)
, _metaDataMap (FactMetaData::createMapFromJsonFile(QStringLiteral(":/json/TransectStyle.SettingsGroup.json"), this)) , _metaDataMap (FactMetaData::createMapFromJsonFile(QStringLiteral(":/json/TransectStyle.SettingsGroup.json"), this))
, _turnAroundDistanceFact (_settingsGroup, _metaDataMap[_vehicle->multiRotor() ? turnAroundDistanceMultiRotorName : turnAroundDistanceName]) , _turnAroundDistanceFact (_settingsGroup, _metaDataMap[_vehicle->multiRotor() ? turnAroundDistanceMultiRotorName : turnAroundDistanceName])
, _cameraTriggerInTurnAroundFact(_settingsGroup, _metaDataMap[cameraTriggerInTurnAroundName]) , _cameraTriggerInTurnAroundFact (_settingsGroup, _metaDataMap[cameraTriggerInTurnAroundName])
, _hoverAndCaptureFact (_settingsGroup, _metaDataMap[hoverAndCaptureName]) , _hoverAndCaptureFact (_settingsGroup, _metaDataMap[hoverAndCaptureName])
, _refly90DegreesFact (_settingsGroup, _metaDataMap[refly90DegreesName]) , _refly90DegreesFact (_settingsGroup, _metaDataMap[refly90DegreesName])
, _terrainAdjustToleranceFact (_settingsGroup, _metaDataMap[terrainAdjustToleranceName])
, _terrainAdjustMaxClimbRateFact (_settingsGroup, _metaDataMap[terrainAdjustMaxClimbRateName])
, _terrainAdjustMaxDescentRateFact (_settingsGroup, _metaDataMap[terrainAdjustMaxDescentRateName])
{ {
_terrainQueryTimer.setInterval(_terrainQueryTimeoutMsecs);
_terrainQueryTimer.setSingleShot(true);
connect(&_terrainQueryTimer, &QTimer::timeout, this, &TransectStyleComplexItem::_reallyQueryTransectsPathHeightInfo);
connect(&_turnAroundDistanceFact, &Fact::valueChanged, this, &TransectStyleComplexItem::_rebuildTransects); connect(&_turnAroundDistanceFact, &Fact::valueChanged, this, &TransectStyleComplexItem::_rebuildTransects);
connect(&_hoverAndCaptureFact, &Fact::valueChanged, this, &TransectStyleComplexItem::_rebuildTransects); connect(&_hoverAndCaptureFact, &Fact::valueChanged, this, &TransectStyleComplexItem::_rebuildTransects);
connect(&_refly90DegreesFact, &Fact::valueChanged, this, &TransectStyleComplexItem::_rebuildTransects); connect(&_refly90DegreesFact, &Fact::valueChanged, this, &TransectStyleComplexItem::_rebuildTransects);
@ -303,3 +318,88 @@ void TransectStyleComplexItem::_rebuildTransects(void)
_rebuildTransectsPhase1(); _rebuildTransectsPhase1();
_rebuildTransectsPhase2(); _rebuildTransectsPhase2();
} }
void TransectStyleComplexItem::_queryTransectsPathHeightInfo(void)
{
_transectsPathHeightInfo.clear();
if (_terrainPolyPathQuery) {
// Toss previous query
_terrainPolyPathQuery->deleteLater();
_terrainPolyPathQuery = NULL;
}
if (_transectPoints.count() > 1) {
// We don't actually send the query until this timer times out. This way we only send
// the laset request if we get a bunch in a row.
_terrainQueryTimer.start();
}
}
void TransectStyleComplexItem::_reallyQueryTransectsPathHeightInfo(void)
{
if (_transectPoints.count() > 1) {
_terrainPolyPathQuery = new TerrainPolyPathQuery(this);
connect(_terrainPolyPathQuery, &TerrainPolyPathQuery::terrainData, this, &TransectStyleComplexItem::_polyPathTerrainData);
_terrainPolyPathQuery->requestData(_transectPoints);
}
}
void TransectStyleComplexItem::_polyPathTerrainData(bool success, const QList<TerrainPathQuery::PathHeightInfo_t>& rgPathHeightInfo)
{
if (success) {
_transectsPathHeightInfo = rgPathHeightInfo;
} else {
_transectsPathHeightInfo.clear();
}
}
bool TransectStyleComplexItem::readyForSave(void) const
{
// Make sure we have the terrain data we need
return _transectPoints.count() > 1 ? _transectsPathHeightInfo.count() : false;
}
void TransectStyleComplexItem::_adjustTransectPointsForTerrain(void)
{
if (_followTerrain && !readyForSave()) {
qCWarning(TransectStyleComplexItemLog) << "_adjustTransectPointsForTerrain called when terrain data not ready";
qgcApp()->showMessage(tr("INTERNAL ERROR: TransectStyleComplexItem::_adjustTransectPointsForTerrain called when terrain data not ready. Plan will be incorrect."));
return;
}
double altitude = _cameraCalc.distanceToSurface()->rawValue().toDouble();
for (int i=0; i<_transectPoints.count() - 1; i++) {
QGeoCoordinate transectPoint = _transectPoints[i].value<QGeoCoordinate>();
bool surveyEdgeIndicator = transectPoint.altitude() == _surveyEdgeIndicator;
if (_followTerrain) {
transectPoint.setAltitude(_transectsPathHeightInfo[i].rgHeight[0] + altitude);
} else {
transectPoint.setAltitude(altitude);
}
if (surveyEdgeIndicator) {
// Use to indicate survey edge
transectPoint.setAltitude(-transectPoint.altitude());
}
_transectPoints[i] = QVariant::fromValue(transectPoint);
}
// Take care of last point
QGeoCoordinate transectPoint = _transectPoints.last().value<QGeoCoordinate>();
if (_followTerrain){
transectPoint.setAltitude(_transectsPathHeightInfo.last().rgHeight.last() + altitude);
} else {
transectPoint.setAltitude(altitude);
}
_transectPoints[_transectPoints.count() - 1] = QVariant::fromValue(transectPoint);
}
void TransectStyleComplexItem::setFollowTerrain(bool followTerrain)
{
if (followTerrain != _followTerrain) {
_followTerrain = followTerrain;
emit followTerrainChanged(followTerrain);
}
}

37
src/MissionManager/TransectStyleComplexItem.h

@ -16,6 +16,7 @@
#include "QGCMapPolyline.h" #include "QGCMapPolyline.h"
#include "QGCMapPolygon.h" #include "QGCMapPolygon.h"
#include "CameraCalc.h" #include "CameraCalc.h"
#include "TerrainQuery.h"
Q_DECLARE_LOGGING_CATEGORY(TransectStyleComplexItemLog) Q_DECLARE_LOGGING_CATEGORY(TransectStyleComplexItemLog)
@ -40,6 +41,11 @@ public:
Q_PROPERTY(bool hoverAndCaptureAllowed READ hoverAndCaptureAllowed CONSTANT) Q_PROPERTY(bool hoverAndCaptureAllowed READ hoverAndCaptureAllowed CONSTANT)
Q_PROPERTY(QVariantList transectPoints READ transectPoints NOTIFY transectPointsChanged) Q_PROPERTY(QVariantList transectPoints READ transectPoints NOTIFY transectPointsChanged)
Q_PROPERTY(bool followTerrain READ followTerrain WRITE setFollowTerrain NOTIFY followTerrainChanged)
Q_PROPERTY(Fact* terrainAdjustTolerance READ terrainAdjustTolerance CONSTANT)
Q_PROPERTY(Fact* terrainAdjustMaxDescentRate READ terrainAdjustMaxDescentRate CONSTANT)
Q_PROPERTY(Fact* terrainAdjustMaxClimbRate READ terrainAdjustMaxClimbRate CONSTANT)
QGCMapPolygon* surveyAreaPolygon (void) { return &_surveyAreaPolygon; } QGCMapPolygon* surveyAreaPolygon (void) { return &_surveyAreaPolygon; }
CameraCalc* cameraCalc (void) { return &_cameraCalc; } CameraCalc* cameraCalc (void) { return &_cameraCalc; }
QVariantList transectPoints (void) { return _transectPoints; } QVariantList transectPoints (void) { return _transectPoints; }
@ -48,12 +54,18 @@ public:
Fact* cameraTriggerInTurnAround (void) { return &_cameraTriggerInTurnAroundFact; } Fact* cameraTriggerInTurnAround (void) { return &_cameraTriggerInTurnAroundFact; }
Fact* hoverAndCapture (void) { return &_hoverAndCaptureFact; } Fact* hoverAndCapture (void) { return &_hoverAndCaptureFact; }
Fact* refly90Degrees (void) { return &_refly90DegreesFact; } Fact* refly90Degrees (void) { return &_refly90DegreesFact; }
Fact* terrainAdjustTolerance (void) { return &_terrainAdjustToleranceFact; }
Fact* terrainAdjustMaxDescentRate (void) { return &_terrainAdjustMaxClimbRateFact; }
Fact* terrainAdjustMaxClimbRate (void) { return &_terrainAdjustMaxDescentRateFact; }
int cameraShots (void) const { return _cameraShots; } int cameraShots (void) const { return _cameraShots; }
double timeBetweenShots (void); double timeBetweenShots (void);
double coveredArea (void) const; double coveredArea (void) const;
double cameraMinTriggerInterval(void) const { return _cameraMinTriggerInterval; } double cameraMinTriggerInterval(void) const { return _cameraMinTriggerInterval; }
bool hoverAndCaptureAllowed (void) const; bool hoverAndCaptureAllowed (void) const;
bool followTerrain (void) const { return _followTerrain; }
void setFollowTerrain(bool followTerrain);
// Overrides from ComplexMissionItem // Overrides from ComplexMissionItem
@ -85,6 +97,7 @@ public:
double specifiedGimbalYaw (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(); } double specifiedGimbalPitch (void) final { return std::numeric_limits<double>::quiet_NaN(); }
void setMissionFlightStatus (MissionController::MissionFlightStatus_t& missionFlightStatus) final; void setMissionFlightStatus (MissionController::MissionFlightStatus_t& missionFlightStatus) final;
bool readyForSave (void) const override;
bool coordinateHasRelativeAltitude (void) const final { return true /*_altitudeRelative*/; } bool coordinateHasRelativeAltitude (void) const final { return true /*_altitudeRelative*/; }
bool exitCoordinateHasRelativeAltitude (void) const final { return true /*_altitudeRelative*/; } bool exitCoordinateHasRelativeAltitude (void) const final { return true /*_altitudeRelative*/; }
@ -99,6 +112,9 @@ public:
static const char* cameraTriggerInTurnAroundName; static const char* cameraTriggerInTurnAroundName;
static const char* hoverAndCaptureName; static const char* hoverAndCaptureName;
static const char* refly90DegreesName; static const char* refly90DegreesName;
static const char* terrainAdjustToleranceName;
static const char* terrainAdjustMaxClimbRateName;
static const char* terrainAdjustMaxDescentRateName;
signals: signals:
void cameraShotsChanged (void); void cameraShotsChanged (void);
@ -106,6 +122,7 @@ signals:
void cameraMinTriggerIntervalChanged(double cameraMinTriggerInterval); void cameraMinTriggerIntervalChanged(double cameraMinTriggerInterval);
void transectPointsChanged (void); void transectPointsChanged (void);
void coveredAreaChanged (void); void coveredAreaChanged (void);
void followTerrainChanged (bool followTerrain);
protected slots: protected slots:
virtual void _rebuildTransectsPhase1 (void) = 0; virtual void _rebuildTransectsPhase1 (void) = 0;
@ -115,6 +132,7 @@ protected slots:
void _setIfDirty (bool dirty); void _setIfDirty (bool dirty);
void _updateCoordinateAltitudes (void); void _updateCoordinateAltitudes (void);
void _signalLastSequenceNumberChanged (void); void _signalLastSequenceNumberChanged (void);
void _polyPathTerrainData (bool success, const QList<TerrainPathQuery::PathHeightInfo_t>& rgPathHeightInfo);
protected: protected:
void _save (QJsonObject& saveObject); void _save (QJsonObject& saveObject);
@ -124,15 +142,21 @@ protected:
double _triggerDistance (void) const; double _triggerDistance (void) const;
bool _hasTurnaround (void) const; bool _hasTurnaround (void) const;
double _turnaroundDistance (void) const; double _turnaroundDistance (void) const;
void _queryTransectsPathHeightInfo (void);
void _adjustTransectPointsForTerrain (void);
QString _settingsGroup; QString _settingsGroup;
int _sequenceNumber; int _sequenceNumber;
bool _dirty; bool _dirty;
QGeoCoordinate _coordinate; QGeoCoordinate _coordinate;
QGeoCoordinate _exitCoordinate; QGeoCoordinate _exitCoordinate;
QVariantList _transectPoints;
QGCMapPolygon _surveyAreaPolygon; QGCMapPolygon _surveyAreaPolygon;
QVariantList _transectPoints;
QList<TerrainPathQuery::PathHeightInfo_t> _transectsPathHeightInfo;
TerrainPolyPathQuery* _terrainPolyPathQuery;
QTimer _terrainQueryTimer;
bool _ignoreRecalc; bool _ignoreRecalc;
double _complexDistance; double _complexDistance;
int _cameraShots; int _cameraShots;
@ -140,6 +164,7 @@ protected:
double _cameraMinTriggerInterval; double _cameraMinTriggerInterval;
double _cruiseSpeed; double _cruiseSpeed;
CameraCalc _cameraCalc; CameraCalc _cameraCalc;
bool _followTerrain;
QObject* _loadedMissionItemsParent; ///< Parent for all items in _loadedMissionItems for simpler delete QObject* _loadedMissionItemsParent; ///< Parent for all items in _loadedMissionItems for simpler delete
QList<MissionItem*> _loadedMissionItems; ///< Mission items loaded from plan file QList<MissionItem*> _loadedMissionItems; ///< Mission items loaded from plan file
@ -150,12 +175,20 @@ protected:
SettingsFact _cameraTriggerInTurnAroundFact; SettingsFact _cameraTriggerInTurnAroundFact;
SettingsFact _hoverAndCaptureFact; SettingsFact _hoverAndCaptureFact;
SettingsFact _refly90DegreesFact; SettingsFact _refly90DegreesFact;
SettingsFact _terrainAdjustToleranceFact;
SettingsFact _terrainAdjustMaxClimbRateFact;
SettingsFact _terrainAdjustMaxDescentRateFact;
static const char* _jsonCameraCalcKey; static const char* _jsonCameraCalcKey;
static const char* _jsonTransectStyleComplexItemKey; static const char* _jsonTransectStyleComplexItemKey;
static const char* _jsonTransectPointsKey; static const char* _jsonTransectPointsKey;
static const char* _jsonItemsKey; static const char* _jsonItemsKey;
static const int _terrainQueryTimeoutMsecs;
static const double _surveyEdgeIndicator; ///< Altitude value in _transectPoints which indicates survey entry
private slots: private slots:
void _rebuildTransects(void); void _rebuildTransects (void);
void _reallyQueryTransectsPathHeightInfo (void);
}; };

58
src/PlanView/CorridorScanEditor.qml

@ -57,6 +57,11 @@ Rectangle {
spacing: _margin spacing: _margin
QGCLabel { QGCLabel {
text: "WIP: Careful!"
color: qgcPal.warningText
}
QGCLabel {
anchors.left: parent.left anchors.left: parent.left
anchors.right: parent.right anchors.right: parent.right
text: qsTr("WARNING: Photo interval is below minimum interval (%1 secs) supported by camera.").arg(missionItem.cameraMinTriggerInterval.toFixed(1)) text: qsTr("WARNING: Photo interval is below minimum interval (%1 secs) supported by camera.").arg(missionItem.cameraMinTriggerInterval.toFixed(1))
@ -127,6 +132,59 @@ Rectangle {
} }
SectionHeader { SectionHeader {
id: terrainHeader
text: qsTr("Terrain")
checked: false
}
ColumnLayout {
anchors.left: parent.left
anchors.right: parent.right
spacing: _margin
visible: terrainHeader.checked
QGCCheckBox {
id: followsTerrainCheckBox
text: qsTr("Vehicle follows terrain")
checked: missionItem.followTerrain
onClicked: missionItem.followTerrain = checked
}
GridLayout {
anchors.left: parent.left
anchors.right: parent.right
columnSpacing: _margin
rowSpacing: _margin
columns: 2
visible: followsTerrainCheckBox.checked
QGCLabel {
text: "WIP: Careful!"
color: qgcPal.warningText
Layout.columnSpan: 2
}
QGCLabel { text: qsTr("Tolerance") }
FactTextField {
fact: missionItem.terrainAdjustTolerance
Layout.fillWidth: true
}
QGCLabel { text: qsTr("Max Climb Rate") }
FactTextField {
fact: missionItem.terrainAdjustMaxClimbRate
Layout.fillWidth: true
}
QGCLabel { text: qsTr("Max Descent Rate") }
FactTextField {
fact: missionItem.terrainAdjustMaxDescentRate
Layout.fillWidth: true
}
}
}
SectionHeader {
id: statsHeader id: statsHeader
text: qsTr("Statistics") text: qsTr("Statistics")
} }

72
src/Terrain/TerrainQuery.cc

@ -264,7 +264,7 @@ void TerrainAtCoordinateQuery::_signalTerrainData(bool success, QList<float>& al
TerrainPathQuery::TerrainPathQuery(QObject* parent) TerrainPathQuery::TerrainPathQuery(QObject* parent)
: TerrainQuery(parent) : TerrainQuery(parent)
{ {
qRegisterMetaType<PathHeightInfo_t>();
} }
void TerrainPathQuery::requestData(const QGeoCoordinate& fromCoord, const QGeoCoordinate& toCoord) void TerrainPathQuery::requestData(const QGeoCoordinate& fromCoord, const QGeoCoordinate& toCoord)
@ -287,29 +287,29 @@ void TerrainPathQuery::requestData(const QGeoCoordinate& fromCoord, const QGeoCo
void TerrainPathQuery::_getNetworkReplyFailed(void) void TerrainPathQuery::_getNetworkReplyFailed(void)
{ {
QList<double> altitudes; PathHeightInfo_t pathHeightInfo;
emit terrainData(false, 0, 0, altitudes); emit terrainData(false, pathHeightInfo);
} }
void TerrainPathQuery::_requestFailed(QNetworkReply::NetworkError error) void TerrainPathQuery::_requestFailed(QNetworkReply::NetworkError error)
{ {
Q_UNUSED(error); Q_UNUSED(error);
QList<double> altitudes; PathHeightInfo_t pathHeightInfo;
emit terrainData(false, 0, 0, altitudes); emit terrainData(false, pathHeightInfo);
} }
void TerrainPathQuery::_requestJsonParseFailed(const QString& errorString) void TerrainPathQuery::_requestJsonParseFailed(const QString& errorString)
{ {
Q_UNUSED(errorString); Q_UNUSED(errorString);
QList<double> altitudes; PathHeightInfo_t pathHeightInfo;
emit terrainData(false, 0, 0, altitudes); emit terrainData(false, pathHeightInfo);
} }
void TerrainPathQuery::_requestAirmapStatusFailed(const QString& status) void TerrainPathQuery::_requestAirmapStatusFailed(const QString& status)
{ {
Q_UNUSED(status); Q_UNUSED(status);
QList<double> altitudes; PathHeightInfo_t pathHeightInfo;
emit terrainData(false, 0, 0, altitudes); emit terrainData(false, pathHeightInfo);
} }
void TerrainPathQuery::_requestSucess(const QJsonValue& dataJsonValue) void TerrainPathQuery::_requestSucess(const QJsonValue& dataJsonValue)
@ -318,14 +318,56 @@ void TerrainPathQuery::_requestSucess(const QJsonValue& dataJsonValue)
QJsonArray stepArray = jsonObject["step"].toArray(); QJsonArray stepArray = jsonObject["step"].toArray();
QJsonArray profileArray = jsonObject["profile"].toArray(); QJsonArray profileArray = jsonObject["profile"].toArray();
QList<double> rgProfile; PathHeightInfo_t pathHeightInfo;
pathHeightInfo.latStep = stepArray[0].toDouble();
pathHeightInfo.lonStep = stepArray[1].toDouble();
foreach (const QJsonValue& profileValue, profileArray) { foreach (const QJsonValue& profileValue, profileArray) {
rgProfile.append(profileValue.toDouble()); pathHeightInfo.rgHeight.append(profileValue.toDouble());
} }
emit terrainData(true, // success emit terrainData(true /* success */, pathHeightInfo);
stepArray[0].toDouble(), // lat step }
stepArray[1].toDouble(), // lon step
rgProfile); TerrainPolyPathQuery::TerrainPolyPathQuery(QObject* parent)
: QObject (parent)
, _curIndex (0)
{
connect(&_pathQuery, &TerrainPathQuery::terrainData, this, &TerrainPolyPathQuery::_terrainDataReceived);
} }
void TerrainPolyPathQuery::requestData(const QVariantList& polyPath)
{
QList<QGeoCoordinate> path;
foreach (const QVariant& geoVar, polyPath) {
path.append(geoVar.value<QGeoCoordinate>());
}
requestData(path);
}
void TerrainPolyPathQuery::requestData(const QList<QGeoCoordinate>& polyPath)
{
// Kick off first request
_rgCoords = polyPath;
_curIndex = 0;
_pathQuery.requestData(_rgCoords[0], _rgCoords[1]);
}
void TerrainPolyPathQuery::_terrainDataReceived(bool success, const TerrainPathQuery::PathHeightInfo_t& pathHeightInfo)
{
if (!success) {
_rgPathHeightInfo.clear();
emit terrainData(false /* success */, _rgPathHeightInfo);
return;
}
_rgPathHeightInfo.append(pathHeightInfo);
if (++_curIndex >= _rgCoords.count() - 1) {
// We've finished all requests
emit terrainData(true /* success */, _rgPathHeightInfo);
} else {
_pathQuery.requestData(_rgCoords[_curIndex], _rgCoords[_curIndex+1]);
}
}

41
src/Terrain/TerrainQuery.h

@ -126,17 +126,50 @@ public:
/// @param coordinates to query /// @param coordinates to query
void requestData(const QGeoCoordinate& fromCoord, const QGeoCoordinate& toCoord); void requestData(const QGeoCoordinate& fromCoord, const QGeoCoordinate& toCoord);
typedef struct {
double latStep; ///< Amount of latitudinal distance between each returned height
double lonStep; ///< Amount of longitudinal distance between each returned height
QList<double> rgHeight; ///< Terrain heights along path
} PathHeightInfo_t;
signals:
/// Signalled when terrain data comes back from server
void terrainData(bool success, const PathHeightInfo_t& pathHeightInfo);
protected: protected:
void _getNetworkReplyFailed (void) final; void _getNetworkReplyFailed (void) final;
void _requestFailed (QNetworkReply::NetworkError error) final; void _requestFailed (QNetworkReply::NetworkError error) final;
void _requestJsonParseFailed (const QString& errorString) final; void _requestJsonParseFailed (const QString& errorString) final;
void _requestAirmapStatusFailed (const QString& status) final; void _requestAirmapStatusFailed (const QString& status) final;
void _requestSucess (const QJsonValue& dataJsonValue) final; void _requestSucess (const QJsonValue& dataJsonValue) final;
};
Q_DECLARE_METATYPE(TerrainPathQuery::PathHeightInfo_t)
class TerrainPolyPathQuery : public QObject
{
Q_OBJECT
public:
TerrainPolyPathQuery(QObject* parent = NULL);
/// Async terrain query for terrain heights for the paths between each specified QGeoCoordinate.
/// When the query is done, the terrainData() signal is emitted.
/// @param polyPath List of QGeoCoordinate
void requestData(const QVariantList& polyPath);
void requestData(const QList<QGeoCoordinate>& polyPath);
signals: signals:
/// Signalled when terrain data comes back from server /// Signalled when terrain data comes back from server
/// @param latStep Amount of latitudinal distance between each returned height void terrainData(bool success, const QList<TerrainPathQuery::PathHeightInfo_t>& rgPathHeightInfo);
/// @param lonStep Amount of longitudinal distance between each returned height
/// @param altitudes Altitudes along specified path private slots:
void terrainData(bool success, double latStep, double lonStep, QList<double> altitudes); void _terrainDataReceived(bool success, const TerrainPathQuery::PathHeightInfo_t& pathHeightInfo);
private:
int _curIndex;
QList<QGeoCoordinate> _rgCoords;
QList<TerrainPathQuery::PathHeightInfo_t> _rgPathHeightInfo;
TerrainPathQuery _pathQuery;
}; };

Loading…
Cancel
Save