Commit 62a24a38 authored by DoinLakeFlyer's avatar DoinLakeFlyer

parent 0f32617d
......@@ -590,6 +590,7 @@ HEADERS += \
src/MissionManager/GeoFenceController.h \
src/MissionManager/GeoFenceManager.h \
src/MissionManager/KMLPlanDomDocument.h \
src/MissionManager/LandingComplexItem.h \
src/MissionManager/MissionCommandList.h \
src/MissionManager/MissionCommandTree.h \
src/MissionManager/MissionCommandUIInfo.h \
......@@ -800,6 +801,7 @@ SOURCES += \
src/MissionManager/GeoFenceController.cc \
src/MissionManager/GeoFenceManager.cc \
src/MissionManager/KMLPlanDomDocument.cc \
src/MissionManager/LandingComplexItem.cc \
src/MissionManager/MissionCommandList.cc \
src/MissionManager/MissionCommandTree.cc \
src/MissionManager/MissionCommandUIInfo.cc \
......
......@@ -49,7 +49,7 @@ const char* FixedWingLandingComplexItem::_jsonLandingAltitudeRelativeKey = "lan
const char* FixedWingLandingComplexItem::_jsonLoiterAltitudeRelativeKey = "loiterAltitudeRelative";
FixedWingLandingComplexItem::FixedWingLandingComplexItem(PlanMasterController* masterController, bool flyView, QObject* parent)
: ComplexMissionItem (masterController, flyView, parent)
: LandingComplexItem (masterController, flyView, parent)
, _metaDataMap (FactMetaData::createMapFromJsonFile(QStringLiteral(":/json/FWLandingPattern.FactMetaData.json"), this))
, _landingDistanceFact (settingsGroup, _metaDataMap[loiterToLandDistanceName])
, _loiterAltitudeFact (settingsGroup, _metaDataMap[loiterAltitudeName])
......@@ -498,39 +498,6 @@ bool FixedWingLandingComplexItem::scanForItem(QmlObjectListModel* visualItems, b
return true;
}
double FixedWingLandingComplexItem::complexDistance(void) const
{
return _loiterCoordinate.distanceTo(_landingCoordinate);
}
void FixedWingLandingComplexItem::setLandingCoordinate(const QGeoCoordinate& coordinate)
{
if (coordinate != _landingCoordinate) {
_landingCoordinate = coordinate;
if (_landingCoordSet) {
emit exitCoordinateChanged(coordinate);
emit landingCoordinateChanged(coordinate);
} else {
_ignoreRecalcSignals = true;
emit exitCoordinateChanged(coordinate);
emit landingCoordinateChanged(coordinate);
_ignoreRecalcSignals = false;
_landingCoordSet = true;
_recalcFromHeadingAndDistanceChange();
emit landingCoordSetChanged(true);
}
}
}
void FixedWingLandingComplexItem::setLoiterCoordinate(const QGeoCoordinate& coordinate)
{
if (coordinate != _loiterCoordinate) {
_loiterCoordinate = coordinate;
emit coordinateChanged(coordinate);
emit loiterCoordinateChanged(coordinate);
}
}
double FixedWingLandingComplexItem::_mathematicAngleToHeading(double angle)
{
double heading = (angle - 90) * -1;
......@@ -629,17 +596,6 @@ void FixedWingLandingComplexItem::_recalcFromHeadingAndDistanceChange(void)
}
}
QPointF FixedWingLandingComplexItem::_rotatePoint(const QPointF& point, const QPointF& origin, double angle)
{
QPointF rotated;
double radians = (M_PI / 180.0) * angle;
rotated.setX(((point.x() - origin.x()) * cos(radians)) - ((point.y() - origin.y()) * sin(radians)) + origin.x());
rotated.setY(((point.x() - origin.x()) * sin(radians)) + ((point.y() - origin.y()) * cos(radians)) + origin.y());
return rotated;
}
void FixedWingLandingComplexItem::_recalcFromCoordinateChange(void)
{
// Fixed:
......@@ -752,24 +708,3 @@ double FixedWingLandingComplexItem::amslExitAlt(void) const
return _landingAltitudeFact.rawValue().toDouble() + (_altitudesAreRelative ? _missionController->plannedHomePosition().altitude() : 0);
}
// Never call this method directly. If you want to update the flight segments you emit _updateFlightPathSegmentsSignal()
void FixedWingLandingComplexItem::_updateFlightPathSegmentsDontCallDirectly(void)
{
if (_cTerrainCollisionSegments != 0) {
_cTerrainCollisionSegments = 0;
emit terrainCollisionChanged(false);
}
_flightPathSegments.beginReset();
_flightPathSegments.clearAndDeleteContents();
_appendFlightPathSegment(_loiterTangentCoordinate, amslEntryAlt(), _landingCoordinate, amslExitAlt()); // Loiter to land
_appendFlightPathSegment(_landingCoordinate, amslEntryAlt(), _landingCoordinate, amslExitAlt()); // Land to ground
_flightPathSegments.endReset();
if (_cTerrainCollisionSegments != 0) {
emit terrainCollisionChanged(true);
}
_masterController->missionController()->recalcTerrainProfile();
}
......@@ -10,7 +10,7 @@
#ifndef FixedWingLandingComplexItem_H
#define FixedWingLandingComplexItem_H
#include "ComplexMissionItem.h"
#include "LandingComplexItem.h"
#include "MissionItem.h"
#include "Fact.h"
#include "QGCLoggingCategory.h"
......@@ -20,46 +20,27 @@ Q_DECLARE_LOGGING_CATEGORY(FixedWingLandingComplexItemLog)
class FWLandingPatternTest;
class PlanMasterController;
class FixedWingLandingComplexItem : public ComplexMissionItem
class FixedWingLandingComplexItem : public LandingComplexItem
{
Q_OBJECT
public:
FixedWingLandingComplexItem(PlanMasterController* masterController, bool flyView, QObject* parent);
Q_PROPERTY(Fact* loiterAltitude READ loiterAltitude CONSTANT)
Q_PROPERTY(Fact* loiterRadius READ loiterRadius CONSTANT)
Q_PROPERTY(Fact* landingAltitude READ landingAltitude CONSTANT)
Q_PROPERTY(Fact* landingHeading READ landingHeading CONSTANT)
Q_PROPERTY(Fact* valueSetIsDistance READ valueSetIsDistance CONSTANT)
Q_PROPERTY(Fact* landingDistance READ landingDistance CONSTANT)
Q_PROPERTY(Fact* glideSlope READ glideSlope CONSTANT)
Q_PROPERTY(bool loiterClockwise MEMBER _loiterClockwise NOTIFY loiterClockwiseChanged)
Q_PROPERTY(bool altitudesAreRelative MEMBER _altitudesAreRelative NOTIFY altitudesAreRelativeChanged)
Q_PROPERTY(Fact* stopTakingPhotos READ stopTakingPhotos CONSTANT)
Q_PROPERTY(Fact* stopTakingVideo READ stopTakingVideo CONSTANT)
Q_PROPERTY(QGeoCoordinate loiterCoordinate READ loiterCoordinate WRITE setLoiterCoordinate NOTIFY loiterCoordinateChanged)
Q_PROPERTY(QGeoCoordinate loiterTangentCoordinate READ loiterTangentCoordinate NOTIFY loiterTangentCoordinateChanged)
Q_PROPERTY(QGeoCoordinate landingCoordinate READ landingCoordinate WRITE setLandingCoordinate NOTIFY landingCoordinateChanged)
Q_PROPERTY(bool landingCoordSet MEMBER _landingCoordSet NOTIFY landingCoordSetChanged)
Q_INVOKABLE void moveLandingPosition(const QGeoCoordinate& coordinate); // Maintains the current landing distance and heading
Fact* loiterAltitude (void) { return &_loiterAltitudeFact; }
Fact* loiterRadius (void) { return &_loiterRadiusFact; }
Fact* landingAltitude (void) { return &_landingAltitudeFact; }
Fact* landingDistance (void) { return &_landingDistanceFact; }
Fact* landingHeading (void) { return &_landingHeadingFact; }
Fact* loiterAltitude (void) final { return &_loiterAltitudeFact; }
Fact* loiterRadius (void) final { return &_loiterRadiusFact; }
Fact* landingAltitude (void) final { return &_landingAltitudeFact; }
Fact* landingDistance (void) final { return &_landingDistanceFact; }
Fact* landingHeading (void) final { return &_landingHeadingFact; }
Fact* stopTakingPhotos (void) final { return &_stopTakingPhotosFact; }
Fact* stopTakingVideo (void) final { return &_stopTakingVideoFact; }
Fact* glideSlope (void) { return &_glideSlopeFact; }
Fact* stopTakingPhotos (void) { return &_stopTakingPhotosFact; }
Fact* stopTakingVideo (void) { return &_stopTakingVideoFact; }
Fact* valueSetIsDistance (void) { return &_valueSetIsDistanceFact; }
QGeoCoordinate landingCoordinate (void) const { return _landingCoordinate; }
QGeoCoordinate loiterCoordinate (void) const { return _loiterCoordinate; }
QGeoCoordinate loiterTangentCoordinate (void) const { return _loiterTangentCoordinate; }
void setLandingCoordinate (const QGeoCoordinate& coordinate);
void setLoiterCoordinate (const QGeoCoordinate& coordinate);
/// Scans the loaded items for a landing pattern complex item
static bool scanForItem(QmlObjectListModel* visualItems, bool flyView, PlanMasterController* masterController);
......@@ -70,7 +51,6 @@ public:
// Overrides from ComplexMissionItem
QString patternName (void) const final { return name; }
double complexDistance (void) const final;
int lastSequenceNumber (void) const final;
bool load (const QJsonObject& complexObject, int sequenceNumber, QString& errorString) final;
double greatestDistanceTo (const QGeoCoordinate &other) const final;
......@@ -121,14 +101,7 @@ public:
static const char* valueSetIsDistanceName;
signals:
void loiterCoordinateChanged (QGeoCoordinate coordinate);
void loiterTangentCoordinateChanged (QGeoCoordinate coordinate);
void landingCoordinateChanged (QGeoCoordinate coordinate);
void landingCoordSetChanged (bool landingCoordSet);
void loiterClockwiseChanged (bool loiterClockwise);
void altitudesAreRelativeChanged (bool altitudesAreRelative);
void valueSetIsDistanceChanged (bool valueSetIsDistance);
void _updateFlightPathSegmentsSignal(void);
private slots:
void _recalcFromHeadingAndDistanceChange (void);
......@@ -141,22 +114,10 @@ private slots:
void _setDirty (void);
void _glideSlopeChanged (void);
void _signalLastSequenceNumberChanged (void);
void _updateFlightPathSegmentsDontCallDirectly (void);
private:
QPointF _rotatePoint (const QPointF& point, const QPointF& origin, double angle);
void _calcGlideSlope (void);
int _sequenceNumber = 0;
bool _dirty = false;
QGeoCoordinate _loiterCoordinate;
QGeoCoordinate _loiterTangentCoordinate;
QGeoCoordinate _landingCoordinate;
bool _landingCoordSet = false;
bool _ignoreRecalcSignals = false;
bool _loiterClockwise = true;
bool _altitudesAreRelative = true;
QMap<QString, FactMetaData*> _metaDataMap;
Fact _landingDistanceFact;
......@@ -169,7 +130,6 @@ private:
Fact _stopTakingVideoFact;
Fact _valueSetIsDistanceFact;
static const char* _jsonLoiterCoordinateKey;
static const char* _jsonLoiterRadiusKey;
static const char* _jsonLoiterClockwiseKey;
......
/****************************************************************************
*
* (c) 2009-2020 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org>
*
* QGroundControl is licensed according to the terms in the file
* COPYING.md in the root of the source code directory.
*
****************************************************************************/
#include "LandingComplexItem.h"
#include "JsonHelper.h"
#include "MissionController.h"
#include "QGCGeo.h"
#include "SimpleMissionItem.h"
#include "PlanMasterController.h"
#include "FlightPathSegment.h"
#include <QPolygonF>
QGC_LOGGING_CATEGORY(LandingComplexItemLog, "LandingComplexItemLog")
LandingComplexItem::LandingComplexItem(PlanMasterController* masterController, bool flyView, QObject* parent)
: ComplexMissionItem (masterController, flyView, parent)
{
_isIncomplete = false;
// The follow is used to compress multiple recalc calls in a row to into a single call.
connect(this, &LandingComplexItem::_updateFlightPathSegmentsSignal, this, &LandingComplexItem::_updateFlightPathSegmentsDontCallDirectly, Qt::QueuedConnection);
qgcApp()->addCompressedSignal(QMetaMethod::fromSignal(&LandingComplexItem::_updateFlightPathSegmentsSignal));
}
double LandingComplexItem::complexDistance(void) const
{
return loiterCoordinate().distanceTo(loiterTangentCoordinate()) + loiterTangentCoordinate().distanceTo(landingCoordinate());
}
// Never call this method directly. If you want to update the flight segments you emit _updateFlightPathSegmentsSignal()
void LandingComplexItem::_updateFlightPathSegmentsDontCallDirectly(void)
{
if (_cTerrainCollisionSegments != 0) {
_cTerrainCollisionSegments = 0;
emit terrainCollisionChanged(false);
}
_flightPathSegments.beginReset();
_flightPathSegments.clearAndDeleteContents();
_appendFlightPathSegment(loiterCoordinate(), amslEntryAlt(), loiterTangentCoordinate(), amslEntryAlt());
_appendFlightPathSegment(loiterTangentCoordinate(), amslEntryAlt(), landingCoordinate(), amslEntryAlt());
_appendFlightPathSegment(landingCoordinate(), amslEntryAlt(), landingCoordinate(), amslExitAlt());
_flightPathSegments.endReset();
if (_cTerrainCollisionSegments != 0) {
emit terrainCollisionChanged(true);
}
_masterController->missionController()->recalcTerrainProfile();
}
void LandingComplexItem::setLandingCoordinate(const QGeoCoordinate& coordinate)
{
if (coordinate != _landingCoordinate) {
_landingCoordinate = coordinate;
if (_landingCoordSet) {
emit exitCoordinateChanged(coordinate);
emit landingCoordinateChanged(coordinate);
} else {
_ignoreRecalcSignals = true;
emit exitCoordinateChanged(coordinate);
emit landingCoordinateChanged(coordinate);
_ignoreRecalcSignals = false;
_landingCoordSet = true;
_recalcFromHeadingAndDistanceChange();
emit landingCoordSetChanged(true);
}
}
}
void LandingComplexItem::setLoiterCoordinate(const QGeoCoordinate& coordinate)
{
if (coordinate != _loiterCoordinate) {
_loiterCoordinate = coordinate;
emit coordinateChanged(coordinate);
emit loiterCoordinateChanged(coordinate);
}
}
QPointF LandingComplexItem::_rotatePoint(const QPointF& point, const QPointF& origin, double angle)
{
QPointF rotated;
double radians = (M_PI / 180.0) * angle;
rotated.setX(((point.x() - origin.x()) * cos(radians)) - ((point.y() - origin.y()) * sin(radians)) + origin.x());
rotated.setY(((point.x() - origin.x()) * sin(radians)) + ((point.y() - origin.y()) * cos(radians)) + origin.y());
return rotated;
}
/****************************************************************************
*
* (c) 2009-2020 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org>
*
* QGroundControl is licensed according to the terms in the file
* COPYING.md in the root of the source code directory.
*
****************************************************************************/
#pragma once
#include "ComplexMissionItem.h"
#include "MissionItem.h"
#include "Fact.h"
#include "QGCLoggingCategory.h"
Q_DECLARE_LOGGING_CATEGORY(LandingComplexItemLog)
class PlanMasterController;
// Base class for landing patterns complex items.
class LandingComplexItem : public ComplexMissionItem
{
Q_OBJECT
public:
LandingComplexItem(PlanMasterController* masterController, bool flyView, QObject* parent);
Q_PROPERTY(Fact* loiterAltitude READ loiterAltitude CONSTANT)
Q_PROPERTY(Fact* loiterRadius READ loiterRadius CONSTANT)
Q_PROPERTY(Fact* landingAltitude READ landingAltitude CONSTANT)
Q_PROPERTY(Fact* landingHeading READ landingHeading CONSTANT)
Q_PROPERTY(Fact* landingDistance READ landingDistance CONSTANT)
Q_PROPERTY(bool loiterClockwise MEMBER _loiterClockwise NOTIFY loiterClockwiseChanged)
Q_PROPERTY(bool altitudesAreRelative MEMBER _altitudesAreRelative NOTIFY altitudesAreRelativeChanged)
Q_PROPERTY(Fact* stopTakingPhotos READ stopTakingPhotos CONSTANT)
Q_PROPERTY(Fact* stopTakingVideo READ stopTakingVideo CONSTANT)
Q_PROPERTY(QGeoCoordinate loiterCoordinate READ loiterCoordinate WRITE setLoiterCoordinate NOTIFY loiterCoordinateChanged)
Q_PROPERTY(QGeoCoordinate loiterTangentCoordinate READ loiterTangentCoordinate NOTIFY loiterTangentCoordinateChanged)
Q_PROPERTY(QGeoCoordinate landingCoordinate READ landingCoordinate WRITE setLandingCoordinate NOTIFY landingCoordinateChanged)
Q_PROPERTY(bool landingCoordSet MEMBER _landingCoordSet NOTIFY landingCoordSetChanged)
virtual Fact* loiterAltitude (void) = 0;
virtual Fact* loiterRadius (void) = 0;
virtual Fact* landingAltitude (void) = 0;
virtual Fact* landingDistance (void) = 0;
virtual Fact* landingHeading (void) = 0;
virtual Fact* stopTakingPhotos (void) = 0;
virtual Fact* stopTakingVideo (void) = 0;
QGeoCoordinate landingCoordinate (void) const { return _landingCoordinate; }
QGeoCoordinate loiterCoordinate (void) const { return _loiterCoordinate; }
QGeoCoordinate loiterTangentCoordinate (void) const { return _loiterTangentCoordinate; }
void setLandingCoordinate (const QGeoCoordinate& coordinate);
void setLoiterCoordinate (const QGeoCoordinate& coordinate);
// Overrides from ComplexMissionItem
double complexDistance(void) const final;
signals:
void loiterCoordinateChanged (QGeoCoordinate coordinate);
void loiterTangentCoordinateChanged (QGeoCoordinate coordinate);
void landingCoordinateChanged (QGeoCoordinate coordinate);
void landingCoordSetChanged (bool landingCoordSet);
void loiterClockwiseChanged (bool loiterClockwise);
void altitudesAreRelativeChanged (bool altitudesAreRelative);
void _updateFlightPathSegmentsSignal(void);
protected slots:
virtual void _recalcFromHeadingAndDistanceChange(void) = 0;
void _updateFlightPathSegmentsDontCallDirectly(void);
protected:
QPointF _rotatePoint(const QPointF& point, const QPointF& origin, double angle);
int _sequenceNumber = 0;
bool _dirty = false;
QGeoCoordinate _loiterCoordinate;
QGeoCoordinate _loiterTangentCoordinate;
QGeoCoordinate _landingCoordinate;
bool _landingCoordSet = false;
bool _ignoreRecalcSignals = false;
bool _loiterClockwise = true;
bool _altitudesAreRelative = true;
};
This diff is collapsed.
......@@ -152,7 +152,7 @@ private slots:
void _rebuildTextFieldFacts (void);
void _possibleAdditionalTimeDelayChanged(void);
void _setDefaultsForCommand (void);
void _possibleVehicleYawChanged (void);
void _possibleVehicleYawChanged (void);
private:
void _connectSignals (void);
......
......@@ -41,7 +41,7 @@ const char* VTOLLandingComplexItem::_jsonStopTakingPhotosKey = "stopTaki
const char* VTOLLandingComplexItem::_jsonStopTakingVideoKey = "stopVideoPhotos";
VTOLLandingComplexItem::VTOLLandingComplexItem(PlanMasterController* masterController, bool flyView, QObject* parent)
: ComplexMissionItem (masterController, flyView, parent)
: LandingComplexItem (masterController, flyView, parent)
, _metaDataMap (FactMetaData::createMapFromJsonFile(QStringLiteral(":/json/VTOLLandingPattern.FactMetaData.json"), this))
, _landingDistanceFact (settingsGroup, _metaDataMap[loiterToLandDistanceName])
, _loiterAltitudeFact (settingsGroup, _metaDataMap[loiterAltitudeName])
......@@ -98,6 +98,10 @@ VTOLLandingComplexItem::VTOLLandingComplexItem(PlanMasterController* masterContr
connect(this, &VTOLLandingComplexItem::landingCoordSetChanged, this, &VTOLLandingComplexItem::readyForSaveStateChanged);
connect(this, &VTOLLandingComplexItem::wizardModeChanged, this, &VTOLLandingComplexItem::readyForSaveStateChanged);
connect(this, &VTOLLandingComplexItem::loiterCoordinateChanged, this, &VTOLLandingComplexItem::complexDistanceChanged);
connect(this, &VTOLLandingComplexItem::loiterTangentCoordinateChanged,this, &VTOLLandingComplexItem::complexDistanceChanged);
connect(this, &VTOLLandingComplexItem::landingCoordinateChanged, this, &VTOLLandingComplexItem::complexDistanceChanged);
connect(this, &VTOLLandingComplexItem::loiterTangentCoordinateChanged,this, &VTOLLandingComplexItem::_updateFlightPathSegmentsSignal);
connect(this, &VTOLLandingComplexItem::landingCoordinateChanged, this, &VTOLLandingComplexItem::_updateFlightPathSegmentsSignal);
connect(&_loiterAltitudeFact, &Fact::valueChanged, this, &VTOLLandingComplexItem::_updateFlightPathSegmentsSignal);
......@@ -459,39 +463,6 @@ bool VTOLLandingComplexItem::scanForItem(QmlObjectListModel* visualItems, bool f
return true;
}
double VTOLLandingComplexItem::complexDistance(void) const
{
return _loiterCoordinate.distanceTo(_landingCoordinate);
}
void VTOLLandingComplexItem::setLandingCoordinate(const QGeoCoordinate& coordinate)
{
if (coordinate != _landingCoordinate) {
_landingCoordinate = coordinate;
if (_landingCoordSet) {
emit exitCoordinateChanged(coordinate);
emit landingCoordinateChanged(coordinate);
} else {
_ignoreRecalcSignals = true;
emit exitCoordinateChanged(coordinate);
emit landingCoordinateChanged(coordinate);
_ignoreRecalcSignals = false;
_landingCoordSet = true;
_recalcFromHeadingAndDistanceChange();
emit landingCoordSetChanged(true);
}
}
}
void VTOLLandingComplexItem::setLoiterCoordinate(const QGeoCoordinate& coordinate)
{
if (coordinate != _loiterCoordinate) {
_loiterCoordinate = coordinate;
emit coordinateChanged(coordinate);
emit loiterCoordinateChanged(coordinate);
}
}
double VTOLLandingComplexItem::_mathematicAngleToHeading(double angle)
{
double heading = (angle - 90) * -1;
......@@ -589,17 +560,6 @@ void VTOLLandingComplexItem::_recalcFromHeadingAndDistanceChange(void)
}
}
QPointF VTOLLandingComplexItem::_rotatePoint(const QPointF& point, const QPointF& origin, double angle)
{
QPointF rotated;
double radians = (M_PI / 180.0) * angle;
rotated.setX(((point.x() - origin.x()) * cos(radians)) - ((point.y() - origin.y()) * sin(radians)) + origin.x());
rotated.setY(((point.x() - origin.x()) * sin(radians)) + ((point.y() - origin.y()) * cos(radians)) + origin.y());
return rotated;
}
void VTOLLandingComplexItem::_recalcFromCoordinateChange(void)
{
// Fixed:
......@@ -685,24 +645,3 @@ double VTOLLandingComplexItem::amslExitAlt(void) const
return _landingAltitudeFact.rawValue().toDouble() + (_altitudesAreRelative ? _missionController->plannedHomePosition().altitude() : 0);
}
// Never call this method directly. If you want to update the flight segments you emit _updateFlightPathSegmentsSignal()
void VTOLLandingComplexItem::_updateFlightPathSegmentsDontCallDirectly(void)
{
if (_cTerrainCollisionSegments != 0) {
_cTerrainCollisionSegments = 0;
emit terrainCollisionChanged(false);
}
_flightPathSegments.beginReset();
_flightPathSegments.clearAndDeleteContents();
_appendFlightPathSegment(_loiterTangentCoordinate, amslEntryAlt(), _landingCoordinate, amslEntryAlt()); // Loiter to land
_appendFlightPathSegment(_landingCoordinate, amslEntryAlt(), _landingCoordinate, amslExitAlt()); // Land to ground
_flightPathSegments.endReset();
if (_cTerrainCollisionSegments != 0) {
emit terrainCollisionChanged(true);
}
_masterController->missionController()->recalcTerrainProfile();
}
......@@ -9,7 +9,7 @@
#pragma once
#include "ComplexMissionItem.h"
#include "LandingComplexItem.h"
#include "MissionItem.h"
#include "Fact.h"
#include "QGCLoggingCategory.h"
......@@ -19,40 +19,20 @@ Q_DECLARE_LOGGING_CATEGORY(VTOLLandingComplexItemLog)
class VTOLLandingPatternTest;
class PlanMasterController;
class VTOLLandingComplexItem : public ComplexMissionItem
class VTOLLandingComplexItem : public LandingComplexItem
{
Q_OBJECT
public:
VTOLLandingComplexItem(PlanMasterController* masterController, bool flyView, QObject* parent);
Q_PROPERTY(Fact* loiterAltitude READ loiterAltitude CONSTANT)
Q_PROPERTY(Fact* loiterRadius READ loiterRadius CONSTANT)
Q_PROPERTY(Fact* landingAltitude READ landingAltitude CONSTANT)
Q_PROPERTY(Fact* landingHeading READ landingHeading CONSTANT)
Q_PROPERTY(Fact* landingDistance READ landingDistance CONSTANT)
Q_PROPERTY(bool loiterClockwise MEMBER _loiterClockwise NOTIFY loiterClockwiseChanged)
Q_PROPERTY(bool altitudesAreRelative MEMBER _altitudesAreRelative NOTIFY altitudesAreRelativeChanged)
Q_PROPERTY(Fact* stopTakingPhotos READ stopTakingPhotos CONSTANT)
Q_PROPERTY(Fact* stopTakingVideo READ stopTakingVideo CONSTANT)
Q_PROPERTY(QGeoCoordinate loiterCoordinate READ loiterCoordinate WRITE setLoiterCoordinate NOTIFY loiterCoordinateChanged)
Q_PROPERTY(QGeoCoordinate loiterTangentCoordinate READ loiterTangentCoordinate NOTIFY loiterTangentCoordinateChanged)
Q_PROPERTY(QGeoCoordinate landingCoordinate READ landingCoordinate WRITE setLandingCoordinate NOTIFY landingCoordinateChanged)
Q_PROPERTY(bool landingCoordSet MEMBER _landingCoordSet NOTIFY landingCoordSetChanged)
Fact* loiterAltitude (void) { return &_loiterAltitudeFact; }
Fact* loiterRadius (void) { return &_loiterRadiusFact; }
Fact* landingAltitude (void) { return &_landingAltitudeFact; }
Fact* landingDistance (void) { return &_landingDistanceFact; }
Fact* landingHeading (void) { return &_landingHeadingFact; }
Fact* stopTakingPhotos (void) { return &_stopTakingPhotosFact; }
Fact* stopTakingVideo (void) { return &_stopTakingVideoFact; }
QGeoCoordinate landingCoordinate (void) const { return _landingCoordinate; }
QGeoCoordinate loiterCoordinate (void) const { return _loiterCoordinate; }
QGeoCoordinate loiterTangentCoordinate (void) const { return _loiterTangentCoordinate; }
void setLandingCoordinate (const QGeoCoordinate& coordinate);
void setLoiterCoordinate (const QGeoCoordinate& coordinate);
Fact* loiterAltitude (void) final { return &_loiterAltitudeFact; }
Fact* loiterRadius (void) final { return &_loiterRadiusFact; }
Fact* landingAltitude (void) final { return &_landingAltitudeFact; }
Fact* landingDistance (void) final { return &_landingDistanceFact; }
Fact* landingHeading (void) final { return &_landingHeadingFact; }
Fact* stopTakingPhotos (void) final { return &_stopTakingPhotosFact; }
Fact* stopTakingVideo (void) final { return &_stopTakingVideoFact; }
/// Scans the loaded items for a landing pattern complex item
static bool scanForItem(QmlObjectListModel* visualItems, bool flyView, PlanMasterController* masterController);
......@@ -63,7 +43,6 @@ public:
// Overrides from ComplexMissionItem
QString patternName (void) const final { return name; }
double complexDistance (void) const final;
int lastSequenceNumber (void) const final;
bool load (const QJsonObject& complexObject, int sequenceNumber, QString& errorString) final;
double greatestDistanceTo (const QGeoCoordinate &other) const final;
......@@ -111,17 +90,8 @@ public:
static const char* stopTakingPhotosName;
static const char* stopTakingVideoName;
signals:
void loiterCoordinateChanged (QGeoCoordinate coordinate);
void loiterTangentCoordinateChanged (QGeoCoordinate coordinate);
void landingCoordinateChanged (QGeoCoordinate coordinate);
void landingCoordSetChanged (bool landingCoordSet);
void loiterClockwiseChanged (bool loiterClockwise);
void altitudesAreRelativeChanged (bool altitudesAreRelative);
void _updateFlightPathSegmentsSignal(void);
private slots:
void _recalcFromHeadingAndDistanceChange (void);
void _recalcFromHeadingAndDistanceChange (void) final;
void _recalcFromCoordinateChange (void);
void _recalcFromRadiusChange (void);
void _updateLoiterCoodinateAltitudeFromFact (void);
......@@ -130,20 +100,8 @@ private slots:
double _headingToMathematicAngle (double heading);
void _setDirty (void);
void _signalLastSequenceNumberChanged (void);
void _updateFlightPathSegmentsDontCallDirectly (void);
private:
QPointF _rotatePoint (const QPointF& point, const QPointF& origin, double angle);
int _sequenceNumber = 0;
bool _dirty = false;
QGeoCoordinate _loiterCoordinate;
QGeoCoordinate _loiterTangentCoordinate;
QGeoCoordinate _landingCoordinate;
bool _landingCoordSet = false;
bool _ignoreRecalcSignals = false;
bool _loiterClockwise = true;
bool _altitudesAreRelative = true;
QMap<QString, FactMetaData*> _metaDataMap;
......@@ -155,7 +113,6 @@ private:
Fact _stopTakingPhotosFact;
Fact _stopTakingVideoFact;
static const char* _jsonLoiterCoordinateKey;
static const char* _jsonLoiterRadiusKey;
static const char* _jsonLoiterClockwiseKey;
......
......@@ -76,7 +76,7 @@ void TerrainProfile::_createGeometry(QSGGeometryNode*& geometryNode, QSGGeometry
void TerrainProfile::_updateSegmentCounts(FlightPathSegment* segment, int& cTerrainPoints, int& cMissingTerrainSegments, int& cTerrainCollisionSegments, double& maxTerrainHeight)
{
if (segment->amslTerrainHeights().count() == 0) {
if (segment->amslTerrainHeights().count() == 0 || qIsNaN(segment->coord1AMSLAlt()) || qIsNaN(segment->coord2AMSLAlt())) {
cMissingTerrainSegments += 1;
} else {
cTerrainPoints += segment->amslTerrainHeights().count();
......@@ -151,6 +151,10 @@ void TerrainProfile::_addFlightProfileSegment(FlightPathSegment* segment, double
double coord1HeightPercent = qMax(((amslCoord1Height - _missionController->minAMSLAltitude()) / amslAltRange), 0.0);
double coord2HeightPercent = qMax(((amslCoord2Height - _missionController->minAMSLAltitude()) / amslAltRange), 0.0);
if (qIsNaN(amslCoord1Height) || qIsNaN(amslCoord2Height)) {
return;
}
float x = currentDistance * _pixelsPerMeter;
float y = _availableHeight() - (coord1HeightPercent * _availableHeight());
......
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