Browse Source

Merge pull request #9265 from DonLakeFlyer/TerrainProfile

Terrain profile fixes
QGC4.4
Don Gagne 4 years ago committed by GitHub
parent
commit
8d1d2d2530
No known key found for this signature in database
GPG Key ID: 4AEE18F83AFDEB23
  1. 2
      src/MissionManager/CameraSectionTest.cc
  2. 12
      src/MissionManager/MissionController.cc
  3. 2
      src/MissionManager/MissionSettingsItem.cc
  4. 64
      src/MissionManager/TransectStyleComplexItem.cc
  5. 11
      src/PlanView/TerrainStatus.qml
  6. 96
      src/QmlControls/TerrainProfile.cc
  7. 16
      src/QmlControls/TerrainProfile.h
  8. 6
      src/ui/preferences/GeneralSettings.qml

2
src/MissionManager/CameraSectionTest.cc

@ -1085,7 +1085,7 @@ void CameraSectionTest::_testScanForMultipleItems(void) @@ -1085,7 +1085,7 @@ void CameraSectionTest::_testScanForMultipleItems(void)
item2->missionItem() = cameraItem->missionItem();
visualItems.append(item1);
visualItems.append(item2);
qDebug() << commandTree->getUIInfo(_controllerVehicle, QGCMAVLink::VehicleClassGeneric, (MAV_CMD)item1->command())->rawName() << commandTree->getUIInfo(_controllerVehicle, QGCMAVLink::VehicleClassGeneric, (MAV_CMD)item2->command())->rawName();;
//qDebug() << commandTree->getUIInfo(_controllerVehicle, QGCMAVLink::VehicleClassGeneric, (MAV_CMD)item1->command())->rawName() << commandTree->getUIInfo(_controllerVehicle, QGCMAVLink::VehicleClassGeneric, (MAV_CMD)item2->command())->rawName();
scanIndex = 0;
QCOMPARE(_cameraSection->scanForSection(&visualItems, scanIndex), true);

12
src/MissionManager/MissionController.cc

@ -1156,10 +1156,10 @@ FlightPathSegment* MissionController::_createFlightPathSegmentWorker(VisualItemP @@ -1156,10 +1156,10 @@ FlightPathSegment* MissionController::_createFlightPathSegmentWorker(VisualItemP
{
QGeoCoordinate coord1 = pair.first->isSimpleItem() ? pair.first->coordinate() : pair.first->exitCoordinate();
QGeoCoordinate coord2 = pair.second->coordinate();
double coord1Alt = pair.first->isSimpleItem() ? pair.first->amslEntryAlt() : pair.first->amslExitAlt();
double coord2Alt = pair.second->amslEntryAlt();
double coord1AMSLAlt = pair.first->isSimpleItem() ? pair.first->amslEntryAlt() : pair.first->amslExitAlt();
double coord2AMSLAlt = pair.second->amslEntryAlt();
FlightPathSegment* segment = new FlightPathSegment(coord1, coord1Alt, coord2, coord2Alt, !_flyView /* queryTerrainData */, this);
FlightPathSegment* segment = new FlightPathSegment(coord1, coord1AMSLAlt, coord2, coord2AMSLAlt, !_flyView /* queryTerrainData */, this);
auto coord1Notifier = pair.first->isSimpleItem() ? &VisualMissionItem::coordinateChanged : &VisualMissionItem::exitCoordinateChanged;
auto coord2Notifier = &VisualMissionItem::coordinateChanged;
@ -1708,6 +1708,12 @@ void MissionController::_recalcMissionFlightStatus() @@ -1708,6 +1708,12 @@ void MissionController::_recalcMissionFlightStatus()
_missionFlightStatus.batteryChangePoint = 0;
}
if (linkStartToHome) {
// Home position is taken into account for min/max values
_minAMSLAltitude = std::fmin(_minAMSLAltitude, _settingsItem->plannedHomePositionAltitude()->rawValue().toDouble());
_maxAMSLAltitude = std::fmax(_maxAMSLAltitude, _settingsItem->plannedHomePositionAltitude()->rawValue().toDouble());
}
emit missionMaxTelemetryChanged (_missionFlightStatus.maxTelemetryDistance);
emit missionDistanceChanged (_missionFlightStatus.totalDistance);
emit missionHoverDistanceChanged (_missionFlightStatus.hoverDistance);

2
src/MissionManager/MissionSettingsItem.cc

@ -286,7 +286,7 @@ double MissionSettingsItem::specifiedFlightSpeed(void) @@ -286,7 +286,7 @@ double MissionSettingsItem::specifiedFlightSpeed(void)
void MissionSettingsItem::_setHomeAltFromTerrain(double terrainAltitude)
{
if (!_plannedHomePositionFromVehicle && !qIsNaN(terrainAltitude)) {
qDebug() << "MissionSettingsItem::_setHomeAltFromTerrain" << terrainAltitude;
qCDebug(MissionSettingsItemLog) << "MissionSettingsItem::_setHomeAltFromTerrain" << terrainAltitude;
_plannedHomePositionAltitudeFact.setRawValue(terrainAltitude);
}
}

64
src/MissionManager/TransectStyleComplexItem.cc

@ -18,6 +18,8 @@ @@ -18,6 +18,8 @@
#include "QGCApplication.h"
#include "PlanMasterController.h"
#include "FlightPathSegment.h"
#include "MissionCommandTree.h"
#include "MissionCommandUIInfo.h"
#include <QPolygonF>
@ -292,12 +294,14 @@ bool TransectStyleComplexItem::_load(const QJsonObject& complexObject, bool forP @@ -292,12 +294,14 @@ bool TransectStyleComplexItem::_load(const QJsonObject& complexObject, bool forP
if (!forPresets) {
// We have to grovel through mission items to determine min/max alt
_minAMSLAltitude = 0;
_maxAMSLAltitude = 0;
_minAMSLAltitude = qQNaN();
_maxAMSLAltitude = qQNaN();
MissionCommandTree* commandTree = qgcApp()->toolbox()->missionCommandTree();
for (const MissionItem* missionItem: _loadedMissionItems) {
if (missionItem->command() == MAV_CMD_NAV_WAYPOINT || missionItem->command() == MAV_CMD_CONDITION_GATE) {
_minAMSLAltitude = qMin(_minAMSLAltitude, missionItem->param7());
_maxAMSLAltitude = qMax(_maxAMSLAltitude, missionItem->param7());
const MissionCommandUIInfo* uiInfo = commandTree->getUIInfo(_controllerVehicle, QGCMAVLink::VehicleClassGeneric, missionItem->command());
if (uiInfo && uiInfo->specifiesCoordinate() && !uiInfo->isStandaloneCoordinate()) {
_minAMSLAltitude = std::fmin(_minAMSLAltitude, missionItem->param7());
_maxAMSLAltitude = std::fmax(_maxAMSLAltitude, missionItem->param7());
}
}
}
@ -1152,40 +1156,58 @@ void TransectStyleComplexItem::_recalcComplexDistance(void) @@ -1152,40 +1156,58 @@ void TransectStyleComplexItem::_recalcComplexDistance(void)
double TransectStyleComplexItem::amslEntryAlt(void) const
{
double alt = qQNaN();
if (_followTerrain) {
if (_loadedMissionItems.count()) {
return _loadedMissionItems.first()->param7();
// The first item might not be a waypoint we have to find it.
MissionCommandTree* commandTree = qgcApp()->toolbox()->missionCommandTree();
for (int i=0; i<_loadedMissionItems.count(); i++) {
MissionItem* item = _loadedMissionItems[i];
const MissionCommandUIInfo* uiInfo = commandTree->getUIInfo(_controllerVehicle, QGCMAVLink::VehicleClassGeneric, item->command());
if (uiInfo && uiInfo->specifiesCoordinate() && !uiInfo->isStandaloneCoordinate()) {
alt = item->param7();
break;
}
}
} else {
if (_transectCount() == 0) {
return qQNaN();
} else {
bool addHomeAlt = !followTerrain() && _cameraCalc.distanceToSurfaceRelative();
return _transects.first().first().coord.altitude() + (addHomeAlt ? _missionController->plannedHomePosition().altitude() : 0);
if (_rgFlightPathCoordInfo.count() != 0) {
alt = _rgFlightPathCoordInfo.first().coord.altitude();
}
}
} else {
return _cameraCalc.distanceToSurface()->rawValue().toDouble() + (_cameraCalc.distanceToSurfaceRelative() ? _missionController->plannedHomePosition().altitude() : 0) ;
alt = _cameraCalc.distanceToSurface()->rawValue().toDouble() + (_cameraCalc.distanceToSurfaceRelative() ? _missionController->plannedHomePosition().altitude() : 0) ;
}
return alt;
}
double TransectStyleComplexItem::amslExitAlt(void) const
{
double alt = qQNaN();
if (_followTerrain) {
if (_loadedMissionItems.count()) {
return _loadedMissionItems.last()->param7();
// The last item might not be a waypoint we have to find it.
MissionCommandTree* commandTree = qgcApp()->toolbox()->missionCommandTree();
for (int i=_loadedMissionItems.count()-1; i>0; i--) {
MissionItem* item = _loadedMissionItems[i];
const MissionCommandUIInfo* uiInfo = commandTree->getUIInfo(_controllerVehicle, QGCMAVLink::VehicleClassGeneric, item->command());
if (uiInfo && uiInfo->specifiesCoordinate() && !uiInfo->isStandaloneCoordinate()) {
alt = item->param7();
break;
}
}
} else {
if (_transectCount() == 0) {
return qQNaN();
} else {
bool addHomeAlt = !followTerrain() && _cameraCalc.distanceToSurfaceRelative();
return _transects.last().last().coord.altitude() + (addHomeAlt ? _missionController->plannedHomePosition().altitude() : 0);
if (_rgFlightPathCoordInfo.count() != 0) {
alt = _rgFlightPathCoordInfo.last().coord.altitude();
}
}
} else {
return _cameraCalc.distanceToSurface()->rawValue().toDouble() + (_cameraCalc.distanceToSurfaceRelative() ? _missionController->plannedHomePosition().altitude() : 0) ;
alt = _cameraCalc.distanceToSurface()->rawValue().toDouble() + (_cameraCalc.distanceToSurfaceRelative() ? _missionController->plannedHomePosition().altitude() : 0) ;
}
return alt;
}
void TransectStyleComplexItem::applyNewAltitude(double newAltitude)

11
src/PlanView/TerrainStatus.qml

@ -26,22 +26,15 @@ Rectangle { @@ -26,22 +26,15 @@ Rectangle {
signal setCurrentSeqNum(int seqNum)
readonly property real _heightBuffer: 10
property real _margins: ScreenTools.defaultFontPixelWidth / 2
property var _visualItems: missionController.visualItems
property real _altRange: _maxAMSLAltitude - _minAMSLAltitude
property real _indicatorSpacing: 5
property real _minAMSLAltitude: isNaN(missionController.minAMSLAltitude) ? 0 : missionController.minAMSLAltitude - _heightBuffer
property real _maxAMSLAltitude: isNaN(missionController.maxAMSLAltitude) ? 100 : missionController.maxAMSLAltitude + _heightBuffer
property real _minAMSLAltitude: isNaN(terrainProfile.minAMSLAlt) ? 0 : terrainProfile.minAMSLAlt
property real _maxAMSLAltitude: isNaN(terrainProfile.maxAMSLAlt) ? 100 : terrainProfile.maxAMSLAlt
property real _missionDistance: isNaN(missionController.missionDistance) ? 100 : missionController.missionDistance
property var _unitsConversion: QGroundControl.unitsConversion
function yPosFromAlt(alt) {
var fullHeight = terrainProfileFlickable.height
return ((alt - _minAMSLAltitude) / _fullHeight) * _fullHeight
}
QGCPalette { id: qgcPal }
QGCLabel {

96
src/QmlControls/TerrainProfile.cc

@ -45,9 +45,7 @@ void TerrainProfile::setMissionController(MissionController* missionController) @@ -45,9 +45,7 @@ void TerrainProfile::setMissionController(MissionController* missionController)
emit missionControllerChanged();
connect(_missionController, &MissionController::visualItemsChanged, this, &TerrainProfile::_newVisualItems);
connect(_missionController, &MissionController::minAMSLAltitudeChanged, this, &TerrainProfile::minAMSLAltChanged);
connect(this, &TerrainProfile::horizontalMarginChanged, this, &TerrainProfile::_updateSignal, Qt::QueuedConnection);
connect(this, &TerrainProfile::visibleWidthChanged, this, &TerrainProfile::_updateSignal, Qt::QueuedConnection);
connect(_missionController, &MissionController::recalcTerrainProfile, this, &TerrainProfile::_updateSignal, Qt::QueuedConnection);
}
@ -76,7 +74,7 @@ void TerrainProfile::_createGeometry(QSGGeometryNode*& geometryNode, QSGGeometry @@ -76,7 +74,7 @@ void TerrainProfile::_createGeometry(QSGGeometryNode*& geometryNode, QSGGeometry
geometryNode->setGeometry(geometry);
}
void TerrainProfile::_updateSegmentCounts(FlightPathSegment* segment, int& cFlightProfileSegments, int& cTerrainProfilePoints, int& cMissingTerrainSegments, int& cTerrainCollisionSegments, double& maxTerrainHeight)
void TerrainProfile::_updateSegmentCounts(FlightPathSegment* segment, int& cFlightProfileSegments, int& cTerrainProfilePoints, int& cMissingTerrainSegments, int& cTerrainCollisionSegments, double& minTerrainHeight, double& maxTerrainHeight)
{
if (_shouldAddFlightProfileSegment(segment)) {
cFlightProfileSegments++;
@ -87,7 +85,8 @@ void TerrainProfile::_updateSegmentCounts(FlightPathSegment* segment, int& cFlig @@ -87,7 +85,8 @@ void TerrainProfile::_updateSegmentCounts(FlightPathSegment* segment, int& cFlig
} else {
cTerrainProfilePoints += segment->amslTerrainHeights().count();
for (int i=0; i<segment->amslTerrainHeights().count(); i++) {
maxTerrainHeight = qMax(maxTerrainHeight, segment->amslTerrainHeights()[i].value<double>());
minTerrainHeight = std::fmin(minTerrainHeight, segment->amslTerrainHeights()[i].value<double>());
maxTerrainHeight = std::fmax(maxTerrainHeight, segment->amslTerrainHeights()[i].value<double>());
}
}
if (segment->terrainCollision()) {
@ -111,12 +110,12 @@ void TerrainProfile::_addTerrainProfileSegment(FlightPathSegment* segment, doubl @@ -111,12 +110,12 @@ void TerrainProfile::_addTerrainProfileSegment(FlightPathSegment* segment, doubl
}
// Move along the y axis which is a view or terrain height as a percentage between the min/max AMSL altitude for all segments
double amslTerrainHeight = segment->amslTerrainHeights()[heightIndex].value<double>();
double terrainHeightPercent = qMax(((amslTerrainHeight - _missionController->minAMSLAltitude()) / amslAltRange), 0.0);
double amslTerrainHeight = segment->amslTerrainHeights()[heightIndex].value<double>();
double terrainHeightPercent = (amslTerrainHeight - _minAMSLAlt) / amslAltRange;
float x = (currentDistance + terrainDistance) * _pixelsPerMeter;
float y = _availableHeight() - (terrainHeightPercent * _availableHeight());
_setVertex(terrainVertices[terrainProfileVertexIndex++], x, y);
float y = height() - (terrainHeightPercent * height());
terrainVertices[terrainProfileVertexIndex++].set(x, y);
}
}
@ -124,9 +123,9 @@ void TerrainProfile::_addMissingTerrainSegment(FlightPathSegment* segment, doubl @@ -124,9 +123,9 @@ void TerrainProfile::_addMissingTerrainSegment(FlightPathSegment* segment, doubl
{
if (_shouldAddMissingTerrainSegment(segment)) {
float x = currentDistance * _pixelsPerMeter;
float y = _availableHeight();
_setVertex(missingTerrainVertices[missingterrainProfileVertexIndex++], x, y);
_setVertex(missingTerrainVertices[missingterrainProfileVertexIndex++], x + (segment->totalDistance() * _pixelsPerMeter), y);
float y = height();
missingTerrainVertices[missingterrainProfileVertexIndex++].set(x, y);
missingTerrainVertices[missingterrainProfileVertexIndex++].set(x + (segment->totalDistance() * _pixelsPerMeter), y);
}
}
@ -135,18 +134,18 @@ void TerrainProfile::_addTerrainCollisionSegment(FlightPathSegment* segment, dou @@ -135,18 +134,18 @@ void TerrainProfile::_addTerrainCollisionSegment(FlightPathSegment* segment, dou
if (segment->terrainCollision()) {
double amslCoord1Height = segment->coord1AMSLAlt();
double amslCoord2Height = segment->coord2AMSLAlt();
double coord1HeightPercent = qMax(((amslCoord1Height - _missionController->minAMSLAltitude()) / amslAltRange), 0.0);
double coord2HeightPercent = qMax(((amslCoord2Height - _missionController->minAMSLAltitude()) / amslAltRange), 0.0);
double coord1HeightPercent = (amslCoord1Height - _minAMSLAlt) / amslAltRange;
double coord2HeightPercent = (amslCoord2Height - _minAMSLAlt) / amslAltRange;
float x = currentDistance * _pixelsPerMeter;
float y = _availableHeight() - (coord1HeightPercent * _availableHeight());
float y = height() - (coord1HeightPercent * height());
_setVertex(terrainCollisionVertices[terrainCollisionVertexIndex++], x, y);
terrainCollisionVertices[terrainCollisionVertexIndex++].set(x, y);
x += segment->totalDistance() * _pixelsPerMeter;
y = _availableHeight() - (coord2HeightPercent * _availableHeight());
y = height() - (coord2HeightPercent * height());
_setVertex(terrainCollisionVertices[terrainCollisionVertexIndex++], x, y);
terrainCollisionVertices[terrainCollisionVertexIndex++].set(x, y);
}
}
@ -158,18 +157,18 @@ void TerrainProfile::_addFlightProfileSegment(FlightPathSegment* segment, double @@ -158,18 +157,18 @@ void TerrainProfile::_addFlightProfileSegment(FlightPathSegment* segment, double
double amslCoord1Height = segment->coord1AMSLAlt();
double amslCoord2Height = segment->coord2AMSLAlt();
double coord1HeightPercent = qMax(((amslCoord1Height - _missionController->minAMSLAltitude()) / amslAltRange), 0.0);
double coord2HeightPercent = qMax(((amslCoord2Height - _missionController->minAMSLAltitude()) / amslAltRange), 0.0);
double coord1HeightPercent = (amslCoord1Height - _minAMSLAlt) / amslAltRange;
double coord2HeightPercent = (amslCoord2Height - _minAMSLAlt) / amslAltRange;
float x = currentDistance * _pixelsPerMeter;
float y = _availableHeight() - (coord1HeightPercent * _availableHeight());
float y = height() - (coord1HeightPercent * height());
_setVertex(flightProfileVertices[flightProfileVertexIndex++], x, y);
flightProfileVertices[flightProfileVertexIndex++].set(x, y);
x += segment->totalDistance() * _pixelsPerMeter;
y = _availableHeight() - (coord2HeightPercent * _availableHeight());
y = height() - (coord2HeightPercent * height());
_setVertex(flightProfileVertices[flightProfileVertexIndex++], x, y);
flightProfileVertices[flightProfileVertexIndex++].set(x, y);
}
QSGNode* TerrainProfile::updatePaintNode(QSGNode* oldNode, QQuickItem::UpdatePaintNodeData* /*updatePaintNodeData*/)
@ -183,7 +182,8 @@ QSGNode* TerrainProfile::updatePaintNode(QSGNode* oldNode, QQuickItem::UpdatePai @@ -183,7 +182,8 @@ QSGNode* TerrainProfile::updatePaintNode(QSGNode* oldNode, QQuickItem::UpdatePai
int cMissingTerrainSegments = 0;
int cFlightProfileSegments = 0;
int cTerrainCollisionSegments = 0;
double maxTerrainHeight = 0;
double minTerrainHeight = qQNaN();
double maxTerrainHeight = qQNaN();
// First we need to determine:
// - how many terrain profile vertices we need
@ -198,24 +198,37 @@ QSGNode* TerrainProfile::updatePaintNode(QSGNode* oldNode, QQuickItem::UpdatePai @@ -198,24 +198,37 @@ QSGNode* TerrainProfile::updatePaintNode(QSGNode* oldNode, QQuickItem::UpdatePai
if (visualItem->simpleFlightPathSegment()) {
FlightPathSegment* segment = visualItem->simpleFlightPathSegment();
_updateSegmentCounts(segment, cFlightProfileSegments, cTerrainProfilePoints, cMissingTerrainSegments, cTerrainCollisionSegments, maxTerrainHeight);
_updateSegmentCounts(segment, cFlightProfileSegments, cTerrainProfilePoints, cMissingTerrainSegments, cTerrainCollisionSegments, minTerrainHeight, maxTerrainHeight);
}
if (complexItem) {
for (int segmentIndex=0; segmentIndex<complexItem->flightPathSegments()->count(); segmentIndex++) {
FlightPathSegment* segment = complexItem->flightPathSegments()->value<FlightPathSegment*>(segmentIndex);
_updateSegmentCounts(segment, cFlightProfileSegments, cTerrainProfilePoints, cMissingTerrainSegments, cTerrainCollisionSegments, maxTerrainHeight);
_updateSegmentCounts(segment, cFlightProfileSegments, cTerrainProfilePoints, cMissingTerrainSegments, cTerrainCollisionSegments, minTerrainHeight, maxTerrainHeight);
}
}
}
double amslAltRange = qMax(_missionController->maxAMSLAltitude(), maxTerrainHeight) - _missionController->minAMSLAltitude();
// The profile view min/max is setup to include a full terrain profile as well as the flight path segments.
_minAMSLAlt = std::fmin(_missionController->minAMSLAltitude(), minTerrainHeight);
_maxAMSLAlt = std::fmax(_missionController->maxAMSLAltitude(), maxTerrainHeight);
// We add a buffer to the min/max alts such that the visuals don't draw lines right at the edges of the display
double amslAltRange = _maxAMSLAlt - _minAMSLAlt;
double amslAltRangeBuffer = amslAltRange * 0.1;
_maxAMSLAlt += amslAltRangeBuffer;
if (_minAMSLAlt > 0.0) {
_minAMSLAlt -= amslAltRangeBuffer;
_minAMSLAlt = std::fmax(_minAMSLAlt, 0.0);
}
amslAltRange = _maxAMSLAlt - _minAMSLAlt;
static int counter = 0;
qCDebug(TerrainProfileLog) << QStringLiteral("updatePaintNode counter:%1 cFlightProfileSegments:%2 cTerrainProfilePoints:%3 cMissingTerrainSegments:%4 cTerrainCollisionSegments:%5 minAMSLAlt:%6 maxTerrainHeight:%7")
.arg(counter++).arg(cFlightProfileSegments).arg(cTerrainProfilePoints).arg(cMissingTerrainSegments).arg(cTerrainCollisionSegments).arg(minAMSLAlt()).arg(maxTerrainHeight);
qCDebug(TerrainProfileLog) << "missionController min/max" << _missionController->minAMSLAltitude() << _missionController->maxAMSLAltitude();
qCDebug(TerrainProfileLog) << QStringLiteral("updatePaintNode counter:%1 cFlightProfileSegments:%2 cTerrainProfilePoints:%3 cMissingTerrainSegments:%4 cTerrainCollisionSegments:%5 _minAMSLAlt:%6 _maxAMSLAlt:%7 maxTerrainHeight:%8")
.arg(counter++).arg(cFlightProfileSegments).arg(cTerrainProfilePoints).arg(cMissingTerrainSegments).arg(cTerrainCollisionSegments).arg(_minAMSLAlt).arg(_maxAMSLAlt).arg(maxTerrainHeight);
_pixelsPerMeter = (_visibleWidth - (_horizontalMargin * 2)) / _missionController->missionDistance();
_pixelsPerMeter = _visibleWidth / _missionController->missionDistance();
// Instantiate nodes
if (!rootNode) {
@ -309,31 +322,12 @@ QSGNode* TerrainProfile::updatePaintNode(QSGNode* oldNode, QQuickItem::UpdatePai @@ -309,31 +322,12 @@ QSGNode* TerrainProfile::updatePaintNode(QSGNode* oldNode, QQuickItem::UpdatePai
emit implicitWidthChanged();
emit widthChanged();
emit pixelsPerMeterChanged();
double newMaxAMSLAlt = qMax(_missionController->maxAMSLAltitude(), maxTerrainHeight);
if (!QGC::fuzzyCompare(newMaxAMSLAlt, _maxAMSLAlt)) {
_maxAMSLAlt = newMaxAMSLAlt;
emit maxAMSLAltChanged();
}
emit minAMSLAltChanged();
emit maxAMSLAltChanged();
return rootNode;
}
double TerrainProfile::minAMSLAlt(void)
{
return _missionController->minAMSLAltitude();
}
double TerrainProfile::_availableHeight(void) const
{
return height() - (_verticalMargin * 2);
}
void TerrainProfile::_setVertex(QSGGeometry::Point2D& vertex, double x, double y)
{
vertex.set(x + _horizontalMargin, y + _verticalMargin);
}
bool TerrainProfile::_shouldAddFlightProfileSegment (FlightPathSegment* segment)
{
return !qIsNaN(segment->coord1AMSLAlt()) && !qIsNaN(segment->coord2AMSLAlt());

16
src/QmlControls/TerrainProfile.h

@ -29,16 +29,13 @@ class TerrainProfile : public QQuickItem @@ -29,16 +29,13 @@ class TerrainProfile : public QQuickItem
public:
TerrainProfile(QQuickItem *parent = nullptr);
Q_PROPERTY(double horizontalMargin MEMBER _horizontalMargin NOTIFY horizontalMarginChanged)
Q_PROPERTY(double visibleWidth MEMBER _visibleWidth NOTIFY visibleWidthChanged)
Q_PROPERTY(MissionController* missionController READ missionController WRITE setMissionController NOTIFY missionControllerChanged)
Q_PROPERTY(double pixelsPerMeter MEMBER _pixelsPerMeter NOTIFY pixelsPerMeterChanged)
Q_PROPERTY(double minAMSAlt READ minAMSLAlt NOTIFY minAMSLAltChanged)
Q_PROPERTY(double maxAMSAlt MEMBER _maxAMSLAlt NOTIFY maxAMSLAltChanged)
Q_PROPERTY(double minAMSLAlt MEMBER _minAMSLAlt NOTIFY minAMSLAltChanged)
Q_PROPERTY(double maxAMSLAlt MEMBER _maxAMSLAlt NOTIFY maxAMSLAltChanged)
MissionController* missionController (void) { return _missionController; }
double minAMSLAlt (void);
double maxAMSLAlt (void) { return _maxAMSLAlt; }
MissionController* missionController(void) { return _missionController; }
void setMissionController(MissionController* missionController);
@ -51,7 +48,6 @@ public: @@ -51,7 +48,6 @@ public:
signals:
void missionControllerChanged (void);
void visibleWidthChanged (void);
void horizontalMarginChanged (void);
void pixelsPerMeterChanged (void);
void minAMSLAltChanged (void);
void maxAMSLAltChanged (void);
@ -62,26 +58,22 @@ private slots: @@ -62,26 +58,22 @@ private slots:
private:
void _createGeometry (QSGGeometryNode*& geometryNode, QSGGeometry*& geometry, QSGGeometry::DrawingMode drawingMode, const QColor& color);
void _updateSegmentCounts (FlightPathSegment* segment, int& cFlightProfileSegments, int& cTerrainPoints, int& cMissingTerrainSegments, int& cTerrainCollisionSegments, double& maxTerrainHeight);
void _updateSegmentCounts (FlightPathSegment* segment, int& cFlightProfileSegments, int& cTerrainPoints, int& cMissingTerrainSegments, int& cTerrainCollisionSegments, double& minTerrainHeight, double& maxTerrainHeight);
void _addTerrainProfileSegment (FlightPathSegment* segment, double currentDistance, double amslAltRange, QSGGeometry::Point2D* terrainProfileVertices, int& terrainVertexIndex);
void _addMissingTerrainSegment (FlightPathSegment* segment, double currentDistance, QSGGeometry::Point2D* missingTerrainVertices, int& missingTerrainVertexIndex);
void _addTerrainCollisionSegment (FlightPathSegment* segment, double currentDistance, double amslAltRange, QSGGeometry::Point2D* terrainCollisionVertices, int& terrainCollisionVertexIndex);
void _addFlightProfileSegment (FlightPathSegment* segment, double currentDistance, double amslAltRange, QSGGeometry::Point2D* flightProfileVertices, int& flightProfileVertexIndex);
double _availableHeight (void) const;
void _setVertex (QSGGeometry::Point2D& vertex, double x, double y);
bool _shouldAddFlightProfileSegment (FlightPathSegment* segment);
bool _shouldAddMissingTerrainSegment (FlightPathSegment* segment);
MissionController* _missionController = nullptr;
QmlObjectListModel* _visualItems = nullptr;
double _visibleWidth = 0;
double _horizontalMargin = 0;
double _pixelsPerMeter = 0;
double _minAMSLAlt = 0;
double _maxAMSLAlt = 0;
static const int _lineWidth = 7;
static const int _verticalMargin = 0;
Q_DISABLE_COPY(TerrainProfile)
};

6
src/ui/preferences/GeneralSettings.qml

@ -408,14 +408,14 @@ Rectangle { @@ -408,14 +408,14 @@ Rectangle {
Layout.fillWidth: false
anchors.horizontalCenter: parent.horizontalCenter
flow: GridLayout.TopToBottom
rows: 4
rows: 5
Repeater {
model: [ qsTr("Distance"), qsTr("Area"), qsTr("Speed"), qsTr("Temperature") ]
model: [ qsTr("Horizontal Distance"), qsTr("Vertical Distance"), qsTr("Area"), qsTr("Speed"), qsTr("Temperature") ]
QGCLabel { text: modelData }
}
Repeater {
model: [ QGroundControl.settingsManager.unitsSettings.horizontalDistanceUnits, QGroundControl.settingsManager.unitsSettings.areaUnits, QGroundControl.settingsManager.unitsSettings.speedUnits, QGroundControl.settingsManager.unitsSettings.temperatureUnits ]
model: [ QGroundControl.settingsManager.unitsSettings.horizontalDistanceUnits, QGroundControl.settingsManager.unitsSettings.verticalDistanceUnits, QGroundControl.settingsManager.unitsSettings.areaUnits, QGroundControl.settingsManager.unitsSettings.speedUnits, QGroundControl.settingsManager.unitsSettings.temperatureUnits ]
FactComboBox {
Layout.preferredWidth: _comboFieldWidth
fact: modelData

Loading…
Cancel
Save