Commit e6f439f4 authored by DonLakeFlyer's avatar DonLakeFlyer

parent 925e581d
...@@ -10,6 +10,7 @@ ...@@ -10,6 +10,7 @@
#include "CorridorScanPlanCreator.h" #include "CorridorScanPlanCreator.h"
#include "PlanMasterController.h" #include "PlanMasterController.h"
#include "MissionSettingsItem.h" #include "MissionSettingsItem.h"
#include "FixedWingLandingComplexItem.h"
CorridorScanPlanCreator::CorridorScanPlanCreator(PlanMasterController* planMasterController, QObject* parent) CorridorScanPlanCreator::CorridorScanPlanCreator(PlanMasterController* planMasterController, QObject* parent)
: PlanCreator(planMasterController, MissionController::patternCorridorScanName, QStringLiteral("/qmlimages/PlanCreator/CorridorScanPlanCreator.png"), parent) : PlanCreator(planMasterController, MissionController::patternCorridorScanName, QStringLiteral("/qmlimages/PlanCreator/CorridorScanPlanCreator.png"), parent)
...@@ -20,19 +21,16 @@ CorridorScanPlanCreator::CorridorScanPlanCreator(PlanMasterController* planMaste ...@@ -20,19 +21,16 @@ CorridorScanPlanCreator::CorridorScanPlanCreator(PlanMasterController* planMaste
void CorridorScanPlanCreator::createPlan(const QGeoCoordinate& mapCenterCoord) void CorridorScanPlanCreator::createPlan(const QGeoCoordinate& mapCenterCoord)
{ {
_planMasterController->removeAll(); _planMasterController->removeAll();
int seqNum = _missionController->insertComplexMissionItem( VisualMissionItem* takeoffItem = _missionController->insertSimpleMissionItem(mapCenterCoord, -1);
MissionController::patternCorridorScanName, takeoffItem->setWizardMode(true);
mapCenterCoord, _missionController->insertComplexMissionItem(MissionController::patternCorridorScanName, mapCenterCoord, -1)->setWizardMode(true);
_missionController->visualItems()->count());
if (_planMasterController->managerVehicle()->fixedWing()) { if (_planMasterController->managerVehicle()->fixedWing()) {
_missionController->insertComplexMissionItem( FixedWingLandingComplexItem* landingItem = qobject_cast<FixedWingLandingComplexItem*>(_missionController->insertComplexMissionItem(MissionController::patternFWLandingName, mapCenterCoord, -1));
MissionController::patternFWLandingName, landingItem->setWizardMode(true);
mapCenterCoord, landingItem->setLoiterDragAngleOnly(true);
_missionController->visualItems()->count());
} else { } else {
MissionSettingsItem* settingsItem = _missionController->visualItems()->value<MissionSettingsItem*>(0); MissionSettingsItem* settingsItem = _missionController->visualItems()->value<MissionSettingsItem*>(0);
settingsItem->setMissionEndRTL(true); settingsItem->setMissionEndRTL(true);
} }
_missionController->setCurrentPlanViewIndex(seqNum, false); _missionController->setCurrentPlanViewIndex(takeoffItem->sequenceNumber(), true);
} }
...@@ -10,6 +10,7 @@ ...@@ -10,6 +10,7 @@
#include "CustomPlanCreator.h" #include "CustomPlanCreator.h"
#include "PlanMasterController.h" #include "PlanMasterController.h"
#include "MissionSettingsItem.h" #include "MissionSettingsItem.h"
#include "FixedWingLandingComplexItem.h"
CustomPlanCreator::CustomPlanCreator(PlanMasterController* planMasterController, QObject* parent) CustomPlanCreator::CustomPlanCreator(PlanMasterController* planMasterController, QObject* parent)
: PlanCreator(planMasterController, tr("Custom"), QStringLiteral("/qmlimages/PlanCreator/CustomPlanCreator.png"), parent) : PlanCreator(planMasterController, tr("Custom"), QStringLiteral("/qmlimages/PlanCreator/CustomPlanCreator.png"), parent)
...@@ -20,18 +21,18 @@ CustomPlanCreator::CustomPlanCreator(PlanMasterController* planMasterController, ...@@ -20,18 +21,18 @@ CustomPlanCreator::CustomPlanCreator(PlanMasterController* planMasterController,
void CustomPlanCreator::createPlan(const QGeoCoordinate& mapCenterCoord) void CustomPlanCreator::createPlan(const QGeoCoordinate& mapCenterCoord)
{ {
_planMasterController->removeAll(); _planMasterController->removeAll();
int seqNum = _missionController->insertSimpleMissionItem(mapCenterCoord, _missionController->visualItems()->count()); VisualMissionItem* takeoffItem = _missionController->insertSimpleMissionItem(mapCenterCoord, -1);
_missionController->insertSimpleMissionItem(mapCenterCoord.atDistanceAndAzimuth(50, 135), _missionController->visualItems()->count()); takeoffItem->setWizardMode(true);
_missionController->insertSimpleMissionItem(mapCenterCoord.atDistanceAndAzimuth(50, -135), _missionController->visualItems()->count()); _missionController->insertSimpleMissionItem(mapCenterCoord.atDistanceAndAzimuth(50, 135), -1)->setWizardMode(true);
_missionController->insertSimpleMissionItem(mapCenterCoord.atDistanceAndAzimuth(50, -135),-1)->setWizardMode(true);
if (_planMasterController->managerVehicle()->fixedWing()) { if (_planMasterController->managerVehicle()->fixedWing()) {
_missionController->insertComplexMissionItem( FixedWingLandingComplexItem* landingItem = qobject_cast<FixedWingLandingComplexItem*>(_missionController->insertComplexMissionItem(MissionController::patternFWLandingName, mapCenterCoord, -1));
MissionController::patternFWLandingName, landingItem->setWizardMode(true);
mapCenterCoord, landingItem->setLoiterDragAngleOnly(true);
_missionController->visualItems()->count());
} else { } else {
MissionSettingsItem* settingsItem = _missionController->visualItems()->value<MissionSettingsItem*>(0); MissionSettingsItem* settingsItem = _missionController->visualItems()->value<MissionSettingsItem*>(0);
settingsItem->setMissionEndRTL(true); settingsItem->setMissionEndRTL(true);
} }
_missionController->setCurrentPlanViewIndex(seqNum, false); _missionController->setCurrentPlanViewIndex(takeoffItem->sequenceNumber(), true);
} }
...@@ -51,6 +51,7 @@ FixedWingLandingComplexItem::FixedWingLandingComplexItem(Vehicle* vehicle, bool ...@@ -51,6 +51,7 @@ FixedWingLandingComplexItem::FixedWingLandingComplexItem(Vehicle* vehicle, bool
, _dirty (false) , _dirty (false)
, _landingCoordSet (false) , _landingCoordSet (false)
, _ignoreRecalcSignals (false) , _ignoreRecalcSignals (false)
, _loiterDragAngleOnly (false)
, _metaDataMap (FactMetaData::createMapFromJsonFile(QStringLiteral(":/json/FWLandingPattern.FactMetaData.json"), this)) , _metaDataMap (FactMetaData::createMapFromJsonFile(QStringLiteral(":/json/FWLandingPattern.FactMetaData.json"), this))
, _landingDistanceFact (settingsGroup, _metaDataMap[loiterToLandDistanceName]) , _landingDistanceFact (settingsGroup, _metaDataMap[loiterToLandDistanceName])
, _loiterAltitudeFact (settingsGroup, _metaDataMap[loiterAltitudeName]) , _loiterAltitudeFact (settingsGroup, _metaDataMap[loiterAltitudeName])
...@@ -101,6 +102,8 @@ FixedWingLandingComplexItem::FixedWingLandingComplexItem(Vehicle* vehicle, bool ...@@ -101,6 +102,8 @@ FixedWingLandingComplexItem::FixedWingLandingComplexItem(Vehicle* vehicle, bool
connect(this, &FixedWingLandingComplexItem::altitudesAreRelativeChanged, this, &FixedWingLandingComplexItem::exitCoordinateHasRelativeAltitudeChanged); connect(this, &FixedWingLandingComplexItem::altitudesAreRelativeChanged, this, &FixedWingLandingComplexItem::exitCoordinateHasRelativeAltitudeChanged);
connect(this, &FixedWingLandingComplexItem::landingCoordSetChanged, this, &FixedWingLandingComplexItem::readyForSaveStateChanged); connect(this, &FixedWingLandingComplexItem::landingCoordSetChanged, this, &FixedWingLandingComplexItem::readyForSaveStateChanged);
connect(this, &FixedWingLandingComplexItem::wizardModeChanged, this, &FixedWingLandingComplexItem::readyForSaveStateChanged);
if (vehicle->apmFirmware()) { if (vehicle->apmFirmware()) {
// ArduPilot does not support camera commands // ArduPilot does not support camera commands
_stopTakingVideoFact.setRawValue(false); _stopTakingVideoFact.setRawValue(false);
...@@ -712,5 +715,13 @@ void FixedWingLandingComplexItem::_signalLastSequenceNumberChanged(void) ...@@ -712,5 +715,13 @@ void FixedWingLandingComplexItem::_signalLastSequenceNumberChanged(void)
FixedWingLandingComplexItem::ReadyForSaveState FixedWingLandingComplexItem::readyForSaveState(void) const FixedWingLandingComplexItem::ReadyForSaveState FixedWingLandingComplexItem::readyForSaveState(void) const
{ {
return _landingCoordSet ? ReadyForSave : NotReadyForSaveData; return _landingCoordSet && !_wizardMode ? ReadyForSave : NotReadyForSaveData;
}
void FixedWingLandingComplexItem::setLoiterDragAngleOnly(bool loiterDragAngleOnly)
{
if (loiterDragAngleOnly != _loiterDragAngleOnly) {
_loiterDragAngleOnly = loiterDragAngleOnly;
emit loiterDragAngleOnlyChanged(_loiterDragAngleOnly);
}
} }
...@@ -26,21 +26,22 @@ class FixedWingLandingComplexItem : public ComplexMissionItem ...@@ -26,21 +26,22 @@ class FixedWingLandingComplexItem : public ComplexMissionItem
public: public:
FixedWingLandingComplexItem(Vehicle* vehicle, bool flyView, QObject* parent); FixedWingLandingComplexItem(Vehicle* vehicle, bool flyView, QObject* parent);
Q_PROPERTY(Fact* loiterAltitude READ loiterAltitude CONSTANT) Q_PROPERTY(Fact* loiterAltitude READ loiterAltitude CONSTANT)
Q_PROPERTY(Fact* loiterRadius READ loiterRadius CONSTANT) Q_PROPERTY(Fact* loiterRadius READ loiterRadius CONSTANT)
Q_PROPERTY(Fact* landingAltitude READ landingAltitude CONSTANT) Q_PROPERTY(Fact* landingAltitude READ landingAltitude CONSTANT)
Q_PROPERTY(Fact* landingHeading READ landingHeading CONSTANT) Q_PROPERTY(Fact* landingHeading READ landingHeading CONSTANT)
Q_PROPERTY(Fact* valueSetIsDistance READ valueSetIsDistance CONSTANT) Q_PROPERTY(Fact* valueSetIsDistance READ valueSetIsDistance CONSTANT)
Q_PROPERTY(Fact* landingDistance READ landingDistance CONSTANT) Q_PROPERTY(Fact* landingDistance READ landingDistance CONSTANT)
Q_PROPERTY(Fact* glideSlope READ glideSlope CONSTANT) Q_PROPERTY(Fact* glideSlope READ glideSlope CONSTANT)
Q_PROPERTY(bool loiterClockwise MEMBER _loiterClockwise NOTIFY loiterClockwiseChanged) Q_PROPERTY(bool loiterClockwise MEMBER _loiterClockwise NOTIFY loiterClockwiseChanged)
Q_PROPERTY(bool altitudesAreRelative MEMBER _altitudesAreRelative NOTIFY altitudesAreRelativeChanged) Q_PROPERTY(bool altitudesAreRelative MEMBER _altitudesAreRelative NOTIFY altitudesAreRelativeChanged)
Q_PROPERTY(Fact* stopTakingPhotos READ stopTakingPhotos CONSTANT) Q_PROPERTY(Fact* stopTakingPhotos READ stopTakingPhotos CONSTANT)
Q_PROPERTY(Fact* stopTakingVideo READ stopTakingVideo CONSTANT) Q_PROPERTY(Fact* stopTakingVideo READ stopTakingVideo CONSTANT)
Q_PROPERTY(QGeoCoordinate loiterCoordinate READ loiterCoordinate WRITE setLoiterCoordinate NOTIFY loiterCoordinateChanged) Q_PROPERTY(QGeoCoordinate loiterCoordinate READ loiterCoordinate WRITE setLoiterCoordinate NOTIFY loiterCoordinateChanged)
Q_PROPERTY(QGeoCoordinate loiterTangentCoordinate READ loiterTangentCoordinate NOTIFY loiterTangentCoordinateChanged) Q_PROPERTY(QGeoCoordinate loiterTangentCoordinate READ loiterTangentCoordinate NOTIFY loiterTangentCoordinateChanged)
Q_PROPERTY(QGeoCoordinate landingCoordinate READ landingCoordinate WRITE setLandingCoordinate NOTIFY landingCoordinateChanged) Q_PROPERTY(QGeoCoordinate landingCoordinate READ landingCoordinate WRITE setLandingCoordinate NOTIFY landingCoordinateChanged)
Q_PROPERTY(bool landingCoordSet MEMBER _landingCoordSet NOTIFY landingCoordSetChanged) Q_PROPERTY(bool landingCoordSet MEMBER _landingCoordSet NOTIFY landingCoordSetChanged)
Q_PROPERTY(bool loiterDragAngleOnly READ loiterDragAngleOnly WRITE setLoiterDragAngleOnly NOTIFY loiterDragAngleOnlyChanged)
Fact* loiterAltitude (void) { return &_loiterAltitudeFact; } Fact* loiterAltitude (void) { return &_loiterAltitudeFact; }
Fact* loiterRadius (void) { return &_loiterRadiusFact; } Fact* loiterRadius (void) { return &_loiterRadiusFact; }
...@@ -54,9 +55,11 @@ public: ...@@ -54,9 +55,11 @@ public:
QGeoCoordinate landingCoordinate (void) const { return _landingCoordinate; } QGeoCoordinate landingCoordinate (void) const { return _landingCoordinate; }
QGeoCoordinate loiterCoordinate (void) const { return _loiterCoordinate; } QGeoCoordinate loiterCoordinate (void) const { return _loiterCoordinate; }
QGeoCoordinate loiterTangentCoordinate (void) const { return _loiterTangentCoordinate; } QGeoCoordinate loiterTangentCoordinate (void) const { return _loiterTangentCoordinate; }
bool loiterDragAngleOnly (void) const { return _loiterDragAngleOnly; }
void setLandingCoordinate (const QGeoCoordinate& coordinate); void setLandingCoordinate (const QGeoCoordinate& coordinate);
void setLoiterCoordinate (const QGeoCoordinate& coordinate); void setLoiterCoordinate (const QGeoCoordinate& coordinate);
void setLoiterDragAngleOnly (bool loiterDragAngleOnly);
/// Scans the loaded items for a landing pattern complex item /// Scans the loaded items for a landing pattern complex item
static bool scanForItem(QmlObjectListModel* visualItems, bool flyView, Vehicle* vehicle); static bool scanForItem(QmlObjectListModel* visualItems, bool flyView, Vehicle* vehicle);
...@@ -66,7 +69,6 @@ public: ...@@ -66,7 +69,6 @@ public:
static MissionItem* createLandItem (int seqNum, bool altRel, double lat, double lon, double alt, QObject* parent); static MissionItem* createLandItem (int seqNum, bool altRel, double lat, double lon, double alt, QObject* parent);
// Overrides from ComplexMissionItem // Overrides from ComplexMissionItem
double complexDistance (void) const final; double complexDistance (void) const final;
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;
...@@ -123,6 +125,7 @@ signals: ...@@ -123,6 +125,7 @@ signals:
void loiterClockwiseChanged (bool loiterClockwise); void loiterClockwiseChanged (bool loiterClockwise);
void altitudesAreRelativeChanged (bool altitudesAreRelative); void altitudesAreRelativeChanged (bool altitudesAreRelative);
void valueSetIsDistanceChanged (bool valueSetIsDistance); void valueSetIsDistanceChanged (bool valueSetIsDistance);
void loiterDragAngleOnlyChanged (bool loiterDragAngleOnly);
private slots: private slots:
void _recalcFromHeadingAndDistanceChange (void); void _recalcFromHeadingAndDistanceChange (void);
...@@ -147,6 +150,7 @@ private: ...@@ -147,6 +150,7 @@ private:
QGeoCoordinate _landingCoordinate; QGeoCoordinate _landingCoordinate;
bool _landingCoordSet; bool _landingCoordSet;
bool _ignoreRecalcSignals; bool _ignoreRecalcSignals;
bool _loiterDragAngleOnly;
QMap<QString, FactMetaData*> _metaDataMap; QMap<QString, FactMetaData*> _metaDataMap;
......
...@@ -349,7 +349,7 @@ int MissionController::_nextSequenceNumber(void) ...@@ -349,7 +349,7 @@ int MissionController::_nextSequenceNumber(void)
} }
} }
int MissionController::insertSimpleMissionItem(QGeoCoordinate coordinate, int visualItemIndex) VisualMissionItem* MissionController::insertSimpleMissionItem(QGeoCoordinate coordinate, int visualItemIndex, bool makeCurrentItem)
{ {
int sequenceNumber = _nextSequenceNumber(); int sequenceNumber = _nextSequenceNumber();
SimpleMissionItem * newItem = new SimpleMissionItem(_controllerVehicle, _flyView, this); SimpleMissionItem * newItem = new SimpleMissionItem(_controllerVehicle, _flyView, this);
...@@ -373,15 +373,23 @@ int MissionController::insertSimpleMissionItem(QGeoCoordinate coordinate, int vi ...@@ -373,15 +373,23 @@ int MissionController::insertSimpleMissionItem(QGeoCoordinate coordinate, int vi
} }
} }
newItem->setMissionFlightStatus(_missionFlightStatus); newItem->setMissionFlightStatus(_missionFlightStatus);
_visualItems->insert(visualItemIndex, newItem); if (visualItemIndex == -1) {
_visualItems->append(newItem);
} else {
_visualItems->insert(visualItemIndex, newItem);
}
// We send the click coordinate through here to be able to set the planned home position from the user click location if needed // We send the click coordinate through here to be able to set the planned home position from the user click location if needed
_recalcAllWithClickCoordinate(coordinate); _recalcAllWithClickCoordinate(coordinate);
return newItem->sequenceNumber(); if (makeCurrentItem) {
setCurrentPlanViewIndex(newItem->sequenceNumber(), true);
}
return newItem;
} }
int MissionController::insertROIMissionItem(QGeoCoordinate coordinate, int visualItemIndex) VisualMissionItem* MissionController::insertROIMissionItem(QGeoCoordinate coordinate, int visualItemIndex, bool makeCurrentItem)
{ {
int sequenceNumber = _nextSequenceNumber(); int sequenceNumber = _nextSequenceNumber();
SimpleMissionItem * newItem = new SimpleMissionItem(_controllerVehicle, _flyView, this); SimpleMissionItem * newItem = new SimpleMissionItem(_controllerVehicle, _flyView, this);
...@@ -399,16 +407,24 @@ int MissionController::insertROIMissionItem(QGeoCoordinate coordinate, int visua ...@@ -399,16 +407,24 @@ int MissionController::insertROIMissionItem(QGeoCoordinate coordinate, int visua
newItem->altitude()->setRawValue(prevAltitude); newItem->altitude()->setRawValue(prevAltitude);
newItem->setAltitudeMode(static_cast<QGroundControlQmlGlobal::AltitudeMode>(prevAltitudeMode)); newItem->setAltitudeMode(static_cast<QGroundControlQmlGlobal::AltitudeMode>(prevAltitudeMode));
} }
_visualItems->insert(visualItemIndex, newItem); if (visualItemIndex == -1) {
_visualItems->append(newItem);
} else {
_visualItems->insert(visualItemIndex, newItem);
}
_recalcAll(); _recalcAll();
return newItem->sequenceNumber(); if (makeCurrentItem) {
setCurrentPlanViewIndex(newItem->sequenceNumber(), true);
}
return newItem;
} }
int MissionController::insertComplexMissionItem(QString itemName, QGeoCoordinate mapCenterCoordinate, int visualItemIndex) VisualMissionItem* MissionController::insertComplexMissionItem(QString itemName, QGeoCoordinate mapCenterCoordinate, int visualItemIndex, bool makeCurrentItem)
{ {
ComplexMissionItem* newItem; ComplexMissionItem* newItem = nullptr;
// If the ComplexMissionItem is inserted first, add a TakeOff SimpleMissionItem // If the ComplexMissionItem is inserted first, add a TakeOff SimpleMissionItem
if (_visualItems->count() == 1 && (_controllerVehicle->fixedWing() || _controllerVehicle->vtol() || _controllerVehicle->multiRotor())) { if (_visualItems->count() == 1 && (_controllerVehicle->fixedWing() || _controllerVehicle->vtol() || _controllerVehicle->multiRotor())) {
...@@ -428,15 +444,17 @@ int MissionController::insertComplexMissionItem(QString itemName, QGeoCoordinate ...@@ -428,15 +444,17 @@ int MissionController::insertComplexMissionItem(QString itemName, QGeoCoordinate
newItem = new CorridorScanComplexItem(_controllerVehicle, _flyView, QString() /* kmlFile */, _visualItems /* parent */); newItem = new CorridorScanComplexItem(_controllerVehicle, _flyView, QString() /* kmlFile */, _visualItems /* parent */);
} else { } else {
qWarning() << "Internal error: Unknown complex item:" << itemName; qWarning() << "Internal error: Unknown complex item:" << itemName;
return sequenceNumber; return nullptr;
} }
return _insertComplexMissionItemWorker(newItem, visualItemIndex); _insertComplexMissionItemWorker(newItem, visualItemIndex, makeCurrentItem);
return newItem;
} }
int MissionController::insertComplexMissionItemFromKMLOrSHP(QString itemName, QString file, int visualItemIndex) VisualMissionItem* MissionController::insertComplexMissionItemFromKMLOrSHP(QString itemName, QString file, int visualItemIndex, bool makeCurrentItem)
{ {
ComplexMissionItem* newItem; ComplexMissionItem* newItem = nullptr;
if (itemName == patternSurveyName) { if (itemName == patternSurveyName) {
newItem = new SurveyComplexItem(_controllerVehicle, _flyView, file, _visualItems); newItem = new SurveyComplexItem(_controllerVehicle, _flyView, file, _visualItems);
...@@ -446,13 +464,15 @@ int MissionController::insertComplexMissionItemFromKMLOrSHP(QString itemName, QS ...@@ -446,13 +464,15 @@ int MissionController::insertComplexMissionItemFromKMLOrSHP(QString itemName, QS
newItem = new CorridorScanComplexItem(_controllerVehicle, _flyView, file, _visualItems); newItem = new CorridorScanComplexItem(_controllerVehicle, _flyView, file, _visualItems);
} else { } else {
qWarning() << "Internal error: Unknown complex item:" << itemName; qWarning() << "Internal error: Unknown complex item:" << itemName;
return _nextSequenceNumber(); return nullptr;
} }
return _insertComplexMissionItemWorker(newItem, visualItemIndex); _insertComplexMissionItemWorker(newItem, visualItemIndex, makeCurrentItem);
return newItem;
} }
int MissionController::_insertComplexMissionItemWorker(ComplexMissionItem* complexItem, int visualItemIndex) void MissionController::_insertComplexMissionItemWorker(ComplexMissionItem* complexItem, int visualItemIndex, bool makeCurrentItem)
{ {
int sequenceNumber = _nextSequenceNumber(); int sequenceNumber = _nextSequenceNumber();
bool surveyStyleItem = qobject_cast<SurveyComplexItem*>(complexItem) || bool surveyStyleItem = qobject_cast<SurveyComplexItem*>(complexItem) ||
...@@ -500,7 +520,9 @@ int MissionController::_insertComplexMissionItemWorker(ComplexMissionItem* compl ...@@ -500,7 +520,9 @@ int MissionController::_insertComplexMissionItemWorker(ComplexMissionItem* compl
} }
_recalcAll(); _recalcAll();
return complexItem->sequenceNumber(); if (makeCurrentItem) {
setCurrentPlanViewIndex(complexItem->sequenceNumber(), true);
}
} }
void MissionController::removeMissionItem(int index) void MissionController::removeMissionItem(int index)
......
...@@ -103,28 +103,35 @@ public: ...@@ -103,28 +103,35 @@ public:
Q_INVOKABLE void removeMissionItem(int index); Q_INVOKABLE void removeMissionItem(int index);
/// Add a new simple mission item to the list /// Add a new simple mission item to the list
/// @param visualItemIndex: index to insert at /// @param coordinate: Coordinate for item
/// @return Sequence number for new item /// @param visualItemIndex: index to insert at, -1 for end of list
Q_INVOKABLE int insertSimpleMissionItem(QGeoCoordinate coordinate, int visualItemIndex); /// @param makeCurrentItem: true: Make this item the current item
/// @return Newly created item
Q_INVOKABLE VisualMissionItem* insertSimpleMissionItem(QGeoCoordinate coordinate, int visualItemIndex, bool makeCurrentItem = false);
/// Add a new ROI mission item to the list /// Add a new ROI mission item to the list
/// @param visualItemIndex: index to insert at /// @param coordinate: Coordinate for item
/// @return Sequence number for new item /// @param visualItemIndex: index to insert at, -1 for end of list
Q_INVOKABLE int insertROIMissionItem(QGeoCoordinate coordinate, int visualItemIndex); /// @param makeCurrentItem: true: Make this item the current item
/// @return Newly created item
Q_INVOKABLE VisualMissionItem* insertROIMissionItem(QGeoCoordinate coordinate, int visualItemIndex, bool makeCurrentItem = false);
/// Add a new complex mission item to the list /// Add a new complex mission item to the list
/// @param itemName: Name of complex item to create (from complexMissionItemNames) /// @param itemName: Name of complex item to create (from complexMissionItemNames)
/// @param mapCenterCoordinate: coordinate for current center of map /// @param mapCenterCoordinate: coordinate for current center of map
/// @param visualItemIndex: index to insert at /// @param visualItemIndex: index to insert at, -1 for end of list
/// @return Sequence number for new item /// @param makeCurrentItem: true: Make this item the current item
Q_INVOKABLE int insertComplexMissionItem(QString itemName, QGeoCoordinate mapCenterCoordinate, int visualItemIndex); /// @return Newly created item
Q_INVOKABLE VisualMissionItem* insertComplexMissionItem(QString itemName, QGeoCoordinate mapCenterCoordinate, int visualItemIndex, bool makeCurrentItem = false);
/// Add a new complex mission item to the list /// Add a new complex mission item to the list
/// @param itemName: Name of complex item to create (from complexMissionItemNames) /// @param itemName: Name of complex item to create (from complexMissionItemNames)
/// @param file: kml or shp file to load from shape from /// @param file: kml or shp file to load from shape from
/// @param visualItemIndex: index to insert at, -1 for end /// @param coordinate: Coordinate for item
/// @return Sequence number for new item /// @param visualItemIndex: index to insert at, -1 for end of list
Q_INVOKABLE int insertComplexMissionItemFromKMLOrSHP(QString itemName, QString file, int visualItemIndex); /// @param makeCurrentItem: true: Make this item the current item
/// @return Newly created item
Q_INVOKABLE VisualMissionItem* insertComplexMissionItemFromKMLOrSHP(QString itemName, QString file, int visualItemIndex, bool makeCurrentItem = false);
Q_INVOKABLE void resumeMission(int resumeIndex); Q_INVOKABLE void resumeMission(int resumeIndex);
...@@ -284,7 +291,7 @@ private: ...@@ -284,7 +291,7 @@ private:
void _initLoadedVisualItems(QmlObjectListModel* loadedVisualItems); void _initLoadedVisualItems(QmlObjectListModel* loadedVisualItems);
CoordinateVector* _addWaypointLineSegment(CoordVectHashTable& prevItemPairHashTable, VisualItemPair& pair); CoordinateVector* _addWaypointLineSegment(CoordVectHashTable& prevItemPairHashTable, VisualItemPair& pair);
void _addTimeDistance(bool vtolInHover, double hoverTime, double cruiseTime, double extraTime, double distance, int seqNum); void _addTimeDistance(bool vtolInHover, double hoverTime, double cruiseTime, double extraTime, double distance, int seqNum);
int _insertComplexMissionItemWorker(ComplexMissionItem* complexItem, int visualItemIndex); void _insertComplexMissionItemWorker(ComplexMissionItem* complexItem, int visualItemIndex, bool makeCurrentItem);
void _warnIfTerrainFrameUsed(void); void _warnIfTerrainFrameUsed(void);
private: private:
......
...@@ -200,6 +200,8 @@ void SimpleMissionItem::_connectSignals(void) ...@@ -200,6 +200,8 @@ void SimpleMissionItem::_connectSignals(void)
connect(this, &SimpleMissionItem::cameraSectionChanged, this, &SimpleMissionItem::_setDirty); connect(this, &SimpleMissionItem::cameraSectionChanged, this, &SimpleMissionItem::_setDirty);
connect(this, &SimpleMissionItem::cameraSectionChanged, this, &SimpleMissionItem::_updateLastSequenceNumber); connect(this, &SimpleMissionItem::cameraSectionChanged, this, &SimpleMissionItem::_updateLastSequenceNumber);
connect(this, &SimpleMissionItem::wizardModeChanged, this, &SimpleMissionItem::readyForSaveStateChanged);
// These are coordinate parameters, they must emit coordinateChanged signal // These are coordinate parameters, they must emit coordinateChanged signal
connect(&_missionItem._param5Fact, &Fact::valueChanged, this, &SimpleMissionItem::_sendCoordinateChanged); connect(&_missionItem._param5Fact, &Fact::valueChanged, this, &SimpleMissionItem::_sendCoordinateChanged);
connect(&_missionItem._param6Fact, &Fact::valueChanged, this, &SimpleMissionItem::_sendCoordinateChanged); connect(&_missionItem._param6Fact, &Fact::valueChanged, this, &SimpleMissionItem::_sendCoordinateChanged);
...@@ -325,6 +327,7 @@ bool SimpleMissionItem::load(QTextStream &loadStream) ...@@ -325,6 +327,7 @@ bool SimpleMissionItem::load(QTextStream &loadStream)
} }
_updateOptionalSections(); _updateOptionalSections();
} }
return success; return success;
} }
...@@ -726,6 +729,10 @@ void SimpleMissionItem::_terrainAltChanged(void) ...@@ -726,6 +729,10 @@ void SimpleMissionItem::_terrainAltChanged(void)
SimpleMissionItem::ReadyForSaveState SimpleMissionItem::readyForSaveState(void) const SimpleMissionItem::ReadyForSaveState SimpleMissionItem::readyForSaveState(void) const
{ {
if (_wizardMode) {
return NotReadyForSaveData;
}
bool terrainReady = !specifiesAltitude() || !qIsNaN(_missionItem._param7Fact.rawValue().toDouble()); bool terrainReady = !specifiesAltitude() || !qIsNaN(_missionItem._param7Fact.rawValue().toDouble());
return terrainReady ? ReadyForSave : NotReadyForSaveTerrain; return terrainReady ? ReadyForSave : NotReadyForSaveTerrain;
} }
......
...@@ -99,7 +99,6 @@ public: ...@@ -99,7 +99,6 @@ public:
const MissionItem& missionItem(void) const { return _missionItem; } const MissionItem& missionItem(void) const { return _missionItem; }
// Overrides from VisualMissionItem // Overrides from VisualMissionItem
bool dirty (void) const final { return _dirty; } bool dirty (void) const final { return _dirty; }
bool isSimpleItem (void) const final { return true; } bool isSimpleItem (void) const final { return true; }
bool isStandaloneCoordinate (void) const final; bool isStandaloneCoordinate (void) const final;
...@@ -154,7 +153,7 @@ private slots: ...@@ -154,7 +153,7 @@ private slots:
void _rebuildFacts (void); void _rebuildFacts (void);
void _rebuildTextFieldFacts (void); void _rebuildTextFieldFacts (void);
void _possibleAdditionalTimeDelayChanged(void); void _possibleAdditionalTimeDelayChanged(void);
void _setDefaultsForCommand (void); void _setDefaultsForCommand (void);
private: private:
void _connectSignals (void); void _connectSignals (void);
......
...@@ -87,6 +87,8 @@ StructureScanComplexItem::StructureScanComplexItem(Vehicle* vehicle, bool flyVie ...@@ -87,6 +87,8 @@ StructureScanComplexItem::StructureScanComplexItem(Vehicle* vehicle, bool flyVie
connect(&_layersFact, &Fact::valueChanged, this, &StructureScanComplexItem::_recalcScanDistance); connect(&_layersFact, &Fact::valueChanged, this, &StructureScanComplexItem::_recalcScanDistance);
connect(&_flightPolygon, &QGCMapPolygon::pathChanged, this, &StructureScanComplexItem::_recalcScanDistance); connect(&_flightPolygon, &QGCMapPolygon::pathChanged, this, &StructureScanComplexItem::_recalcScanDistance);
connect(this, &StructureScanComplexItem::wizardModeChanged, this, &StructureScanComplexItem::readyForSaveStateChanged);
_recalcLayerInfo(); _recalcLayerInfo();
if (!kmlOrShpFile.isEmpty()) { if (!kmlOrShpFile.isEmpty()) {
...@@ -621,5 +623,5 @@ void StructureScanComplexItem::_recalcScanDistance() ...@@ -621,5 +623,5 @@ void StructureScanComplexItem::_recalcScanDistance()
StructureScanComplexItem::ReadyForSaveState StructureScanComplexItem::readyForSaveState(void) const StructureScanComplexItem::ReadyForSaveState StructureScanComplexItem::readyForSaveState(void) const
{ {
return _structurePolygon.isValid() ? ReadyForSave : NotReadyForSaveData; return _structurePolygon.isValid() && !_wizardMode ? ReadyForSave : NotReadyForSaveData;
} }
...@@ -10,6 +10,7 @@ ...@@ -10,6 +10,7 @@
#include "StructureScanPlanCreator.h" #include "StructureScanPlanCreator.h"
#include "PlanMasterController.h" #include "PlanMasterController.h"
#include "MissionSettingsItem.h" #include "MissionSettingsItem.h"
#include "FixedWingLandingComplexItem.h"
StructureScanPlanCreator::StructureScanPlanCreator(PlanMasterController* planMasterController, QObject* parent) StructureScanPlanCreator::StructureScanPlanCreator(PlanMasterController* planMasterController, QObject* parent)
: PlanCreator(planMasterController, MissionController::patternStructureScanName, QStringLiteral("/qmlimages/PlanCreator/StructureScanPlanCreator.png"), parent) : PlanCreator(planMasterController, MissionController::patternStructureScanName, QStringLiteral("/qmlimages/PlanCreator/StructureScanPlanCreator.png"), parent)
...@@ -20,18 +21,16 @@ StructureScanPlanCreator::StructureScanPlanCreator(PlanMasterController* planMas ...@@ -20,18 +21,16 @@ StructureScanPlanCreator::StructureScanPlanCreator(PlanMasterController* planMas
void StructureScanPlanCreator::createPlan(const QGeoCoordinate& mapCenterCoord) void StructureScanPlanCreator::createPlan(const QGeoCoordinate& mapCenterCoord)
{ {
_planMasterController->removeAll(); _planMasterController->removeAll();
int seqNum = _missionController->insertComplexMissionItem( VisualMissionItem* takeoffItem = _missionController->insertSimpleMissionItem(mapCenterCoord, -1);
MissionController::patternStructureScanName, takeoffItem->setWizardMode(true);
mapCenterCoord, _missionController->insertComplexMissionItem(MissionController::patternStructureScanName, mapCenterCoord, -1)->setWizardMode(true);
_missionController->visualItems()->count());
if (_planMasterController->managerVehicle()->fixedWing()) { if (_planMasterController->managerVehicle()->fixedWing()) {
_missionController->insertComplexMissionItem( FixedWingLandingComplexItem* landingItem = qobject_cast<FixedWingLandingComplexItem*>(_missionController->insertComplexMissionItem(MissionController::patternFWLandingName, mapCenterCoord, -1));
MissionController::patternFWLandingName, landingItem->setWizardMode(true);
mapCenterCoord, landingItem->setLoiterDragAngleOnly(true);
_missionController->visualItems()->count());
} else { } else {
MissionSettingsItem* settingsItem = _missionController->visualItems()->value<MissionSettingsItem*>(0); MissionSettingsItem* settingsItem = _missionController->visualItems()->value<MissionSettingsItem*>(0);
settingsItem->setMissionEndRTL(true); settingsItem->setMissionEndRTL(true);
} }
_missionController->setCurrentPlanViewIndex(seqNum, false); _missionController->setCurrentPlanViewIndex(takeoffItem->sequenceNumber(), true);
} }
...@@ -10,6 +10,8 @@ ...@@ -10,6 +10,8 @@
#include "SurveyPlanCreator.h" #include "SurveyPlanCreator.h"
#include "PlanMasterController.h" #include "PlanMasterController.h"
#include "MissionSettingsItem.h" #include "MissionSettingsItem.h"
#include "FixedWingLandingComplexItem.h"
#include "FixedWingLandingComplexItem.h"
SurveyPlanCreator::SurveyPlanCreator(PlanMasterController* planMasterController, QObject* parent) SurveyPlanCreator::SurveyPlanCreator(PlanMasterController* planMasterController, QObject* parent)
: PlanCreator(planMasterController, MissionController::patternSurveyName, QStringLiteral("/qmlimages/PlanCreator/SurveyPlanCreator.png"), parent) : PlanCreator(planMasterController, MissionController::patternSurveyName, QStringLiteral("/qmlimages/PlanCreator/SurveyPlanCreator.png"), parent)
...@@ -20,18 +22,16 @@ SurveyPlanCreator::SurveyPlanCreator(PlanMasterController* planMasterController, ...@@ -20,18 +22,16 @@ SurveyPlanCreator::SurveyPlanCreator(PlanMasterController* planMasterController,
void SurveyPlanCreator::createPlan(const QGeoCoordinate& mapCenterCoord) void SurveyPlanCreator::createPlan(const QGeoCoordinate& mapCenterCoord)
{ {
_planMasterController->removeAll(); _planMasterController->removeAll();
int seqNum = _missionController->insertComplexMissionItem( VisualMissionItem* takeoffItem = _missionController->insertSimpleMissionItem(mapCenterCoord, -1);
MissionController::patternSurveyName, takeoffItem->setWizardMode(true);
mapCenterCoord, _missionController->insertComplexMissionItem(MissionController::patternSurveyName, mapCenterCoord, -1)->setWizardMode(true);
_missionController->visualItems()->count());
if (_planMasterController->managerVehicle()->fixedWing()) { if (_planMasterController->managerVehicle()->fixedWing()) {
_missionController->insertComplexMissionItem( FixedWingLandingComplexItem* landingItem = qobject_cast<FixedWingLandingComplexItem*>(_missionController->insertComplexMissionItem(MissionController::patternFWLandingName, mapCenterCoord, -1));
MissionController::patternFWLandingName, landingItem->setWizardMode(true);
mapCenterCoord, landingItem->setLoiterDragAngleOnly(true);
_missionController->visualItems()->count());
} else { } else {
MissionSettingsItem* settingsItem = _missionController->visualItems()->value<MissionSettingsItem*>(0); MissionSettingsItem* settingsItem = _missionController->visualItems()->value<MissionSettingsItem*>(0);
settingsItem->setMissionEndRTL(true); settingsItem->setMissionEndRTL(true);
} }
_missionController->setCurrentPlanViewIndex(seqNum, false); _missionController->setCurrentPlanViewIndex(takeoffItem->sequenceNumber(), true);
} }
...@@ -106,8 +106,8 @@ TransectStyleComplexItem::TransectStyleComplexItem(Vehicle* vehicle, bool flyVie ...@@ -106,8 +106,8 @@ TransectStyleComplexItem::TransectStyleComplexItem(Vehicle* vehicle, bool flyVie
connect(this, &TransectStyleComplexItem::visualTransectPointsChanged, this, &TransectStyleComplexItem::complexDistanceChanged); connect(this, &TransectStyleComplexItem::visualTransectPointsChanged, this, &TransectStyleComplexItem::complexDistanceChanged);
connect(this, &TransectStyleComplexItem::visualTransectPointsChanged, this, &TransectStyleComplexItem::greatestDistanceToChanged); connect(this, &TransectStyleComplexItem::visualTransectPointsChanged, this, &TransectStyleComplexItem::greatestDistanceToChanged);
connect(this, &TransectStyleComplexItem::followTerrainChanged, this, &TransectStyleComplexItem::_followTerrainChanged);
connect(this, &TransectStyleComplexItem::followTerrainChanged, this, &TransectStyleComplexItem::_followTerrainChanged); connect(this, &TransectStyleComplexItem::wizardModeChanged, this, &TransectStyleComplexItem::readyForSaveStateChanged);
connect(&_surveyAreaPolygon, &QGCMapPolygon::isValidChanged, this, &TransectStyleComplexItem::readyForSaveStateChanged); connect(&_surveyAreaPolygon, &QGCMapPolygon::isValidChanged, this, &TransectStyleComplexItem::readyForSaveStateChanged);
...@@ -494,7 +494,7 @@ TransectStyleComplexItem::ReadyForSaveState TransectStyleComplexItem::readyForSa ...@@ -494,7 +494,7 @@ TransectStyleComplexItem::ReadyForSaveState TransectStyleComplexItem::readyForSa
{ {
bool terrainReady = _followTerrain ? _transectsPathHeightInfo.count() : true; bool terrainReady = _followTerrain ? _transectsPathHeightInfo.count() : true;
bool polygonNotReady = !_surveyAreaPolygon.isValid(); bool polygonNotReady = !_surveyAreaPolygon.isValid();
return polygonNotReady ? return (polygonNotReady || _wizardMode) ?
NotReadyForSaveData : NotReadyForSaveData :
(terrainReady ? ReadyForSave : NotReadyForSaveTerrain); (terrainReady ? ReadyForSave : NotReadyForSaveTerrain);
} }
......
...@@ -37,6 +37,7 @@ VisualMissionItem::VisualMissionItem(Vehicle* vehicle, bool flyView, QObject* pa ...@@ -37,6 +37,7 @@ VisualMissionItem::VisualMissionItem(Vehicle* vehicle, bool flyView, QObject* pa
, _distance (0.0) , _distance (0.0)
, _missionGimbalYaw (qQNaN()) , _missionGimbalYaw (qQNaN())
, _missionVehicleYaw (qQNaN()) , _missionVehicleYaw (qQNaN())
, _wizardMode (false)
, _lastLatTerrainQuery (0) , _lastLatTerrainQuery (0)
, _lastLonTerrainQuery (0) , _lastLonTerrainQuery (0)
{ {
...@@ -56,6 +57,7 @@ VisualMissionItem::VisualMissionItem(const VisualMissionItem& other, bool flyVie ...@@ -56,6 +57,7 @@ VisualMissionItem::VisualMissionItem(const VisualMissionItem& other, bool flyVie
, _terrainCollision (false) , _terrainCollision (false)
, _azimuth (0.0) , _azimuth (0.0)
, _distance (0.0) , _distance (0.0)
, _wizardMode (false)
{ {
*this = other; *this = other;
...@@ -218,3 +220,10 @@ void VisualMissionItem::_setBoundingCube(QGCGeoBoundingCube bc) ...@@ -218,3 +220,10 @@ void VisualMissionItem::_setBoundingCube(QGCGeoBoundingCube bc)
} }
} }
void VisualMissionItem::setWizardMode(bool wizardMode)
{
if (wizardMode != _wizardMode) {
_wizardMode = wizardMode;
emit wizardModeChanged(_wizardMode);
}
}
...@@ -74,6 +74,7 @@ public: ...@@ -74,6 +74,7 @@ public:
Q_PROPERTY(double missionGimbalYaw READ missionGimbalYaw NOTIFY missionGimbalYawChanged) ///< Current gimbal yaw state at this point in mission Q_PROPERTY(double missionGimbalYaw READ missionGimbalYaw NOTIFY missionGimbalYawChanged) ///< Current gimbal yaw state at this point in mission
Q_PROPERTY(double missionVehicleYaw READ missionVehicleYaw NOTIFY missionVehicleYawChanged) ///< Expected vehicle yaw at this point in mission Q_PROPERTY(double missionVehicleYaw READ missionVehicleYaw NOTIFY missionVehicleYawChanged) ///< Expected vehicle yaw at this point in mission
Q_PROPERTY(bool flyView READ flyView CONSTANT) Q_PROPERTY(bool flyView READ flyView CONSTANT)
Q_PROPERTY(bool wizardMode READ wizardMode WRITE setWizardMode NOTIFY wizardModeChanged)
Q_PROPERTY(ReadyForSaveState readyForSaveState READ readyForSaveState NOTIFY readyForSaveStateChanged) Q_PROPERTY(ReadyForSaveState readyForSaveState READ readyForSaveState NOTIFY readyForSaveStateChanged)
Q_PROPERTY(QGCGeoBoundingCube* boundingCube READ boundingCube NOTIFY boundingCubeChanged) Q_PROPERTY(QGCGeoBoundingCube* boundingCube READ boundingCube NOTIFY boundingCubeChanged)
...@@ -88,19 +89,17 @@ public: ...@@ -88,19 +89,17 @@ public:
Q_PROPERTY(double distance READ distance WRITE setDistance NOTIFY distanceChanged) ///< Distance to previous waypoint Q_PROPERTY(double distance READ distance WRITE setDistance NOTIFY distanceChanged) ///< Distance to previous waypoint
// Property accesors // Property accesors
bool homePosition (void) const { return _homePositionSpecialCase; }
bool homePosition (void) const { return _homePositionSpecialCase; } double altDifference (void) const { return _altDifference; }
void setHomePositionSpecialCase (bool homePositionSpecialCase) { _homePositionSpecialCase = homePositionSpecialCase; } double altPercent (void) const { return _altPercent; }
double terrainPercent (void) const { return _terrainPercent; }
double altDifference (void) const { return _altDifference; } bool terrainCollision(void) const { return _terrainCollision; }
double altPercent (void) const { return _altPercent; } double azimuth (void) const { return _azimuth; }
double terrainPercent (void) const { return _terrainPercent; } double distance (void) const { return _distance; }
bool terrainCollision (void) const { return _terrainCollision; } bool isCurrentItem (void) const { return _isCurrentItem; }
double azimuth (void) const { return _azimuth; } double terrainAltitude (void) const { return _terrainAltitude; }
double distance (void) const { return _distance; } bool flyView (void) const { return _flyView; }
bool isCurrentItem (void) const { return _isCurrentItem; } bool wizardMode (void) const { return _wizardMode; }
double terrainAltitude (void) const { return _terrainAltitude; }
bool flyView (void) const { return _flyView; }
QmlObjectListModel* childItems(void) { return &_childItems; } QmlObjectListModel* childItems(void) { return &_childItems; }
...@@ -111,6 +110,9 @@ public: ...@@ -111,6 +110,9 @@ public:
void setTerrainCollision(bool terrainCollision); void setTerrainCollision(bool terrainCollision);
void setAzimuth (double azimuth); void setAzimuth (double azimuth);
void setDistance (double distance); void setDistance (double distance);
void setWizardMode (bool wizardMode);
void setHomePositionSpecialCase (bool homePositionSpecialCase) { _homePositionSpecialCase = homePositionSpecialCase; }
Vehicle* vehicle(void) { return _vehicle; } Vehicle* vehicle(void) { return _vehicle; }
...@@ -205,6 +207,7 @@ signals: ...@@ -205,6 +207,7 @@ signals:
void additionalTimeDelayChanged (void); void additionalTimeDelayChanged (void);
void boundingCubeChanged (void); void boundingCubeChanged (void);
void readyForSaveStateChanged (void); void readyForSaveStateChanged (void);
void wizardModeChanged (bool wizardMode);
void coordinateHasRelativeAltitudeChanged (bool coordinateHasRelativeAltitude); void coordinateHasRelativeAltitudeChanged (bool coordinateHasRelativeAltitude);
void exitCoordinateHasRelativeAltitudeChanged (bool exitCoordinateHasRelativeAltitude); void exitCoordinateHasRelativeAltitudeChanged (bool exitCoordinateHasRelativeAltitude);
...@@ -226,6 +229,7 @@ protected: ...@@ -226,6 +229,7 @@ protected:
QString _editorQml; ///< Qml resource for editing item QString _editorQml; ///< Qml resource for editing item
double _missionGimbalYaw; double _missionGimbalYaw;
double _missionVehicleYaw; double _missionVehicleYaw;
bool _wizardMode; ///< true: Item editor is showing wizard completion panel
QGCGeoBoundingCube _boundingCube; ///< The bounding "cube" of this element. QGCGeoBoundingCube _boundingCube; ///< The bounding "cube" of this element.
......
...@@ -56,23 +56,34 @@ Rectangle { ...@@ -56,23 +56,34 @@ Rectangle {
anchors.right: parent.right anchors.right: parent.right
ColumnLayout { ColumnLayout {
id: wizardModeColumn
anchors.left: parent.left anchors.left: parent.left
anchors.right: parent.right anchors.right: parent.right
spacing: _margin spacing: _margin
visible: !missionItem.corridorPolyline.isValid visible: !missionItem.corridorPolyline.isValid || missionItem.wizardMode
QGCLabel { QGCLabel {
Layout.fillWidth: true Layout.fillWidth: true
wrapMode: Text.WordWrap wrapMode: Text.WordWrap
text: qsTr("Use the Corridor Tools to create the polyline which defines the corridor.") text: qsTr("Use the Corridor Tools to create the polyline which defines the corridor.")
} }
QGCButton {
text: qsTr("Done With Polyline")
Layout.fillWidth: true
enabled: missionItem.corridorPolyline.isValid
onClicked: {
missionItem.wizardMode = false
editorRoot.selectNextNotReadyItem()
}
}
} }
Column { Column {
anchors.left: parent.left anchors.left: parent.left
anchors.right: parent.right anchors.right: parent.right
spacing: _margin spacing: _margin
visible: missionItem.corridorPolyline.isValid visible: !wizardModeColumn.visible
QGCTabBar { QGCTabBar {
id: tabBar id: tabBar
......
...@@ -49,7 +49,7 @@ Rectangle { ...@@ -49,7 +49,7 @@ Rectangle {
anchors.left: parent.left anchors.left: parent.left
anchors.right: parent.right anchors.right: parent.right
spacing: _margin spacing: _margin
visible: missionItem.landingCoordSet visible: !editorColumnNeedLandingPoint.visible
SectionHeader { SectionHeader {
id: loiterPointSection id: loiterPointSection
...@@ -216,33 +216,70 @@ Rectangle { ...@@ -216,33 +216,70 @@ Rectangle {
anchors.top: parent.top anchors.top: parent.top
anchors.left: parent.left anchors.left: parent.left
anchors.right: parent.right anchors.right: parent.right
visible: !missionItem.landingCoordSet visible: !missionItem.landingCoordSet || missionItem.wizardMode
spacing: ScreenTools.defaultFontPixelHeight spacing: ScreenTools.defaultFontPixelHeight
QGCLabel { Column {
anchors.left: parent.left id: landingCoordColumn
anchors.right: parent.right anchors.left: parent.left
wrapMode: Text.WordWrap anchors.right: parent.right
horizontalAlignment: Text.AlignHCenter spacing: ScreenTools.defaultFontPixelHeight
text: qsTr("Click in map to set landing point.") visible: !missionItem.landingCoordSet
}
QGCLabel {
anchors.left: parent.left
anchors.right: parent.right
wrapMode: Text.WordWrap
horizontalAlignment: Text.AlignHCenter
text: qsTr("Click in map to set landing point.")
}
QGCLabel { QGCLabel {
anchors.left: parent.left anchors.left: parent.left
anchors.right: parent.right anchors.right: parent.right
horizontalAlignment: Text.AlignHCenter horizontalAlignment: Text.AlignHCenter
text: qsTr("- or -") text: qsTr("- or -")
visible: activeVehicle visible: activeVehicle
}
QGCButton {
anchors.horizontalCenter: parent.horizontalCenter
text: _setToVehicleLocationStr
visible: activeVehicle
onClicked: {
missionItem.landingCoordinate = activeVehicle.coordinate
missionItem.landingHeading.rawValue = activeVehicle.heading.rawValue
}
}
} }
QGCButton { ColumnLayout {
anchors.horizontalCenter: parent.horizontalCenter anchors.left: parent.left
text: _setToVehicleLocationStr anchors.right: parent.right
visible: activeVehicle spacing: ScreenTools.defaultFontPixelHeight
visible: !landingCoordColumn.visible
onVisibleChanged: {
if (visible) {
console.log(missionItem.landingDistance.rawValue)
}
}
onClicked: { QGCLabel {
missionItem.landingCoordinate = activeVehicle.coordinate Layout.fillWidth: true
missionItem.landingHeading.rawValue = activeVehicle.heading.rawValue wrapMode: Text.WordWrap
text: qsTr("Drag the loiter point to adjust landing direction for wind and obstacles.")
}
QGCButton {
text: qsTr("Done Adjusting")
Layout.fillWidth: true
onClicked: {
missionItem.wizardMode = false
missionItem.landingDragAngleOnly = false
editorRoot.selectNextNotReadyItem()
}
} }
} }
} }
......
...@@ -198,11 +198,25 @@ Item { ...@@ -198,11 +198,25 @@ Item {
itemIndicator: _loiterPointObject itemIndicator: _loiterPointObject
itemCoordinate: _missionItem.loiterCoordinate itemCoordinate: _missionItem.loiterCoordinate
onItemCoordinateChanged: _missionItem.loiterCoordinate = itemCoordinate property bool _preventReentrancy: false
onItemCoordinateChanged: {
if (!_preventReentrancy) {
if (Drag.active && _missionItem.loiterDragAngleOnly) {
_preventReentrancy = true
var angle = _missionItem.landingCoordinate.azimuthTo(itemCoordinate)
var distance = _missionItem.landingCoordinate.distanceTo(_missionItem.loiterCoordinate)
_missionItem.loiterCoordinate = _missionItem.landingCoordinate.atDistanceAndAzimuth(distance, angle)
_preventReentrancy = false
} else {
_missionItem.loiterCoordinate = itemCoordinate
}
}
}
} }
} }
// Control which is used to drag the loiter point // Control which is used to drag the landing point
Component { Component {
id: landDragAreaComponent id: landDragAreaComponent
......
...@@ -29,6 +29,7 @@ Rectangle { ...@@ -29,6 +29,7 @@ Rectangle {
signal remove signal remove
signal insertWaypoint signal insertWaypoint
signal insertComplexItem(string complexItemName) signal insertComplexItem(string complexItemName)
signal selectNextNotReadyItem
property var _masterController: masterController property var _masterController: masterController
property var _missionController: _masterController.missionController property var _missionController: _masterController.missionController
......
...@@ -68,13 +68,11 @@ Item { ...@@ -68,13 +68,11 @@ Item {
} }
function insertComplexMissionItem(complexItemName, coordinate, index) { function insertComplexMissionItem(complexItemName, coordinate, index) {
var sequenceNumber = _missionController.insertComplexMissionItem(complexItemName, coordinate, index) _missionController.insertComplexMissionItem(complexItemName, coordinate, index, true /* makeCurrentItem */)
_missionController.setCurrentPlanViewIndex(sequenceNumber, true)
} }
function insertComplexMissionItemFromKMLOrSHP(complexItemName, file, index) { function insertComplexMissionItemFromKMLOrSHP(complexItemName, file, index) {
var sequenceNumber = _missionController.insertComplexMissionItemFromKMLOrSHP(complexItemName, file, index) _missionController.insertComplexMissionItemFromKMLOrSHP(complexItemName, file, index, true /* makeCurrentItem */)
_missionController.setCurrentPlanViewIndex(sequenceNumber, true)
} }
function updateAirspace(reset) { function updateAirspace(reset) {
...@@ -267,8 +265,7 @@ Item { ...@@ -267,8 +265,7 @@ Item {
/// @param coordinate Location to insert item /// @param coordinate Location to insert item
/// @param index Insert item at this index /// @param index Insert item at this index
function insertSimpleMissionItem(coordinate, index) { function insertSimpleMissionItem(coordinate, index) {
var sequenceNumber = _missionController.insertSimpleMissionItem(coordinate, index) _missionController.insertSimpleMissionItem(coordinate, index, true /* makeCurrentItem */)
_missionController.setCurrentPlanViewIndex(sequenceNumber, true)
} }
/// Inserts a new ROI mission item /// Inserts a new ROI mission item
...@@ -281,6 +278,17 @@ Item { ...@@ -281,6 +278,17 @@ Item {
toolStrip.lastClickedButton.checked = false toolStrip.lastClickedButton.checked = false
} }
function selectNextNotReady() {
var foundCurrent = false
for (var i=0; i<_missionController.visualItems.count; i++) {
var vmi = _missionController.visualItems.get(i)
if (vmi.readyForSaveState === VisualMissionItem.NotReadyForSaveData) {
_missionController.setCurrentPlanViewIndex(vmi.sequenceNumber, true)
break
}
}
}
property int _moveDialogMissionItemIndex property int _moveDialogMissionItemIndex
QGCFileDialog { QGCFileDialog {
...@@ -822,8 +830,9 @@ Item { ...@@ -822,8 +830,9 @@ Item {
} }
_missionController.setCurrentPlanViewIndex(removeIndex, true) _missionController.setCurrentPlanViewIndex(removeIndex, true)
} }
onInsertWaypoint: insertSimpleMissionItem(editorMap.center, index) onInsertWaypoint: insertSimpleMissionItem(editorMap.center, index)
onInsertComplexItem: insertComplexMissionItem(complexItemName, editorMap.center, index) onInsertComplexItem: insertComplexMissionItem(complexItemName, editorMap.center, index)
onSelectNextNotReadyItem: selectNextNotReady()
} }
} }
} }
......
This diff is collapsed.
...@@ -57,23 +57,34 @@ Rectangle { ...@@ -57,23 +57,34 @@ Rectangle {
anchors.right: parent.right anchors.right: parent.right
ColumnLayout { ColumnLayout {
id: wizardColumn
anchors.left: parent.left anchors.left: parent.left
anchors.right: parent.right anchors.right: parent.right
spacing: _margin spacing: _margin
visible: !missionItem.structurePolygon.isValid visible: !missionItem.structurePolygon.isValid || missionItem.wizardMode
QGCLabel { QGCLabel {
Layout.fillWidth: true Layout.fillWidth: true
wrapMode: Text.WordWrap wrapMode: Text.WordWrap
text: qsTr("Use the Polygon Tools to create the polygon which outlines the structure.") text: qsTr("Use the Polygon Tools to create the polygon which outlines the structure.")
} }
QGCButton {
text: qsTr("Done With Polygon")
Layout.fillWidth: true
enabled: missionItem.structurePolygon.isValid
onClicked: {
missionItem.wizardMode = false
editorRoot.selectNextNotReadyItem()
}
}
} }
Column { Column {
anchors.left: parent.left anchors.left: parent.left
anchors.right: parent.right anchors.right: parent.right
spacing: _margin spacing: _margin
visible: missionItem.structurePolygon.isValid visible: !wizardColumn.visible
QGCTabBar { QGCTabBar {
id: tabBar id: tabBar
......
...@@ -56,23 +56,34 @@ Rectangle { ...@@ -56,23 +56,34 @@ Rectangle {
anchors.right: parent.right anchors.right: parent.right
ColumnLayout { ColumnLayout {
id: wizardColumn
anchors.left: parent.left anchors.left: parent.left
anchors.right: parent.right anchors.right: parent.right
spacing: _margin spacing: _margin
visible: !missionItem.surveyAreaPolygon.isValid visible: !missionItem.surveyAreaPolygon.isValid || missionItem.wizardMode
QGCLabel { QGCLabel {
Layout.fillWidth: true Layout.fillWidth: true
wrapMode: Text.WordWrap wrapMode: Text.WordWrap
text: qsTr("Use the Polygon Tools to create the polygon which outlines your survey area.") text: qsTr("Use the Polygon Tools to create the polygon which outlines your survey area.")
} }
QGCButton {
text: qsTr("Done With Polygon")
Layout.fillWidth: true
enabled: missionItem.surveyAreaPolygon.isValid
onClicked: {
missionItem.wizardMode = false
editorRoot.selectNextNotReadyItem()
}
}
} }
Column { Column {
anchors.left: parent.left anchors.left: parent.left
anchors.right: parent.right anchors.right: parent.right
spacing: _margin spacing: _margin
visible: missionItem.surveyAreaPolygon.isValid visible: !wizardColumn.visible
QGCTabBar { QGCTabBar {
id: tabBar id: tabBar
......
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