Commit 7bd7938c authored by Don Gagne's avatar Don Gagne

Break out SurveyMissionItem->ComplexMissionItem class hierarchy

parent f4b62d90
......@@ -267,13 +267,14 @@ HEADERS += \
src/JsonHelper.h \
src/LogCompressor.h \
src/MG.h \
src/MissionManager/ComplexMissionItem.h \
src/MissionManager/MissionCommandList.h \
src/MissionManager/MissionCommands.h \
src/MissionManager/MissionController.h \
src/MissionManager/MissionItem.h \
src/MissionManager/MissionManager.h \
src/MissionManager/ComplexMissionItem.h \
src/MissionManager/SimpleMissionItem.h \
src/MissionManager/SurveyMissionItem.h \
src/MissionManager/VisualMissionItem.h \
src/QGC.h \
src/QGCApplication.h \
......@@ -426,13 +427,14 @@ SOURCES += \
src/FollowMe/FollowMe.cc \
src/LogCompressor.cc \
src/main.cc \
src/MissionManager/ComplexMissionItem.cc \
src/MissionManager/MissionCommandList.cc \
src/MissionManager/MissionCommands.cc \
src/MissionManager/MissionController.cc \
src/MissionManager/MissionItem.cc \
src/MissionManager/MissionManager.cc \
src/MissionManager/ComplexMissionItem.cc \
src/MissionManager/SimpleMissionItem.cc \
src/MissionManager/SurveyMissionItem.cc \
src/MissionManager/VisualMissionItem.cc \
src/QGC.cc \
src/QGCApplication.cc \
......
This diff is collapsed.
......@@ -7,16 +7,10 @@
*
****************************************************************************/
#ifndef ComplexMissionItem_H
#define ComplexMissionItem_H
#include "VisualMissionItem.h"
#include "MissionItem.h"
#include "Fact.h"
#include "QGCLoggingCategory.h"
Q_DECLARE_LOGGING_CATEGORY(ComplexMissionItemLog)
class ComplexMissionItem : public VisualMissionItem
{
......@@ -27,139 +21,33 @@ public:
const ComplexMissionItem& operator=(const ComplexMissionItem& other);
Q_PROPERTY(Fact* gridAltitude READ gridAltitude CONSTANT)
Q_PROPERTY(bool gridAltitudeRelative MEMBER _gridAltitudeRelative NOTIFY gridAltitudeRelativeChanged)
Q_PROPERTY(Fact* gridAngle READ gridAngle CONSTANT)
Q_PROPERTY(Fact* gridSpacing READ gridSpacing CONSTANT)
Q_PROPERTY(bool cameraTrigger MEMBER _cameraTrigger NOTIFY cameraTriggerChanged)
Q_PROPERTY(Fact* cameraTriggerDistance READ cameraTriggerDistance CONSTANT)
Q_PROPERTY(QVariantList polygonPath READ polygonPath NOTIFY polygonPathChanged)
Q_PROPERTY(int lastSequenceNumber READ lastSequenceNumber NOTIFY lastSequenceNumberChanged)
Q_PROPERTY(QVariantList gridPoints READ gridPoints NOTIFY gridPointsChanged)
Q_PROPERTY(double surveyDistance READ surveyDistance NOTIFY surveyDistanceChanged)
Q_PROPERTY(int cameraShots READ cameraShots NOTIFY cameraShotsChanged)
Q_PROPERTY(double coveredArea READ coveredArea NOTIFY coveredAreaChanged)
Q_INVOKABLE void clearPolygon(void);
Q_INVOKABLE void addPolygonCoordinate(const QGeoCoordinate coordinate);
Q_INVOKABLE void adjustPolygonCoordinate(int vertexIndex, const QGeoCoordinate coordinate);
QVariantList polygonPath(void) { return _polygonPath; }
QVariantList gridPoints (void) { return _gridPoints; }
Q_PROPERTY(int lastSequenceNumber READ lastSequenceNumber NOTIFY lastSequenceNumberChanged)
Q_PROPERTY(double complexDistance READ complexDistance NOTIFY complexDistanceChanged)
Fact* gridAltitude(void) { return &_gridAltitudeFact; }
Fact* gridAngle(void) { return &_gridAngleFact; }
Fact* gridSpacing(void) { return &_gridSpacingFact; }
Fact* cameraTriggerDistance(void) { return &_cameraTriggerDistanceFact; }
double surveyDistance (void) const { return _surveyDistance; }
int cameraShots (void) const { return _cameraShots; }
double coveredArea (void) const { return _coveredArea; }
void setSurveyDistance (double surveyDistance);
void setCameraShots (int cameraShots);
void setCoveredArea (double coveredArea);
/// @return The distance covered the complex mission item in meters.
virtual double complexDistance(void) const = 0;
/// @return The last sequence number used by this item. Takes into account child items of the complex item
int lastSequenceNumber(void) const;
virtual int lastSequenceNumber(void) const = 0;
/// Returns the mission items associated with the complex item. Caller is responsible for freeing. Calling
/// delete on returned QmlObjectListModel will free all memory including internal items.
QmlObjectListModel* getMissionItems(void) const;
virtual QmlObjectListModel* getMissionItems(void) const = 0;
/// Load the complex mission item from Json
/// @param complexObject Complex mission item json object
/// @param[out] errorString Error if load fails
/// @return true: load success, false: load failed, errorString set
bool load(const QJsonObject& complexObject, QString& errorString);
virtual bool load(const QJsonObject& complexObject, QString& errorString) = 0;
/// Get the point of complex mission item furthest away from a coordinate
/// @param other QGeoCoordinate to which distance is calculated
/// @return the greatest distance from any point of the complex item to some coordinate
double greatestDistanceTo(const QGeoCoordinate &other) const;
// Overrides from VisualMissionItem
bool dirty (void) const final { return _dirty; }
bool isSimpleItem (void) const final { return false; }
bool isStandaloneCoordinate (void) const final { return false; }
bool specifiesCoordinate (void) const final;
QString commandDescription (void) const final { return "Survey"; }
QString commandName (void) const final { return "Survey"; }
QString abbreviation (void) const final { return "S"; }
QGeoCoordinate coordinate (void) const final { return _coordinate; }
QGeoCoordinate exitCoordinate (void) const final { return _exitCoordinate; }
int sequenceNumber (void) const final { return _sequenceNumber; }
bool coordinateHasRelativeAltitude (void) const final { return _gridAltitudeRelative; }
bool exitCoordinateHasRelativeAltitude (void) const final { return _gridAltitudeRelative; }
bool exitCoordinateSameAsEntry (void) const final { return false; }
void setDirty (bool dirty) final;
void setCoordinate (const QGeoCoordinate& coordinate) final;
void setSequenceNumber (int sequenceNumber) final;
void save (QJsonObject& saveObject) const final;
virtual double greatestDistanceTo(const QGeoCoordinate &other) const = 0;
signals:
void polygonPathChanged (void);
void lastSequenceNumberChanged (int lastSequenceNumber);
void altitudeChanged (double altitude);
void gridAngleChanged (double gridAngle);
void gridPointsChanged (void);
void cameraTriggerChanged (bool cameraTrigger);
void gridAltitudeRelativeChanged (bool gridAltitudeRelative);
void surveyDistanceChanged (double surveyDistance);
void cameraShotsChanged (int cameraShots);
void coveredAreaChanged (double coveredArea);
private slots:
void _cameraTriggerChanged(void);
private:
void _clear(void);
void _setExitCoordinate(const QGeoCoordinate& coordinate);
void _clearGrid(void);
void _generateGrid(void);
void _gridGenerator(const QList<QPointF>& polygonPoints, QList<QPointF>& gridPoints);
QPointF _rotatePoint(const QPointF& point, const QPointF& origin, double angle);
void _intersectLinesWithRect(const QList<QLineF>& lineList, const QRectF& boundRect, QList<QLineF>& resultLines);
void _intersectLinesWithPolygon(const QList<QLineF>& lineList, const QPolygonF& polygon, QList<QLineF>& resultLines);
void _adjustLineDirection(const QList<QLineF>& lineList, QList<QLineF>& resultLines);
int _sequenceNumber;
bool _dirty;
QVariantList _polygonPath;
QVariantList _gridPoints;
QGeoCoordinate _coordinate;
QGeoCoordinate _exitCoordinate;
double _altitude;
double _gridAngle;
bool _cameraTrigger;
bool _gridAltitudeRelative;
double _surveyDistance;
int _cameraShots;
double _coveredArea;
Fact _gridAltitudeFact;
Fact _gridAngleFact;
Fact _gridSpacingFact;
Fact _cameraTriggerDistanceFact;
static const char* _jsonVersionKey;
static const char* _jsonTypeKey;
static const char* _jsonPolygonKey;
static const char* _jsonIdKey;
static const char* _jsonGridAltitudeKey;
static const char* _jsonGridAltitudeRelativeKey;
static const char* _jsonGridAngleKey;
static const char* _jsonGridSpacingKey;
static const char* _jsonCameraTriggerKey;
static const char* _jsonCameraTriggerDistanceKey;
static const char* _complexType;
void lastSequenceNumberChanged (int lastSequenceNumber);
void complexDistanceChanged (double complexDistance);
};
#endif
......@@ -45,7 +45,7 @@ void ComplexMissionItemTest::init(void)
_rgComplexMissionItemSignals[exitCoordinateHasRelativeAltitudeChangedIndex] = SIGNAL(exitCoordinateHasRelativeAltitudeChanged(bool));
_rgComplexMissionItemSignals[exitCoordinateSameAsEntryChangedIndex] = SIGNAL(exitCoordinateSameAsEntryChanged(bool));
_complexItem = new ComplexMissionItem(NULL /* Vehicle */, this);
_complexItem = new SurveyMissionItem(NULL /* Vehicle */, this);
// It's important to check that the right signals are emitted at the right time since that drives ui change.
// It's also important to check that things are not being over-signalled when they should not be, since that can lead
......
......@@ -14,7 +14,7 @@
#include "UnitTest.h"
#include "TCPLink.h"
#include "MultiSignalSpy.h"
#include "ComplexMissionItem.h"
#include "SurveyMissionItem.h"
#include <QGeoCoordinate>
......@@ -95,7 +95,7 @@ private:
const char* _rgComplexMissionItemSignals[_cComplexMissionItemSignals];
MultiSignalSpy* _multiSpy;
ComplexMissionItem* _complexItem;
SurveyMissionItem* _complexItem;
QList<QGeoCoordinate> _polyPoints;
};
......
......@@ -15,7 +15,7 @@
#include "FirmwarePlugin.h"
#include "QGCApplication.h"
#include "SimpleMissionItem.h"
#include "ComplexMissionItem.h"
#include "SurveyMissionItem.h"
#include "JsonHelper.h"
#include "ParameterLoader.h"
#include "QGroundControlQmlGlobal.h"
......@@ -200,7 +200,7 @@ int MissionController::insertSimpleMissionItem(QGeoCoordinate coordinate, int i)
int MissionController::insertComplexMissionItem(QGeoCoordinate coordinate, int i)
{
int sequenceNumber = _nextSequenceNumber();
ComplexMissionItem* newItem = new ComplexMissionItem(_activeVehicle, this);
SurveyMissionItem* newItem = new SurveyMissionItem(_activeVehicle, this);
newItem->setSequenceNumber(sequenceNumber);
newItem->setCoordinate(coordinate);
_initVisualItem(newItem);
......@@ -220,9 +220,7 @@ void MissionController::removeMissionItem(int index)
_deinitVisualItem(item);
if (!item->isSimpleItem()) {
ComplexMissionItem* complexItem = qobject_cast<ComplexMissionItem*>(_complexItems->removeOne(item));
if (complexItem) {
complexItem->deleteLater();
} else {
if (!complexItem) {
qWarning() << "Complex item missing";
}
}
......@@ -299,7 +297,7 @@ bool MissionController::_loadJsonMissionFile(const QByteArray& bytes, QmlObjectL
return false;
}
ComplexMissionItem* item = new ComplexMissionItem(_activeVehicle, this);
SurveyMissionItem* item = new SurveyMissionItem(_activeVehicle, this);
if (item->load(itemValue.toObject(), errorString)) {
qCDebug(MissionControllerLog) << "Json load: complex item start:stop" << item->sequenceNumber() << item->lastSequenceNumber();
complexItems->append(item);
......@@ -321,7 +319,7 @@ bool MissionController::_loadJsonMissionFile(const QByteArray& bytes, QmlObjectL
// If there is a complex item that should be next in sequence add it in
if (nextComplexItemIndex < complexItems->count()) {
ComplexMissionItem* complexItem = qobject_cast<ComplexMissionItem*>(complexItems->get(nextComplexItemIndex));
SurveyMissionItem* complexItem = qobject_cast<SurveyMissionItem*>(complexItems->get(nextComplexItemIndex));
if (complexItem->sequenceNumber() == nextSequenceNumber) {
qCDebug(MissionControllerLog) << "Json load: injecting complex item expectedSequence:actualSequence:" << nextSequenceNumber << complexItem->sequenceNumber();
......@@ -832,11 +830,11 @@ void MissionController::_recalcAltitudeRangeBearing()
}
}
} else {
missionDistance += qobject_cast<ComplexMissionItem*>(item)->surveyDistance();
missionDistance += qobject_cast<ComplexMissionItem*>(item)->complexDistance();
telemetryDistance = qobject_cast<ComplexMissionItem*>(item)->greatestDistanceTo(homeItem->exitCoordinate());
if (vtolCalc){
cruiseDistance += qobject_cast<ComplexMissionItem*>(item)->surveyDistance(); //assume all survey missions undertaken in cruise
cruiseDistance += qobject_cast<ComplexMissionItem*>(item)->complexDistance(); //assume all survey missions undertaken in cruise
}
}
......@@ -845,11 +843,11 @@ void MissionController::_recalcAltitudeRangeBearing()
}
}
else if (lastCoordinateItem == homeItem && !item->isSimpleItem()){
missionDistance += qobject_cast<ComplexMissionItem*>(item)->surveyDistance();
missionDistance += qobject_cast<ComplexMissionItem*>(item)->complexDistance();
missionMaxTelemetry = qobject_cast<ComplexMissionItem*>(item)->greatestDistanceTo(homeItem->exitCoordinate());
if (vtolCalc){
cruiseDistance += qobject_cast<ComplexMissionItem*>(item)->surveyDistance(); //assume all survey missions undertaken in cruise
cruiseDistance += qobject_cast<ComplexMissionItem*>(item)->complexDistance(); //assume all survey missions undertaken in cruise
}
}
lastCoordinateItem = item;
......@@ -1015,7 +1013,7 @@ void MissionController::_initVisualItem(VisualMissionItem* visualItem)
// We need to track changes of lastSequenceNumber so we can recalc sequence numbers for subsequence items
ComplexMissionItem* complexItem = qobject_cast<ComplexMissionItem*>(visualItem);
connect(complexItem, &ComplexMissionItem::lastSequenceNumberChanged, this, &MissionController::_recalcSequence);
connect(complexItem, &ComplexMissionItem::surveyDistanceChanged, this, &MissionController::_recalcAltitudeRangeBearing);
connect(complexItem, &ComplexMissionItem::complexDistanceChanged, this, &MissionController::_recalcAltitudeRangeBearing);
}
}
......
......@@ -27,7 +27,7 @@
#include "QmlObjectListModel.h"
#include "MissionCommands.h"
class ComplexMissionItem;
class SurveyMissionItem;
class SimpleMissionItem;
class MissionController;
#ifdef UNITTEST_BUILD
......@@ -128,7 +128,7 @@ private:
static const char* _jsonAutoContinueKey;
static const char* _jsonCoordinateKey;
friend class ComplexMissionItem;
friend class SurveyMissionItem;
friend class SimpleMissionItem;
friend class MissionController;
#ifdef UNITTEST_BUILD
......
......@@ -124,7 +124,7 @@ SimpleMissionItem::SimpleMissionItem(const SimpleMissionItem& other, QObject* pa
const SimpleMissionItem& SimpleMissionItem::operator=(const SimpleMissionItem& other)
{
static_cast<VisualMissionItem&>(*this) = other;
VisualMissionItem::operator=(other);
setRawEdit(other._rawEdit);
setDirty(other._dirty);
......
This diff is collapsed.
/****************************************************************************
*
* (c) 2009-2016 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.
*
****************************************************************************/
#ifndef SurveyMissionItem_H
#define SurveyMissionItem_H
#include "ComplexMissionItem.h"
#include "MissionItem.h"
#include "Fact.h"
#include "QGCLoggingCategory.h"
Q_DECLARE_LOGGING_CATEGORY(SurveyMissionItemLog)
class SurveyMissionItem : public ComplexMissionItem
{
Q_OBJECT
public:
SurveyMissionItem(Vehicle* vehicle, QObject* parent = NULL);
const SurveyMissionItem& operator=(const SurveyMissionItem& other);
Q_PROPERTY(Fact* gridAltitude READ gridAltitude CONSTANT)
Q_PROPERTY(bool gridAltitudeRelative MEMBER _gridAltitudeRelative NOTIFY gridAltitudeRelativeChanged)
Q_PROPERTY(Fact* gridAngle READ gridAngle CONSTANT)
Q_PROPERTY(Fact* gridSpacing READ gridSpacing CONSTANT)
Q_PROPERTY(bool cameraTrigger MEMBER _cameraTrigger NOTIFY cameraTriggerChanged)
Q_PROPERTY(Fact* cameraTriggerDistance READ cameraTriggerDistance CONSTANT)
Q_PROPERTY(QVariantList polygonPath READ polygonPath NOTIFY polygonPathChanged)
Q_PROPERTY(QVariantList gridPoints READ gridPoints NOTIFY gridPointsChanged)
Q_PROPERTY(int cameraShots READ cameraShots NOTIFY cameraShotsChanged)
Q_PROPERTY(double coveredArea READ coveredArea NOTIFY coveredAreaChanged)
Q_INVOKABLE void clearPolygon(void);
Q_INVOKABLE void addPolygonCoordinate(const QGeoCoordinate coordinate);
Q_INVOKABLE void adjustPolygonCoordinate(int vertexIndex, const QGeoCoordinate coordinate);
QVariantList polygonPath(void) { return _polygonPath; }
QVariantList gridPoints (void) { return _gridPoints; }
Fact* gridAltitude(void) { return &_gridAltitudeFact; }
Fact* gridAngle(void) { return &_gridAngleFact; }
Fact* gridSpacing(void) { return &_gridSpacingFact; }
Fact* cameraTriggerDistance(void) { return &_cameraTriggerDistanceFact; }
int cameraShots (void) const { return _cameraShots; }
double coveredArea (void) const { return _coveredArea; }
// Overrides from ComplexMissionItem
double complexDistance (void) const final { return _surveyDistance; }
int lastSequenceNumber (void) const final;
QmlObjectListModel* getMissionItems (void) const final;
bool load (const QJsonObject& complexObject, QString& errorString) final;
double greatestDistanceTo (const QGeoCoordinate &other) const final;
// Overrides from VisualMissionItem
bool dirty (void) const final { return _dirty; }
bool isSimpleItem (void) const final { return false; }
bool isStandaloneCoordinate (void) const final { return false; }
bool specifiesCoordinate (void) const final;
QString commandDescription (void) const final { return "Survey"; }
QString commandName (void) const final { return "Survey"; }
QString abbreviation (void) const final { return "S"; }
QGeoCoordinate coordinate (void) const final { return _coordinate; }
QGeoCoordinate exitCoordinate (void) const final { return _exitCoordinate; }
int sequenceNumber (void) const final { return _sequenceNumber; }
bool coordinateHasRelativeAltitude (void) const final { return _gridAltitudeRelative; }
bool exitCoordinateHasRelativeAltitude (void) const final { return _gridAltitudeRelative; }
bool exitCoordinateSameAsEntry (void) const final { return false; }
void setDirty (bool dirty) final;
void setCoordinate (const QGeoCoordinate& coordinate) final;
void setSequenceNumber (int sequenceNumber) final;
void save (QJsonObject& saveObject) const final;
signals:
void polygonPathChanged (void);
void altitudeChanged (double altitude);
void gridAngleChanged (double gridAngle);
void gridPointsChanged (void);
void cameraTriggerChanged (bool cameraTrigger);
void gridAltitudeRelativeChanged (bool gridAltitudeRelative);
void cameraShotsChanged (int cameraShots);
void coveredAreaChanged (double coveredArea);
private slots:
void _cameraTriggerChanged(void);
private:
void _clear(void);
void _setExitCoordinate(const QGeoCoordinate& coordinate);
void _clearGrid(void);
void _generateGrid(void);
void _gridGenerator(const QList<QPointF>& polygonPoints, QList<QPointF>& gridPoints);
QPointF _rotatePoint(const QPointF& point, const QPointF& origin, double angle);
void _intersectLinesWithRect(const QList<QLineF>& lineList, const QRectF& boundRect, QList<QLineF>& resultLines);
void _intersectLinesWithPolygon(const QList<QLineF>& lineList, const QPolygonF& polygon, QList<QLineF>& resultLines);
void _adjustLineDirection(const QList<QLineF>& lineList, QList<QLineF>& resultLines);
void _setSurveyDistance(double surveyDistance);
void _setCameraShots(int cameraShots);
void _setCoveredArea(double coveredArea);
int _sequenceNumber;
bool _dirty;
QVariantList _polygonPath;
QVariantList _gridPoints;
QGeoCoordinate _coordinate;
QGeoCoordinate _exitCoordinate;
double _altitude;
double _gridAngle;
bool _cameraTrigger;
bool _gridAltitudeRelative;
double _surveyDistance;
int _cameraShots;
double _coveredArea;
Fact _gridAltitudeFact;
Fact _gridAngleFact;
Fact _gridSpacingFact;
Fact _cameraTriggerDistanceFact;
static const char* _jsonVersionKey;
static const char* _jsonTypeKey;
static const char* _jsonPolygonKey;
static const char* _jsonIdKey;
static const char* _jsonGridAltitudeKey;
static const char* _jsonGridAltitudeRelativeKey;
static const char* _jsonGridAngleKey;
static const char* _jsonGridSpacingKey;
static const char* _jsonCameraTriggerKey;
static const char* _jsonCameraTriggerDistanceKey;
static const char* _complexType;
};
#endif
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