Commit cfedca5a authored by DonLakeFlyer's avatar DonLakeFlyer

parent 10fc35fb
...@@ -6,6 +6,7 @@ Note: This file only contains high level features or important fixes. ...@@ -6,6 +6,7 @@ Note: This file only contains high level features or important fixes.
### 3.6.0 - Daily Build ### 3.6.0 - Daily Build
* Plan View: New create plan UI for initial plan creation
* New Corridor editing tools ui. Includes ability to trace polyline by clicking. * New Corridor editing tools ui. Includes ability to trace polyline by clicking.
* New Polygon editing tools ui. Includes ability to trace polygon by clicking. * New Polygon editing tools ui. Includes ability to trace polygon by clicking.
* ArduCopter/Rover: Follow Me setup page * ArduCopter/Rover: Follow Me setup page
......
...@@ -127,6 +127,10 @@ ...@@ -127,6 +127,10 @@
<file alias="pipHide.svg">src/FlightMap/Images/pipHide.svg</file> <file alias="pipHide.svg">src/FlightMap/Images/pipHide.svg</file>
<file alias="pipResize.svg">src/FlightMap/Images/pipResize.svg</file> <file alias="pipResize.svg">src/FlightMap/Images/pipResize.svg</file>
<file alias="Plan.svg">src/ui/toolbar/Images/Plan.svg</file> <file alias="Plan.svg">src/ui/toolbar/Images/Plan.svg</file>
<file alias="PlanCreator/CustomPlanCreator.png">src/MissionManager/CustomPlanCreator.png</file>
<file alias="PlanCreator/CorridorScanPlanCreator.png">src/MissionManager/CorridorScanPlanCreator.png</file>
<file alias="PlanCreator/StructureScanPlanCreator.png">src/MissionManager/StructureScanPlanCreator.png</file>
<file alias="PlanCreator/SurveyPlanCreator.png">src/MissionManager/SurveyPlanCreator.png</file>
<file alias="PowerComponentBattery_01cell.svg">src/AutoPilotPlugins/PX4/Images/PowerComponentBattery_01cell.svg</file> <file alias="PowerComponentBattery_01cell.svg">src/AutoPilotPlugins/PX4/Images/PowerComponentBattery_01cell.svg</file>
<file alias="PowerComponentBattery_02cell.svg">src/AutoPilotPlugins/PX4/Images/PowerComponentBattery_02cell.svg</file> <file alias="PowerComponentBattery_02cell.svg">src/AutoPilotPlugins/PX4/Images/PowerComponentBattery_02cell.svg</file>
<file alias="PowerComponentBattery_03cell.svg">src/AutoPilotPlugins/PX4/Images/PowerComponentBattery_03cell.svg</file> <file alias="PowerComponentBattery_03cell.svg">src/AutoPilotPlugins/PX4/Images/PowerComponentBattery_03cell.svg</file>
......
...@@ -591,6 +591,8 @@ HEADERS += \ ...@@ -591,6 +591,8 @@ HEADERS += \
src/MissionManager/CameraSpec.h \ src/MissionManager/CameraSpec.h \
src/MissionManager/ComplexMissionItem.h \ src/MissionManager/ComplexMissionItem.h \
src/MissionManager/CorridorScanComplexItem.h \ src/MissionManager/CorridorScanComplexItem.h \
src/MissionManager/CorridorScanPlanCreator.h \
src/MissionManager/CustomPlanCreator.h \
src/MissionManager/FixedWingLandingComplexItem.h \ src/MissionManager/FixedWingLandingComplexItem.h \
src/MissionManager/GeoFenceController.h \ src/MissionManager/GeoFenceController.h \
src/MissionManager/GeoFenceManager.h \ src/MissionManager/GeoFenceManager.h \
...@@ -603,6 +605,7 @@ HEADERS += \ ...@@ -603,6 +605,7 @@ HEADERS += \
src/MissionManager/MissionManager.h \ src/MissionManager/MissionManager.h \
src/MissionManager/MissionSettingsItem.h \ src/MissionManager/MissionSettingsItem.h \
src/MissionManager/PlanElementController.h \ src/MissionManager/PlanElementController.h \
src/MissionManager/PlanCreator.h \
src/MissionManager/PlanManager.h \ src/MissionManager/PlanManager.h \
src/MissionManager/PlanMasterController.h \ src/MissionManager/PlanMasterController.h \
src/MissionManager/QGCFenceCircle.h \ src/MissionManager/QGCFenceCircle.h \
...@@ -617,7 +620,9 @@ HEADERS += \ ...@@ -617,7 +620,9 @@ HEADERS += \
src/MissionManager/Section.h \ src/MissionManager/Section.h \
src/MissionManager/SpeedSection.h \ src/MissionManager/SpeedSection.h \
src/MissionManager/StructureScanComplexItem.h \ src/MissionManager/StructureScanComplexItem.h \
src/MissionManager/StructureScanPlanCreator.h \
src/MissionManager/SurveyComplexItem.h \ src/MissionManager/SurveyComplexItem.h \
src/MissionManager/SurveyPlanCreator.h \
src/MissionManager/TransectStyleComplexItem.h \ src/MissionManager/TransectStyleComplexItem.h \
src/MissionManager/VisualMissionItem.h \ src/MissionManager/VisualMissionItem.h \
src/PositionManager/PositionManager.h \ src/PositionManager/PositionManager.h \
...@@ -817,6 +822,8 @@ SOURCES += \ ...@@ -817,6 +822,8 @@ SOURCES += \
src/MissionManager/CameraSpec.cc \ src/MissionManager/CameraSpec.cc \
src/MissionManager/ComplexMissionItem.cc \ src/MissionManager/ComplexMissionItem.cc \
src/MissionManager/CorridorScanComplexItem.cc \ src/MissionManager/CorridorScanComplexItem.cc \
src/MissionManager/CorridorScanPlanCreator.cc \
src/MissionManager/CustomPlanCreator.cc \
src/MissionManager/FixedWingLandingComplexItem.cc \ src/MissionManager/FixedWingLandingComplexItem.cc \
src/MissionManager/GeoFenceController.cc \ src/MissionManager/GeoFenceController.cc \
src/MissionManager/GeoFenceManager.cc \ src/MissionManager/GeoFenceManager.cc \
...@@ -829,6 +836,7 @@ SOURCES += \ ...@@ -829,6 +836,7 @@ SOURCES += \
src/MissionManager/MissionManager.cc \ src/MissionManager/MissionManager.cc \
src/MissionManager/MissionSettingsItem.cc \ src/MissionManager/MissionSettingsItem.cc \
src/MissionManager/PlanElementController.cc \ src/MissionManager/PlanElementController.cc \
src/MissionManager/PlanCreator.cc \
src/MissionManager/PlanManager.cc \ src/MissionManager/PlanManager.cc \
src/MissionManager/PlanMasterController.cc \ src/MissionManager/PlanMasterController.cc \
src/MissionManager/QGCFenceCircle.cc \ src/MissionManager/QGCFenceCircle.cc \
...@@ -842,7 +850,9 @@ SOURCES += \ ...@@ -842,7 +850,9 @@ SOURCES += \
src/MissionManager/SimpleMissionItem.cc \ src/MissionManager/SimpleMissionItem.cc \
src/MissionManager/SpeedSection.cc \ src/MissionManager/SpeedSection.cc \
src/MissionManager/StructureScanComplexItem.cc \ src/MissionManager/StructureScanComplexItem.cc \
src/MissionManager/StructureScanPlanCreator.cc \
src/MissionManager/SurveyComplexItem.cc \ src/MissionManager/SurveyComplexItem.cc \
src/MissionManager/SurveyPlanCreator.cc \
src/MissionManager/TransectStyleComplexItem.cc \ src/MissionManager/TransectStyleComplexItem.cc \
src/MissionManager/VisualMissionItem.cc \ src/MissionManager/VisualMissionItem.cc \
src/PositionManager/PositionManager.cpp \ src/PositionManager/PositionManager.cpp \
......
...@@ -102,6 +102,7 @@ ...@@ -102,6 +102,7 @@
<file alias="QGroundControl/Controls/ParameterEditorDialog.qml">src/QmlControls/ParameterEditorDialog.qml</file> <file alias="QGroundControl/Controls/ParameterEditorDialog.qml">src/QmlControls/ParameterEditorDialog.qml</file>
<file alias="QGroundControl/Controls/PIDTuning.qml">src/QmlControls/PIDTuning.qml</file> <file alias="QGroundControl/Controls/PIDTuning.qml">src/QmlControls/PIDTuning.qml</file>
<file alias="QGroundControl/Controls/PlanEditToolbar.qml">src/PlanView/PlanEditToolbar.qml</file> <file alias="QGroundControl/Controls/PlanEditToolbar.qml">src/PlanView/PlanEditToolbar.qml</file>
<file alias="QGroundControl/Controls/PlanStartOverlay.qml">src/PlanView/PlanStartOverlay.qml</file>
<file alias="QGroundControl/Controls/PreFlightCheckButton.qml">src/QmlControls/PreFlightCheckButton.qml</file> <file alias="QGroundControl/Controls/PreFlightCheckButton.qml">src/QmlControls/PreFlightCheckButton.qml</file>
<file alias="QGroundControl/Controls/PreFlightCheckGroup.qml">src/QmlControls/PreFlightCheckGroup.qml</file> <file alias="QGroundControl/Controls/PreFlightCheckGroup.qml">src/QmlControls/PreFlightCheckGroup.qml</file>
<file alias="QGroundControl/Controls/PreFlightCheckModel.qml">src/QmlControls/PreFlightCheckModel.qml</file> <file alias="QGroundControl/Controls/PreFlightCheckModel.qml">src/QmlControls/PreFlightCheckModel.qml</file>
......
...@@ -51,6 +51,8 @@ CorridorScanComplexItem::CorridorScanComplexItem(Vehicle* vehicle, bool flyView, ...@@ -51,6 +51,8 @@ CorridorScanComplexItem::CorridorScanComplexItem(Vehicle* vehicle, bool flyView,
connect(&_corridorPolyline, &QGCMapPolyline::pathChanged, this, &CorridorScanComplexItem::_rebuildCorridorPolygon); connect(&_corridorPolyline, &QGCMapPolyline::pathChanged, this, &CorridorScanComplexItem::_rebuildCorridorPolygon);
connect(&_corridorWidthFact, &Fact::valueChanged, this, &CorridorScanComplexItem::_rebuildCorridorPolygon); connect(&_corridorWidthFact, &Fact::valueChanged, this, &CorridorScanComplexItem::_rebuildCorridorPolygon);
connect(&_corridorPolyline, &QGCMapPolyline::isValidChanged,this, &CorridorScanComplexItem::readyForSaveStateChanged);
if (!kmlFile.isEmpty()) { if (!kmlFile.isEmpty()) {
_corridorPolyline.loadKMLFile(kmlFile); _corridorPolyline.loadKMLFile(kmlFile);
_corridorPolyline.setDirty(false); _corridorPolyline.setDirty(false);
...@@ -490,9 +492,9 @@ void CorridorScanComplexItem::_recalcCameraShots(void) ...@@ -490,9 +492,9 @@ void CorridorScanComplexItem::_recalcCameraShots(void)
emit cameraShotsChanged(); emit cameraShotsChanged();
} }
bool CorridorScanComplexItem::readyForSave(void) const CorridorScanComplexItem::ReadyForSaveState CorridorScanComplexItem::readyForSaveState(void) const
{ {
return TransectStyleComplexItem::readyForSave(); return TransectStyleComplexItem::readyForSaveState();
} }
double CorridorScanComplexItem::timeBetweenShots(void) double CorridorScanComplexItem::timeBetweenShots(void)
......
...@@ -48,11 +48,11 @@ public: ...@@ -48,11 +48,11 @@ public:
QString mapVisualQML (void) const final { return QStringLiteral("CorridorScanMapVisual.qml"); } QString mapVisualQML (void) const final { return QStringLiteral("CorridorScanMapVisual.qml"); }
// Overrides from VisualMissionionItem // Overrides from VisualMissionionItem
QString commandDescription (void) const final { return tr("Corridor Scan"); } QString commandDescription (void) const final { return tr("Corridor Scan"); }
QString commandName (void) const final { return tr("Corridor Scan"); } QString commandName (void) const final { return tr("Corridor Scan"); }
QString abbreviation (void) const final { return tr("C"); } QString abbreviation (void) const final { return tr("C"); }
bool readyForSave (void) const; ReadyForSaveState readyForSaveState (void) const final;
double additionalTimeDelay (void) const final { return 0; } double additionalTimeDelay (void) const final { return 0; }
static const char* jsonComplexItemTypeValue; static const char* jsonComplexItemTypeValue;
......
...@@ -139,7 +139,7 @@ void CorridorScanComplexItemTest::_waitForReadyForSave(void) ...@@ -139,7 +139,7 @@ void CorridorScanComplexItemTest::_waitForReadyForSave(void)
{ {
int loops = 0; int loops = 0;
while (loops++ < 8) { while (loops++ < 8) {
if (_corridorItem->readyForSave()) { if (_corridorItem->readyForSaveState() == CorridorScanComplexItem::ReadyForSave) {
return; return;
} }
QTest::qWait(500); QTest::qWait(500);
......
/****************************************************************************
*
* (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.
*
****************************************************************************/
#include "CorridorScanPlanCreator.h"
#include "PlanMasterController.h"
#include "MissionSettingsItem.h"
CorridorScanPlanCreator::CorridorScanPlanCreator(PlanMasterController* planMasterController, QObject* parent)
: PlanCreator(planMasterController, MissionController::patternCorridorScanName, QStringLiteral("/qmlimages/PlanCreator/CorridorScanPlanCreator.png"), parent)
{
}
void CorridorScanPlanCreator::createPlan(const QGeoCoordinate& mapCenterCoord)
{
_planMasterController->removeAll();
int seqNum = _missionController->insertComplexMissionItem(
MissionController::patternCorridorScanName,
mapCenterCoord,
_missionController->visualItems()->count());
if (_planMasterController->managerVehicle()->fixedWing()) {
_missionController->insertComplexMissionItem(
MissionController::patternFWLandingName,
mapCenterCoord,
_missionController->visualItems()->count());
} else {
MissionSettingsItem* settingsItem = _missionController->visualItems()->value<MissionSettingsItem*>(0);
settingsItem->setMissionEndRTL(true);
}
_missionController->setCurrentPlanViewIndex(seqNum, false);
}
/****************************************************************************
*
* (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.
*
****************************************************************************/
#pragma once
#include "PlanCreator.h"
class CorridorScanPlanCreator : public PlanCreator
{
Q_OBJECT
public:
CorridorScanPlanCreator(PlanMasterController* planMasterController, QObject* parent = nullptr);
Q_INVOKABLE void createPlan(const QGeoCoordinate& mapCenterCoord) final;
};
/****************************************************************************
*
* (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.
*
****************************************************************************/
#include "CustomPlanCreator.h"
#include "PlanMasterController.h"
#include "MissionSettingsItem.h"
CustomPlanCreator::CustomPlanCreator(PlanMasterController* planMasterController, QObject* parent)
: PlanCreator(planMasterController, tr("Custom"), QStringLiteral("/qmlimages/PlanCreator/CustomPlanCreator.png"), parent)
{
}
void CustomPlanCreator::createPlan(const QGeoCoordinate& mapCenterCoord)
{
_planMasterController->removeAll();
int seqNum = _missionController->insertSimpleMissionItem(mapCenterCoord, _missionController->visualItems()->count());
_missionController->insertSimpleMissionItem(mapCenterCoord.atDistanceAndAzimuth(50, 135), _missionController->visualItems()->count());
_missionController->insertSimpleMissionItem(mapCenterCoord.atDistanceAndAzimuth(50, -135), _missionController->visualItems()->count());
if (_planMasterController->managerVehicle()->fixedWing()) {
_missionController->insertComplexMissionItem(
MissionController::patternFWLandingName,
mapCenterCoord,
_missionController->visualItems()->count());
} else {
MissionSettingsItem* settingsItem = _missionController->visualItems()->value<MissionSettingsItem*>(0);
settingsItem->setMissionEndRTL(true);
}
_missionController->setCurrentPlanViewIndex(seqNum, false);
}
/****************************************************************************
*
* (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.
*
****************************************************************************/
#pragma once
#include "PlanCreator.h"
class CustomPlanCreator : public PlanCreator
{
Q_OBJECT
public:
CustomPlanCreator(PlanMasterController* planMasterController, QObject* parent = nullptr);
Q_INVOKABLE void createPlan(const QGeoCoordinate& mapCenterCoord) final;
};
...@@ -100,6 +100,7 @@ FixedWingLandingComplexItem::FixedWingLandingComplexItem(Vehicle* vehicle, bool ...@@ -100,6 +100,7 @@ FixedWingLandingComplexItem::FixedWingLandingComplexItem(Vehicle* vehicle, bool
connect(this, &FixedWingLandingComplexItem::altitudesAreRelativeChanged, this, &FixedWingLandingComplexItem::coordinateHasRelativeAltitudeChanged); connect(this, &FixedWingLandingComplexItem::altitudesAreRelativeChanged, this, &FixedWingLandingComplexItem::coordinateHasRelativeAltitudeChanged);
connect(this, &FixedWingLandingComplexItem::altitudesAreRelativeChanged, this, &FixedWingLandingComplexItem::exitCoordinateHasRelativeAltitudeChanged); connect(this, &FixedWingLandingComplexItem::altitudesAreRelativeChanged, this, &FixedWingLandingComplexItem::exitCoordinateHasRelativeAltitudeChanged);
connect(this, &FixedWingLandingComplexItem::landingCoordSetChanged, 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);
...@@ -708,3 +709,8 @@ void FixedWingLandingComplexItem::_signalLastSequenceNumberChanged(void) ...@@ -708,3 +709,8 @@ void FixedWingLandingComplexItem::_signalLastSequenceNumberChanged(void)
{ {
emit lastSequenceNumberChanged(lastSequenceNumber()); emit lastSequenceNumberChanged(lastSequenceNumber());
} }
FixedWingLandingComplexItem::ReadyForSaveState FixedWingLandingComplexItem::readyForSaveState(void) const
{
return _landingCoordSet ? ReadyForSave : NotReadyForSaveData;
}
...@@ -74,7 +74,6 @@ public: ...@@ -74,7 +74,6 @@ public:
QString mapVisualQML (void) const final { return QStringLiteral("FWLandingPatternMapVisual.qml"); } QString mapVisualQML (void) const final { return QStringLiteral("FWLandingPatternMapVisual.qml"); }
// 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 false; } bool isSimpleItem (void) const final { return false; }
bool isStandaloneCoordinate (void) const final { return false; } bool isStandaloneCoordinate (void) const final { return false; }
...@@ -92,6 +91,7 @@ public: ...@@ -92,6 +91,7 @@ public:
void appendMissionItems (QList<MissionItem*>& items, QObject* missionItemParent) final; void appendMissionItems (QList<MissionItem*>& items, QObject* missionItemParent) final;
void applyNewAltitude (double newAltitude) final; void applyNewAltitude (double newAltitude) final;
double additionalTimeDelay (void) const final { return 0; } double additionalTimeDelay (void) const final { return 0; }
ReadyForSaveState readyForSaveState (void) const final;
bool coordinateHasRelativeAltitude (void) const final { return _altitudesAreRelative; } bool coordinateHasRelativeAltitude (void) const final { return _altitudesAreRelative; }
bool exitCoordinateHasRelativeAltitude (void) const final { return _altitudesAreRelative; } bool exitCoordinateHasRelativeAltitude (void) const final { return _altitudesAreRelative; }
......
...@@ -51,9 +51,10 @@ const char* MissionController::_jsonMavAutopilotKey = "MAV_AUTOPILOT"; ...@@ -51,9 +51,10 @@ const char* MissionController::_jsonMavAutopilotKey = "MAV_AUTOPILOT";
const int MissionController::_missionFileVersion = 2; const int MissionController::_missionFileVersion = 2;
const QString MissionController::patternFWLandingName (QT_TRANSLATE_NOOP("MissionController", "Fixed Wing Landing")); const QString MissionController::patternSurveyName (QT_TRANSLATE_NOOP("MissionController", "Survey"));
const QString MissionController::patternStructureScanName (QT_TRANSLATE_NOOP("MissionController", "Structure Scan")); const QString MissionController::patternFWLandingName (QT_TRANSLATE_NOOP("MissionController", "Fixed Wing Landing"));
const QString MissionController::patternCorridorScanName (QT_TRANSLATE_NOOP("MissionController", "Corridor Scan")); const QString MissionController::patternStructureScanName (QT_TRANSLATE_NOOP("MissionController", "Structure Scan"));
const QString MissionController::patternCorridorScanName (QT_TRANSLATE_NOOP("MissionController", "Corridor Scan"));
MissionController::MissionController(PlanMasterController* masterController, QObject *parent) MissionController::MissionController(PlanMasterController* masterController, QObject *parent)
: PlanElementController (masterController, parent) : PlanElementController (masterController, parent)
...@@ -64,7 +65,6 @@ MissionController::MissionController(PlanMasterController* masterController, QOb ...@@ -64,7 +65,6 @@ MissionController::MissionController(PlanMasterController* masterController, QOb
, _firstItemsFromVehicle (false) , _firstItemsFromVehicle (false)
, _itemsRequested (false) , _itemsRequested (false)
, _inRecalcSequence (false) , _inRecalcSequence (false)
, _surveyMissionItemName (tr("Survey"))
, _appSettings (qgcApp()->toolbox()->settingsManager()->appSettings()) , _appSettings (qgcApp()->toolbox()->settingsManager()->appSettings())
, _progressPct (0) , _progressPct (0)
, _currentPlanViewIndex (-1) , _currentPlanViewIndex (-1)
...@@ -417,7 +417,7 @@ int MissionController::insertComplexMissionItem(QString itemName, QGeoCoordinate ...@@ -417,7 +417,7 @@ int MissionController::insertComplexMissionItem(QString itemName, QGeoCoordinate
} }
int sequenceNumber = _nextSequenceNumber(); int sequenceNumber = _nextSequenceNumber();
if (itemName == _surveyMissionItemName) { if (itemName == patternSurveyName) {
newItem = new SurveyComplexItem(_controllerVehicle, _flyView, QString() /* kmlFile */, _visualItems /* parent */); newItem = new SurveyComplexItem(_controllerVehicle, _flyView, QString() /* kmlFile */, _visualItems /* parent */);
newItem->setCoordinate(mapCenterCoordinate); newItem->setCoordinate(mapCenterCoordinate);
} else if (itemName == patternFWLandingName) { } else if (itemName == patternFWLandingName) {
...@@ -438,7 +438,7 @@ int MissionController::insertComplexMissionItemFromKMLOrSHP(QString itemName, QS ...@@ -438,7 +438,7 @@ int MissionController::insertComplexMissionItemFromKMLOrSHP(QString itemName, QS
{ {
ComplexMissionItem* newItem; ComplexMissionItem* newItem;
if (itemName == _surveyMissionItemName) { if (itemName == patternSurveyName) {
newItem = new SurveyComplexItem(_controllerVehicle, _flyView, file, _visualItems); newItem = new SurveyComplexItem(_controllerVehicle, _flyView, file, _visualItems);
} else if (itemName == patternStructureScanName) { } else if (itemName == patternStructureScanName) {
newItem = new StructureScanComplexItem(_controllerVehicle, _flyView, file, _visualItems); newItem = new StructureScanComplexItem(_controllerVehicle, _flyView, file, _visualItems);
...@@ -987,7 +987,7 @@ bool MissionController::readyForSaveSend(void) const ...@@ -987,7 +987,7 @@ bool MissionController::readyForSaveSend(void) const
{ {
for (int i=0; i<_visualItems->count(); i++) { for (int i=0; i<_visualItems->count(); i++) {
VisualMissionItem* visualItem = qobject_cast<VisualMissionItem*>(_visualItems->get(i)); VisualMissionItem* visualItem = qobject_cast<VisualMissionItem*>(_visualItems->get(i));
if (!visualItem->readyForSave()) { if (visualItem->readyForSaveState() != VisualMissionItem::ReadyForSave) {
return false; return false;
} }
} }
...@@ -2006,7 +2006,7 @@ QStringList MissionController::complexMissionItemNames(void) const ...@@ -2006,7 +2006,7 @@ QStringList MissionController::complexMissionItemNames(void) const
{ {
QStringList complexItems; QStringList complexItems;
complexItems.append(_surveyMissionItemName); complexItems.append(patternSurveyName);
complexItems.append(patternCorridorScanName); complexItems.append(patternCorridorScanName);
if (_controllerVehicle->fixedWing()) { if (_controllerVehicle->fixedWing()) {
complexItems.append(patternFWLandingName); complexItems.append(patternFWLandingName);
...@@ -2112,7 +2112,6 @@ VisualMissionItem* MissionController::currentPlanViewItem(void) const ...@@ -2112,7 +2112,6 @@ VisualMissionItem* MissionController::currentPlanViewItem(void) const
void MissionController::setCurrentPlanViewIndex(int sequenceNumber, bool force) void MissionController::setCurrentPlanViewIndex(int sequenceNumber, bool force)
{ {
qDebug() << "setCurrentPlanViewIndex" << sequenceNumber << force << _currentPlanViewIndex;
if(_visualItems && (force || sequenceNumber != _currentPlanViewIndex)) { if(_visualItems && (force || sequenceNumber != _currentPlanViewIndex)) {
_splitSegment = nullptr; _splitSegment = nullptr;
_currentPlanViewItem = nullptr; _currentPlanViewItem = nullptr;
......
...@@ -180,7 +180,7 @@ public: ...@@ -180,7 +180,7 @@ public:
QGeoCoordinate plannedHomePosition (void) const; QGeoCoordinate plannedHomePosition (void) const;
VisualMissionItem* currentPlanViewItem (void) const; VisualMissionItem* currentPlanViewItem (void) const;
double progressPct (void) const { return _progressPct; } double progressPct (void) const { return _progressPct; }
QString surveyComplexItemName (void) const { return _surveyMissionItemName; } QString surveyComplexItemName (void) const { return patternSurveyName; }
QString corridorScanComplexItemName (void) const { return patternCorridorScanName; } QString corridorScanComplexItemName (void) const { return patternCorridorScanName; }
QString structureScanComplexItemName(void) const { return patternStructureScanName; } QString structureScanComplexItemName(void) const { return patternStructureScanName; }
...@@ -207,6 +207,7 @@ public: ...@@ -207,6 +207,7 @@ public:
static const QString patternFWLandingName; static const QString patternFWLandingName;
static const QString patternStructureScanName; static const QString patternStructureScanName;
static const QString patternCorridorScanName; static const QString patternCorridorScanName;
static const QString patternSurveyName;
signals: signals:
void visualItemsChanged (void); void visualItemsChanged (void);
...@@ -299,7 +300,6 @@ private: ...@@ -299,7 +300,6 @@ private:
bool _itemsRequested; bool _itemsRequested;
bool _inRecalcSequence; bool _inRecalcSequence;
MissionFlightStatus_t _missionFlightStatus; MissionFlightStatus_t _missionFlightStatus;
QString _surveyMissionItemName;
AppSettings* _appSettings; AppSettings* _appSettings;
double _progressPct; double _progressPct;
int _currentPlanViewIndex; int _currentPlanViewIndex;
......
/****************************************************************************
*
* (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.
*
****************************************************************************/
#include "PlanCreator.h"
#include "PlanMasterController.h"
PlanCreator::PlanCreator(PlanMasterController* planMasterController, QString name, QString imageResource, QObject* parent)
: QObject (parent)
, _planMasterController (planMasterController)
, _missionController (planMasterController->missionController())
, _name (name)
, _imageResource (imageResource)
{
}
/****************************************************************************
*
* (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.
*
****************************************************************************/
#pragma once
#include <QObject>
#include <QString>
#include "QGeoCoordinate"
class PlanMasterController;
class MissionController;
/// Base class for PlanCreator objects which are used to create a full plan in a single step.
class PlanCreator : public QObject
{
Q_OBJECT
public:
PlanCreator(PlanMasterController* planMasterController, QString name, QString imageResource, QObject* parent = nullptr);
Q_PROPERTY(QString name MEMBER _name CONSTANT)
Q_PROPERTY(QString imageResource MEMBER _imageResource CONSTANT)
Q_INVOKABLE virtual void createPlan(const QGeoCoordinate& mapCenterCoord) = 0;
protected:
PlanMasterController* _planMasterController;
MissionController* _missionController;
QString _name;
QString _imageResource;
};
...@@ -16,6 +16,10 @@ ...@@ -16,6 +16,10 @@
#include "JsonHelper.h" #include "JsonHelper.h"
#include "MissionManager.h" #include "MissionManager.h"
#include "KML.h" #include "KML.h"
#include "SurveyPlanCreator.h"
#include "StructureScanPlanCreator.h"
#include "CorridorScanPlanCreator.h"
#include "CustomPlanCreator.h"
#if defined(QGC_AIRMAP_ENABLED) #if defined(QGC_AIRMAP_ENABLED)
#include "AirspaceFlightPlanProvider.h" #include "AirspaceFlightPlanProvider.h"
#endif #endif
...@@ -50,6 +54,7 @@ PlanMasterController::PlanMasterController(QObject* parent) ...@@ -50,6 +54,7 @@ PlanMasterController::PlanMasterController(QObject* parent)
, _sendGeoFence (false) , _sendGeoFence (false)
, _sendRallyPoints (false) , _sendRallyPoints (false)
, _deleteWhenSendCompleted (false) , _deleteWhenSendCompleted (false)
, _planCreators (nullptr)
{ {
connect(&_missionController, &MissionController::dirtyChanged, this, &PlanMasterController::dirtyChanged); connect(&_missionController, &MissionController::dirtyChanged, this, &PlanMasterController::dirtyChanged);
connect(&_geoFenceController, &GeoFenceController::dirtyChanged, this, &PlanMasterController::dirtyChanged); connect(&_geoFenceController, &GeoFenceController::dirtyChanged, this, &PlanMasterController::dirtyChanged);
...@@ -79,6 +84,8 @@ void PlanMasterController::start(bool flyView) ...@@ -79,6 +84,8 @@ void PlanMasterController::start(bool flyView)
connect(_multiVehicleMgr, &MultiVehicleManager::activeVehicleChanged, this, &PlanMasterController::_activeVehicleChanged); connect(_multiVehicleMgr, &MultiVehicleManager::activeVehicleChanged, this, &PlanMasterController::_activeVehicleChanged);
_activeVehicleChanged(_multiVehicleMgr->activeVehicle()); _activeVehicleChanged(_multiVehicleMgr->activeVehicle());
_updatePlanCreatorsList();
#if defined(QGC_AIRMAP_ENABLED) #if defined(QGC_AIRMAP_ENABLED)
//-- This assumes there is one single instance of PlanMasterController in edit mode. //-- This assumes there is one single instance of PlanMasterController in edit mode.
if(!flyView) { if(!flyView) {
...@@ -115,12 +122,15 @@ void PlanMasterController::_activeVehicleChanged(Vehicle* activeVehicle) ...@@ -115,12 +122,15 @@ void PlanMasterController::_activeVehicleChanged(Vehicle* activeVehicle)
disconnect(_managerVehicle->missionManager(), &MissionManager::sendComplete, this, &PlanMasterController::_sendMissionComplete); disconnect(_managerVehicle->missionManager(), &MissionManager::sendComplete, this, &PlanMasterController::_sendMissionComplete);
disconnect(_managerVehicle->geoFenceManager(), &GeoFenceManager::sendComplete, this, &PlanMasterController::_sendGeoFenceComplete); disconnect(_managerVehicle->geoFenceManager(), &GeoFenceManager::sendComplete, this, &PlanMasterController::_sendGeoFenceComplete);
disconnect(_managerVehicle->rallyPointManager(), &RallyPointManager::sendComplete, this, &PlanMasterController::_sendRallyPointsComplete); disconnect(_managerVehicle->rallyPointManager(), &RallyPointManager::sendComplete, this, &PlanMasterController::_sendRallyPointsComplete);
disconnect(_managerVehicle, &Vehicle::vehicleTypeChanged, this, &PlanMasterController::_updatePlanCreatorsList);
} }
bool newOffline = false; bool newOffline = false;
if (activeVehicle == nullptr) { if (activeVehicle == nullptr) {
// Since there is no longer an active vehicle we use the offline controller vehicle as the manager vehicle // Since there is no longer an active vehicle we use the offline controller vehicle as the manager vehicle
_managerVehicle = _controllerVehicle; _managerVehicle = _controllerVehicle;
// The vehicle type can change on the offline vehicle. Keep the creators list in sync with that.
connect(_managerVehicle, &Vehicle::vehicleTypeChanged, this, &PlanMasterController::_updatePlanCreatorsList);
newOffline = true; newOffline = true;
} else { } else {
newOffline = false; newOffline = false;
...@@ -172,6 +182,8 @@ void PlanMasterController::_activeVehicleChanged(Vehicle* activeVehicle) ...@@ -172,6 +182,8 @@ void PlanMasterController::_activeVehicleChanged(Vehicle* activeVehicle)
_showPlanFromManagerVehicle(); _showPlanFromManagerVehicle();
} }
} }
_updatePlanCreatorsList();
} }
void PlanMasterController::loadFromVehicle(void) void PlanMasterController::loadFromVehicle(void)
...@@ -583,3 +595,26 @@ bool PlanMasterController::isEmpty(void) const ...@@ -583,3 +595,26 @@ bool PlanMasterController::isEmpty(void) const
_geoFenceController.isEmpty() && _geoFenceController.isEmpty() &&
_rallyPointController.isEmpty(); _rallyPointController.isEmpty();
} }
void PlanMasterController::_updatePlanCreatorsList(void)
{
if (!_flyView) {
if (!_planCreators) {
_planCreators = new QmlObjectListModel(this);
_planCreators->append(new SurveyPlanCreator(this, this));
_planCreators->append(new CorridorScanPlanCreator(this, this));
_planCreators->append(new CustomPlanCreator(this, this));
emit planCreatorsChanged(_planCreators);
}
if (_managerVehicle->fixedWing()) {
if (_planCreators->count() == 4) {
_planCreators->removeAt(_planCreators->count() - 2);
}
} else {
if (_planCreators->count() != 4) {
_planCreators->insert(_planCreators->count() - 1, new StructureScanPlanCreator(this, this));
}
}
}
}
...@@ -17,6 +17,7 @@ ...@@ -17,6 +17,7 @@
#include "Vehicle.h" #include "Vehicle.h"
#include "MultiVehicleManager.h" #include "MultiVehicleManager.h"
#include "QGCLoggingCategory.h" #include "QGCLoggingCategory.h"
#include "QmlObjectListModel.h"
Q_DECLARE_LOGGING_CATEGORY(PlanMasterControllerLog) Q_DECLARE_LOGGING_CATEGORY(PlanMasterControllerLog)
...@@ -29,21 +30,20 @@ public: ...@@ -29,21 +30,20 @@ public:
PlanMasterController(QObject* parent = nullptr); PlanMasterController(QObject* parent = nullptr);
~PlanMasterController(); ~PlanMasterController();
Q_PROPERTY(MissionController* missionController READ missionController CONSTANT) Q_PROPERTY(MissionController* missionController READ missionController CONSTANT)
Q_PROPERTY(GeoFenceController* geoFenceController READ geoFenceController CONSTANT) Q_PROPERTY(GeoFenceController* geoFenceController READ geoFenceController CONSTANT)
Q_PROPERTY(RallyPointController* rallyPointController READ rallyPointController CONSTANT) Q_PROPERTY(RallyPointController* rallyPointController READ rallyPointController CONSTANT)
Q_PROPERTY(Vehicle* controllerVehicle MEMBER _controllerVehicle CONSTANT)
Q_PROPERTY(Vehicle* controllerVehicle MEMBER _controllerVehicle CONSTANT) Q_PROPERTY(bool offline READ offline NOTIFY offlineChanged) ///< true: controller is not connected to an active vehicle
Q_PROPERTY(bool offline READ offline NOTIFY offlineChanged) ///< true: controller is not connected to an active vehicle Q_PROPERTY(bool containsItems READ containsItems NOTIFY containsItemsChanged) ///< true: Elemement is non-empty
Q_PROPERTY(bool containsItems READ containsItems NOTIFY containsItemsChanged) ///< true: Elemement is non-empty Q_PROPERTY(bool syncInProgress READ syncInProgress NOTIFY syncInProgressChanged) ///< true: Information is currently being saved/sent, false: no active save/send in progress
Q_PROPERTY(bool syncInProgress READ syncInProgress NOTIFY syncInProgressChanged) ///< true: Information is currently being saved/sent, false: no active save/send in progress Q_PROPERTY(bool dirty READ dirty WRITE setDirty NOTIFY dirtyChanged) ///< true: Unsaved/sent changes are present, false: no changes since last save/send
Q_PROPERTY(bool dirty READ dirty WRITE setDirty NOTIFY dirtyChanged) ///< true: Unsaved/sent changes are present, false: no changes since last save/send Q_PROPERTY(QString fileExtension READ fileExtension CONSTANT) ///< File extension for missions
Q_PROPERTY(QString fileExtension READ fileExtension CONSTANT) ///< File extension for missions Q_PROPERTY(QString kmlFileExtension READ kmlFileExtension CONSTANT)
Q_PROPERTY(QString kmlFileExtension READ kmlFileExtension CONSTANT) Q_PROPERTY(QString currentPlanFile READ currentPlanFile NOTIFY currentPlanFileChanged)
Q_PROPERTY(QString currentPlanFile READ currentPlanFile NOTIFY currentPlanFileChanged) Q_PROPERTY(QStringList loadNameFilters READ loadNameFilters CONSTANT) ///< File filter list loading plan files
///< kml file extension for missions Q_PROPERTY(QStringList saveNameFilters READ saveNameFilters CONSTANT) ///< File filter list saving plan files
Q_PROPERTY(QStringList loadNameFilters READ loadNameFilters CONSTANT) ///< File filter list loading plan files Q_PROPERTY(QmlObjectListModel* planCreators MEMBER _planCreators NOTIFY planCreatorsChanged)
Q_PROPERTY(QStringList saveNameFilters READ saveNameFilters CONSTANT) ///< File filter list saving plan files
/// Should be called immediately upon Component.onCompleted. /// Should be called immediately upon Component.onCompleted.
Q_INVOKABLE void start(bool flyView); Q_INVOKABLE void start(bool flyView);
...@@ -103,17 +103,19 @@ signals: ...@@ -103,17 +103,19 @@ signals:
void dirtyChanged (bool dirty); void dirtyChanged (bool dirty);
void offlineChanged (bool offlineEditing); void offlineChanged (bool offlineEditing);
void currentPlanFileChanged (); void currentPlanFileChanged ();
void planCreatorsChanged (QmlObjectListModel* planCreators);
private slots: private slots:
void _activeVehicleChanged(Vehicle* activeVehicle); void _activeVehicleChanged (Vehicle* activeVehicle);
void _loadMissionComplete(void); void _loadMissionComplete (void);
void _loadGeoFenceComplete(void); void _loadGeoFenceComplete (void);
void _loadRallyPointsComplete(void); void _loadRallyPointsComplete (void);
void _sendMissionComplete(void); void _sendMissionComplete (void);
void _sendGeoFenceComplete(void); void _sendGeoFenceComplete (void);
void _sendRallyPointsComplete(void); void _sendRallyPointsComplete (void);
void _updatePlanCreatorsList (void);
#if defined(QGC_AIRMAP_ENABLED) #if defined(QGC_AIRMAP_ENABLED)
void _startFlightPlanning(void); void _startFlightPlanning (void);
#endif #endif
private: private:
...@@ -133,5 +135,6 @@ private: ...@@ -133,5 +135,6 @@ private:
bool _sendRallyPoints; bool _sendRallyPoints;
QString _currentPlanFile; QString _currentPlanFile;
bool _deleteWhenSendCompleted; bool _deleteWhenSendCompleted;
QmlObjectListModel* _planCreators;
}; };
...@@ -51,7 +51,10 @@ void QGCMapPolygon::_init(void) ...@@ -51,7 +51,10 @@ void QGCMapPolygon::_init(void)
{ {
connect(&_polygonModel, &QmlObjectListModel::dirtyChanged, this, &QGCMapPolygon::_polygonModelDirtyChanged); connect(&_polygonModel, &QmlObjectListModel::dirtyChanged, this, &QGCMapPolygon::_polygonModelDirtyChanged);
connect(&_polygonModel, &QmlObjectListModel::countChanged, this, &QGCMapPolygon::_polygonModelCountChanged); connect(&_polygonModel, &QmlObjectListModel::countChanged, this, &QGCMapPolygon::_polygonModelCountChanged);
connect(this, &QGCMapPolygon::pathChanged, this, &QGCMapPolygon::_updateCenter);
connect(this, &QGCMapPolygon::pathChanged, this, &QGCMapPolygon::_updateCenter);
connect(this, &QGCMapPolygon::countChanged, this, &QGCMapPolygon::isValidChanged);
connect(this, &QGCMapPolygon::countChanged, this, &QGCMapPolygon::isEmptyChanged);
} }
const QGCMapPolygon& QGCMapPolygon::operator=(const QGCMapPolygon& other) const QGCMapPolygon& QGCMapPolygon::operator=(const QGCMapPolygon& other)
......
...@@ -36,8 +36,8 @@ public: ...@@ -36,8 +36,8 @@ public:
Q_PROPERTY(QGeoCoordinate center READ center WRITE setCenter NOTIFY centerChanged) Q_PROPERTY(QGeoCoordinate center READ center WRITE setCenter NOTIFY centerChanged)
Q_PROPERTY(bool centerDrag READ centerDrag WRITE setCenterDrag NOTIFY centerDragChanged) Q_PROPERTY(bool centerDrag READ centerDrag WRITE setCenterDrag NOTIFY centerDragChanged)
Q_PROPERTY(bool interactive READ interactive WRITE setInteractive NOTIFY interactiveChanged) Q_PROPERTY(bool interactive READ interactive WRITE setInteractive NOTIFY interactiveChanged)
Q_PROPERTY(bool isValid READ isValid NOTIFY countChanged) Q_PROPERTY(bool isValid READ isValid NOTIFY isValidChanged)
Q_PROPERTY(bool empty READ empty NOTIFY countChanged) Q_PROPERTY(bool empty READ empty NOTIFY isEmptyChanged)
Q_INVOKABLE void clear(void); Q_INVOKABLE void clear(void);
Q_INVOKABLE void appendVertex(const QGeoCoordinate& coordinate); Q_INVOKABLE void appendVertex(const QGeoCoordinate& coordinate);
...@@ -122,6 +122,8 @@ signals: ...@@ -122,6 +122,8 @@ signals:
void centerChanged (QGeoCoordinate center); void centerChanged (QGeoCoordinate center);
void centerDragChanged (bool centerDrag); void centerDragChanged (bool centerDrag);
void interactiveChanged (bool interactive); void interactiveChanged (bool interactive);
bool isValidChanged (void);
bool isEmptyChanged (void);
private slots: private slots:
void _polygonModelCountChanged(int count); void _polygonModelCountChanged(int count);
......
...@@ -516,13 +516,11 @@ Item { ...@@ -516,13 +516,11 @@ Item {
id: toolbarComponent id: toolbarComponent
PlanEditToolbar { PlanEditToolbar {
x: mapControl.centerViewport.left + _margins x: mapControl.centerViewport.left
y: mapControl.centerViewport.top + _margins y: mapControl.centerViewport.top
width: mapControl.centerViewport.width - (_margins * 2) width: mapControl.centerViewport.width
z: QGroundControl.zOrderMapItems + 2 z: QGroundControl.zOrderMapItems + 2
property real _margins: ScreenTools.defaultFontPixelWidth
QGCButton { QGCButton {
_horizontalPadding: 0 _horizontalPadding: 0
text: qsTr("Basic") text: qsTr("Basic")
......
...@@ -61,6 +61,9 @@ void QGCMapPolyline::_init(void) ...@@ -61,6 +61,9 @@ void QGCMapPolyline::_init(void)
{ {
connect(&_polylineModel, &QmlObjectListModel::dirtyChanged, this, &QGCMapPolyline::_polylineModelDirtyChanged); connect(&_polylineModel, &QmlObjectListModel::dirtyChanged, this, &QGCMapPolyline::_polylineModelDirtyChanged);
connect(&_polylineModel, &QmlObjectListModel::countChanged, this, &QGCMapPolyline::_polylineModelCountChanged); connect(&_polylineModel, &QmlObjectListModel::countChanged, this, &QGCMapPolyline::_polylineModelCountChanged);
connect(this, &QGCMapPolyline::countChanged, this, &QGCMapPolyline::isValidChanged);
connect(this, &QGCMapPolyline::countChanged, this, &QGCMapPolyline::isEmptyChanged);
} }
void QGCMapPolyline::clear(void) void QGCMapPolyline::clear(void)
......
...@@ -30,8 +30,8 @@ public: ...@@ -30,8 +30,8 @@ public:
Q_PROPERTY(QmlObjectListModel* pathModel READ qmlPathModel CONSTANT) Q_PROPERTY(QmlObjectListModel* pathModel READ qmlPathModel CONSTANT)
Q_PROPERTY(bool dirty READ dirty WRITE setDirty NOTIFY dirtyChanged) Q_PROPERTY(bool dirty READ dirty WRITE setDirty NOTIFY dirtyChanged)
Q_PROPERTY(bool interactive READ interactive WRITE setInteractive NOTIFY interactiveChanged) Q_PROPERTY(bool interactive READ interactive WRITE setInteractive NOTIFY interactiveChanged)
Q_PROPERTY(bool isValid READ isValid NOTIFY countChanged) Q_PROPERTY(bool isValid READ isValid NOTIFY isValidChanged)
Q_PROPERTY(bool empty READ empty NOTIFY countChanged) Q_PROPERTY(bool empty READ empty NOTIFY isEmptyChanged)
Q_INVOKABLE void clear(void); Q_INVOKABLE void clear(void);
Q_INVOKABLE void appendVertex(const QGeoCoordinate& coordinate); Q_INVOKABLE void appendVertex(const QGeoCoordinate& coordinate);
...@@ -104,6 +104,8 @@ signals: ...@@ -104,6 +104,8 @@ signals:
void dirtyChanged (bool dirty); void dirtyChanged (bool dirty);
void cleared (void); void cleared (void);
void interactiveChanged (bool interactive); void interactiveChanged (bool interactive);
void isValidChanged (void);
void isEmptyChanged (void);
private slots: private slots:
void _polylineModelCountChanged(int count); void _polylineModelCountChanged(int count);
......
...@@ -314,13 +314,11 @@ Item { ...@@ -314,13 +314,11 @@ Item {
id: toolbarComponent id: toolbarComponent
PlanEditToolbar { PlanEditToolbar {
x: mapControl.centerViewport.left + _margins x: mapControl.centerViewport.left
y: mapControl.centerViewport.top + _margins y: mapControl.centerViewport.top
width: mapControl.centerViewport.width - (_margins * 2) width: mapControl.centerViewport.width
z: QGroundControl.zOrderMapItems + 2 z: QGroundControl.zOrderMapItems + 2
property real _margins: ScreenTools.defaultFontPixelWidth
QGCButton { QGCButton {
_horizontalPadding: 0 _horizontalPadding: 0
text: qsTr("Basic") text: qsTr("Basic")
......
...@@ -710,25 +710,24 @@ void SimpleMissionItem::_terrainAltChanged(void) ...@@ -710,25 +710,24 @@ void SimpleMissionItem::_terrainAltChanged(void)
} }
if (qIsNaN(terrainAltitude())) { if (qIsNaN(terrainAltitude())) {
qDebug() << "1";
// Set NaNs to signal we are waiting on terrain data // Set NaNs to signal we are waiting on terrain data
_missionItem._param7Fact.setRawValue(qQNaN()); _missionItem._param7Fact.setRawValue(qQNaN());
_amslAltAboveTerrainFact.setRawValue(qQNaN()); _amslAltAboveTerrainFact.setRawValue(qQNaN());
} else { } else {
double newAboveTerrain = terrainAltitude() + _altitudeFact.rawValue().toDouble(); double newAboveTerrain = terrainAltitude() + _altitudeFact.rawValue().toDouble();
double oldAboveTerrain = _amslAltAboveTerrainFact.rawValue().toDouble(); double oldAboveTerrain = _amslAltAboveTerrainFact.rawValue().toDouble();
qDebug() << "2" << newAboveTerrain << oldAboveTerrain;
if (qIsNaN(oldAboveTerrain) || !qFuzzyCompare(newAboveTerrain, oldAboveTerrain)) { if (qIsNaN(oldAboveTerrain) || !qFuzzyCompare(newAboveTerrain, oldAboveTerrain)) {
qDebug() << "3";
_missionItem._param7Fact.setRawValue(newAboveTerrain); _missionItem._param7Fact.setRawValue(newAboveTerrain);
_amslAltAboveTerrainFact.setRawValue(newAboveTerrain); _amslAltAboveTerrainFact.setRawValue(newAboveTerrain);
} }
} }
emit readyForSaveStateChanged();
} }
bool SimpleMissionItem::readyForSave(void) const SimpleMissionItem::ReadyForSaveState SimpleMissionItem::readyForSaveState(void) const
{ {
return !specifiesAltitude() || !qIsNaN(_missionItem._param7Fact.rawValue().toDouble()); bool terrainReady = !specifiesAltitude() || !qIsNaN(_missionItem._param7Fact.rawValue().toDouble());
return terrainReady ? ReadyForSave : NotReadyForSaveTerrain;
} }
void SimpleMissionItem::_setDefaultsForCommand(void) void SimpleMissionItem::_setDefaultsForCommand(void)
......
...@@ -52,7 +52,7 @@ public: ...@@ -52,7 +52,7 @@ public:
/// This should be called before changing the command. It is needed if the command changes /// This should be called before changing the command. It is needed if the command changes
/// from an item which does not include a coordinate to an item which requires a coordinate. /// from an item which does not include a coordinate to an item which requires a coordinate.
/// It uses this value to set that new coordinate. /// It uses this value to set that new coordinate.
Q_INVOKABLE void setMapCenterHintForCommandChange(QGeoCoordinate mapCenter) { _mapCenterHint = mapCenter; }; Q_INVOKABLE void setMapCenterHintForCommandChange(QGeoCoordinate mapCenter) { _mapCenterHint = mapCenter; }
/// Scans the loaded items for additional section settings /// Scans the loaded items for additional section settings
/// @param visualItems List of all visual items /// @param visualItems List of all visual items
...@@ -118,7 +118,7 @@ public: ...@@ -118,7 +118,7 @@ public:
void appendMissionItems (QList<MissionItem*>& items, QObject* missionItemParent) final; void appendMissionItems (QList<MissionItem*>& items, QObject* missionItemParent) final;
void applyNewAltitude (double newAltitude) final; void applyNewAltitude (double newAltitude) final;
void setMissionFlightStatus (MissionController::MissionFlightStatus_t& missionFlightStatus) final; void setMissionFlightStatus (MissionController::MissionFlightStatus_t& missionFlightStatus) final;
bool readyForSave (void) const final; ReadyForSaveState readyForSaveState (void) const final;
double additionalTimeDelay (void) const final; double additionalTimeDelay (void) const final;
bool coordinateHasRelativeAltitude (void) const final { return _missionItem.relativeAltitude(); } bool coordinateHasRelativeAltitude (void) const final { return _missionItem.relativeAltitude(); }
......
...@@ -69,6 +69,7 @@ StructureScanComplexItem::StructureScanComplexItem(Vehicle* vehicle, bool flyVie ...@@ -69,6 +69,7 @@ StructureScanComplexItem::StructureScanComplexItem(Vehicle* vehicle, bool flyVie
connect(&_structurePolygon, &QGCMapPolygon::dirtyChanged, this, &StructureScanComplexItem::_polygonDirtyChanged); connect(&_structurePolygon, &QGCMapPolygon::dirtyChanged, this, &StructureScanComplexItem::_polygonDirtyChanged);
connect(&_structurePolygon, &QGCMapPolygon::pathChanged, this, &StructureScanComplexItem::_rebuildFlightPolygon); connect(&_structurePolygon, &QGCMapPolygon::pathChanged, this, &StructureScanComplexItem::_rebuildFlightPolygon);
connect(&_structurePolygon, &QGCMapPolygon::isValidChanged, this, &StructureScanComplexItem::readyForSaveStateChanged);
connect(&_structurePolygon, &QGCMapPolygon::countChanged, this, &StructureScanComplexItem::_updateLastSequenceNumber); connect(&_structurePolygon, &QGCMapPolygon::countChanged, this, &StructureScanComplexItem::_updateLastSequenceNumber);
connect(&_layersFact, &Fact::valueChanged, this, &StructureScanComplexItem::_updateLastSequenceNumber); connect(&_layersFact, &Fact::valueChanged, this, &StructureScanComplexItem::_updateLastSequenceNumber);
...@@ -617,3 +618,8 @@ void StructureScanComplexItem::_recalcScanDistance() ...@@ -617,3 +618,8 @@ void StructureScanComplexItem::_recalcScanDistance()
<< _layersFact.rawValue().toInt() << " structure height: " << surfaceHeight << _layersFact.rawValue().toInt() << " structure height: " << surfaceHeight
<< " scanDistance: " << _scanDistance; << " scanDistance: " << _scanDistance;
} }
StructureScanComplexItem::ReadyForSaveState StructureScanComplexItem::readyForSaveState(void) const
{
return _structurePolygon.isValid() ? ReadyForSave : NotReadyForSaveData;
}
...@@ -70,7 +70,6 @@ public: ...@@ -70,7 +70,6 @@ public:
QString mapVisualQML (void) const final { return QStringLiteral("StructureScanMapVisual.qml"); } QString mapVisualQML (void) const final { return QStringLiteral("StructureScanMapVisual.qml"); }
// 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 false; } bool isSimpleItem (void) const final { return false; }
bool isStandaloneCoordinate (void) const final { return false; } bool isStandaloneCoordinate (void) const final { return false; }
...@@ -89,6 +88,7 @@ public: ...@@ -89,6 +88,7 @@ public:
void setMissionFlightStatus (MissionController::MissionFlightStatus_t& missionFlightStatus) final; void setMissionFlightStatus (MissionController::MissionFlightStatus_t& missionFlightStatus) final;
void applyNewAltitude (double newAltitude) final; void applyNewAltitude (double newAltitude) final;
double additionalTimeDelay (void) const final { return 0; } double additionalTimeDelay (void) const final { return 0; }
ReadyForSaveState readyForSaveState (void) const final;
bool coordinateHasRelativeAltitude (void) const final { return true; } bool coordinateHasRelativeAltitude (void) const final { return true; }
bool exitCoordinateHasRelativeAltitude (void) const final { return true; } bool exitCoordinateHasRelativeAltitude (void) const final { return true; }
......
/****************************************************************************
*
* (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.
*
****************************************************************************/
#include "StructureScanPlanCreator.h"
#include "PlanMasterController.h"
#include "MissionSettingsItem.h"
StructureScanPlanCreator::StructureScanPlanCreator(PlanMasterController* planMasterController, QObject* parent)
: PlanCreator(planMasterController, MissionController::patternStructureScanName, QStringLiteral("/qmlimages/PlanCreator/StructureScanPlanCreator.png"), parent)
{
}
void StructureScanPlanCreator::createPlan(const QGeoCoordinate& mapCenterCoord)
{
_planMasterController->removeAll();
int seqNum = _missionController->insertComplexMissionItem(
MissionController::patternStructureScanName,
mapCenterCoord,
_missionController->visualItems()->count());
if (_planMasterController->managerVehicle()->fixedWing()) {
_missionController->insertComplexMissionItem(
MissionController::patternFWLandingName,
mapCenterCoord,
_missionController->visualItems()->count());
} else {
MissionSettingsItem* settingsItem = _missionController->visualItems()->value<MissionSettingsItem*>(0);
settingsItem->setMissionEndRTL(true);
}
_missionController->setCurrentPlanViewIndex(seqNum, false);
}
/****************************************************************************
*
* (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.
*
****************************************************************************/
#pragma once
#include "PlanCreator.h"
class StructureScanPlanCreator : public PlanCreator
{
Q_OBJECT
public:
StructureScanPlanCreator(PlanMasterController* planMasterController, QObject* parent = nullptr);
Q_INVOKABLE void createPlan(const QGeoCoordinate& mapCenterCoord) final;
};
...@@ -1496,9 +1496,9 @@ void SurveyComplexItem::applyNewAltitude(double newAltitude) ...@@ -1496,9 +1496,9 @@ void SurveyComplexItem::applyNewAltitude(double newAltitude)
_cameraCalc.setDistanceToSurfaceRelative(true); _cameraCalc.setDistanceToSurfaceRelative(true);
} }
bool SurveyComplexItem::readyForSave(void) const SurveyComplexItem::ReadyForSaveState SurveyComplexItem::readyForSaveState(void) const
{ {
return TransectStyleComplexItem::readyForSave(); return TransectStyleComplexItem::readyForSaveState();
} }
void SurveyComplexItem::appendMissionItems(QList<MissionItem*>& items, QObject* missionItemParent) void SurveyComplexItem::appendMissionItems(QList<MissionItem*>& items, QObject* missionItemParent)
......
...@@ -51,11 +51,11 @@ public: ...@@ -51,11 +51,11 @@ public:
double timeBetweenShots (void) final; double timeBetweenShots (void) final;
// Overrides from VisualMissionionItem // Overrides from VisualMissionionItem
QString commandDescription (void) const final { return tr("Survey"); } QString commandDescription (void) const final { return tr("Survey"); }
QString commandName (void) const final { return tr("Survey"); } QString commandName (void) const final { return tr("Survey"); }
QString abbreviation (void) const final { return tr("S"); } QString abbreviation (void) const final { return tr("S"); }
bool readyForSave (void) const final; ReadyForSaveState readyForSaveState (void) const final;
double additionalTimeDelay (void) const final; double additionalTimeDelay (void) const final;
// Must match json spec for GridEntryLocation // Must match json spec for GridEntryLocation
enum EntryLocation { enum EntryLocation {
......
/****************************************************************************
*
* (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.
*
****************************************************************************/
#include "SurveyPlanCreator.h"
#include "PlanMasterController.h"
#include "MissionSettingsItem.h"
SurveyPlanCreator::SurveyPlanCreator(PlanMasterController* planMasterController, QObject* parent)
: PlanCreator(planMasterController, MissionController::patternSurveyName, QStringLiteral("/qmlimages/PlanCreator/SurveyPlanCreator.png"), parent)
{
}
void SurveyPlanCreator::createPlan(const QGeoCoordinate& mapCenterCoord)
{
_planMasterController->removeAll();
int seqNum = _missionController->insertComplexMissionItem(
MissionController::patternSurveyName,
mapCenterCoord,
_missionController->visualItems()->count());
if (_planMasterController->managerVehicle()->fixedWing()) {
_missionController->insertComplexMissionItem(
MissionController::patternFWLandingName,
mapCenterCoord,
_missionController->visualItems()->count());
} else {
MissionSettingsItem* settingsItem = _missionController->visualItems()->value<MissionSettingsItem*>(0);
settingsItem->setMissionEndRTL(true);
}
_missionController->setCurrentPlanViewIndex(seqNum, false);
}
/****************************************************************************
*
* (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.
*
****************************************************************************/
#pragma once
#include "PlanCreator.h"
class SurveyPlanCreator : public PlanCreator
{
Q_OBJECT
public:
SurveyPlanCreator(PlanMasterController* planMasterController, QObject* parent = nullptr);
Q_INVOKABLE void createPlan(const QGeoCoordinate& mapCenterCoord) final;
};
...@@ -109,6 +109,8 @@ TransectStyleComplexItem::TransectStyleComplexItem(Vehicle* vehicle, bool flyVie ...@@ -109,6 +109,8 @@ TransectStyleComplexItem::TransectStyleComplexItem(Vehicle* vehicle, bool flyVie
connect(this, &TransectStyleComplexItem::followTerrainChanged, this, &TransectStyleComplexItem::_followTerrainChanged); connect(this, &TransectStyleComplexItem::followTerrainChanged, this, &TransectStyleComplexItem::_followTerrainChanged);
connect(&_surveyAreaPolygon, &QGCMapPolygon::isValidChanged, this, &TransectStyleComplexItem::readyForSaveStateChanged);
setDirty(false); setDirty(false);
} }
...@@ -417,6 +419,7 @@ void TransectStyleComplexItem::_rebuildTransects(void) ...@@ -417,6 +419,7 @@ void TransectStyleComplexItem::_rebuildTransects(void)
void TransectStyleComplexItem::_queryTransectsPathHeightInfo(void) void TransectStyleComplexItem::_queryTransectsPathHeightInfo(void)
{ {
_transectsPathHeightInfo.clear(); _transectsPathHeightInfo.clear();
emit readyForSaveStateChanged();
if (_transects.count()) { if (_transects.count()) {
// We don't actually send the query until this timer times out. This way we only send // We don't actually send the query until this timer times out. This way we only send
...@@ -461,6 +464,7 @@ void TransectStyleComplexItem::_reallyQueryTransectsPathHeightInfo(void) ...@@ -461,6 +464,7 @@ void TransectStyleComplexItem::_reallyQueryTransectsPathHeightInfo(void)
void TransectStyleComplexItem::_polyPathTerrainData(bool success, const QList<TerrainPathQuery::PathHeightInfo_t>& rgPathHeightInfo) void TransectStyleComplexItem::_polyPathTerrainData(bool success, const QList<TerrainPathQuery::PathHeightInfo_t>& rgPathHeightInfo)
{ {
_transectsPathHeightInfo.clear(); _transectsPathHeightInfo.clear();
emit readyForSaveStateChanged();
if (success) { if (success) {
// Break out into individual transects // Break out into individual transects
...@@ -473,6 +477,7 @@ void TransectStyleComplexItem::_polyPathTerrainData(bool success, const QList<Te ...@@ -473,6 +477,7 @@ void TransectStyleComplexItem::_polyPathTerrainData(bool success, const QList<Te
} }
pathHeightIndex++; // There is an extra on between each transect pathHeightIndex++; // There is an extra on between each transect
} }
emit readyForSaveStateChanged();
// Now that we have terrain data we can adjust // Now that we have terrain data we can adjust
_adjustTransectsForTerrain(); _adjustTransectsForTerrain();
...@@ -485,16 +490,19 @@ void TransectStyleComplexItem::_polyPathTerrainData(bool success, const QList<Te ...@@ -485,16 +490,19 @@ void TransectStyleComplexItem::_polyPathTerrainData(bool success, const QList<Te
_terrainPolyPathQuery = nullptr; _terrainPolyPathQuery = nullptr;
} }
bool TransectStyleComplexItem::readyForSave(void) const TransectStyleComplexItem::ReadyForSaveState TransectStyleComplexItem::readyForSaveState(void) const
{ {
// Make sure we have the terrain data we need bool terrainReady = _followTerrain ? _transectsPathHeightInfo.count() : true;
return _followTerrain ? _transectsPathHeightInfo.count() : true; bool polygonNotReady = !_surveyAreaPolygon.isValid();
return polygonNotReady ?
NotReadyForSaveData :
(terrainReady ? ReadyForSave : NotReadyForSaveTerrain);
} }
void TransectStyleComplexItem::_adjustTransectsForTerrain(void) void TransectStyleComplexItem::_adjustTransectsForTerrain(void)
{ {
if (_followTerrain) { if (_followTerrain) {
if (!readyForSave()) { if (readyForSaveState() != ReadyForSave) {
qCWarning(TransectStyleComplexItemLog) << "_adjustTransectPointsForTerrain called when terrain data not ready"; qCWarning(TransectStyleComplexItemLog) << "_adjustTransectPointsForTerrain called when terrain data not ready";
qgcApp()->showMessage(tr("INTERNAL ERROR: TransectStyleComplexItem::_adjustTransectPointsForTerrain called when terrain data not ready. Plan will be incorrect.")); qgcApp()->showMessage(tr("INTERNAL ERROR: TransectStyleComplexItem::_adjustTransectPointsForTerrain called when terrain data not ready. Plan will be incorrect."));
return; return;
......
...@@ -99,7 +99,7 @@ public: ...@@ -99,7 +99,7 @@ public:
double specifiedGimbalYaw (void) final { return std::numeric_limits<double>::quiet_NaN(); } double specifiedGimbalYaw (void) final { return std::numeric_limits<double>::quiet_NaN(); }
double specifiedGimbalPitch (void) final { return std::numeric_limits<double>::quiet_NaN(); } double specifiedGimbalPitch (void) final { return std::numeric_limits<double>::quiet_NaN(); }
void setMissionFlightStatus (MissionController::MissionFlightStatus_t& missionFlightStatus) final; void setMissionFlightStatus (MissionController::MissionFlightStatus_t& missionFlightStatus) final;
bool readyForSave (void) const override; ReadyForSaveState readyForSaveState (void) const override;
QString commandDescription (void) const override { return tr("Transect"); } QString commandDescription (void) const override { return tr("Transect"); }
QString commandName (void) const override { return tr("Transect"); } QString commandName (void) const override { return tr("Transect"); }
QString abbreviation (void) const override { return tr("T"); } QString abbreviation (void) const override { return tr("T"); }
......
...@@ -40,6 +40,13 @@ public: ...@@ -40,6 +40,13 @@ public:
const VisualMissionItem& operator=(const VisualMissionItem& other); const VisualMissionItem& operator=(const VisualMissionItem& other);
enum ReadyForSaveState {
ReadyForSave,
NotReadyForSaveTerrain,
NotReadyForSaveData,
};
Q_ENUM(ReadyForSaveState)
Q_PROPERTY(bool homePosition READ homePosition CONSTANT) ///< true: This item is being used as a home position indicator Q_PROPERTY(bool homePosition READ homePosition CONSTANT) ///< true: This item is being used as a home position indicator
Q_PROPERTY(QGeoCoordinate coordinate READ coordinate WRITE setCoordinate NOTIFY coordinateChanged) ///< This is the entry point for a waypoint line into the item. For a simple item it is also the location of the item Q_PROPERTY(QGeoCoordinate coordinate READ coordinate WRITE setCoordinate NOTIFY coordinateChanged) ///< This is the entry point for a waypoint line into the item. For a simple item it is also the location of the item
Q_PROPERTY(double terrainAltitude READ terrainAltitude NOTIFY terrainAltitudeChanged) ///< The altitude of terrain at the coordinate position, NaN if not known Q_PROPERTY(double terrainAltitude READ terrainAltitude NOTIFY terrainAltitudeChanged) ///< The altitude of terrain at the coordinate position, NaN if not known
...@@ -67,6 +74,7 @@ public: ...@@ -67,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(ReadyForSaveState readyForSaveState READ readyForSaveState NOTIFY readyForSaveStateChanged)
Q_PROPERTY(QGCGeoBoundingCube* boundingCube READ boundingCube NOTIFY boundingCubeChanged) Q_PROPERTY(QGCGeoBoundingCube* boundingCube READ boundingCube NOTIFY boundingCubeChanged)
...@@ -139,10 +147,8 @@ public: ...@@ -139,10 +147,8 @@ public:
virtual void setSequenceNumber (int sequenceNumber) = 0; virtual void setSequenceNumber (int sequenceNumber) = 0;
virtual int lastSequenceNumber (void) const = 0; virtual int lastSequenceNumber (void) const = 0;
/// Specifies whether the item has all the data it needs such that it can be saved. Currently the only /// @return Returns whether the item is ready for save and if not, why
/// case where this returns false is if it has not determined terrain values yet. virtual ReadyForSaveState readyForSaveState(void) const { return ReadyForSave; }
/// @return true: Ready to save, false: Still waiting on information
virtual bool readyForSave(void) const { return true; }
/// Save the item(s) in Json format /// Save the item(s) in Json format
/// @param missionItems Current set of mission items, new items should be appended to the end /// @param missionItems Current set of mission items, new items should be appended to the end
...@@ -198,6 +204,7 @@ signals: ...@@ -198,6 +204,7 @@ signals:
void terrainAltitudeChanged (double terrainAltitude); void terrainAltitudeChanged (double terrainAltitude);
void additionalTimeDelayChanged (void); void additionalTimeDelayChanged (void);
void boundingCubeChanged (void); void boundingCubeChanged (void);
void readyForSaveStateChanged (void);
void coordinateHasRelativeAltitudeChanged (bool coordinateHasRelativeAltitude); void coordinateHasRelativeAltitudeChanged (bool coordinateHasRelativeAltitude);
void exitCoordinateHasRelativeAltitudeChanged (bool exitCoordinateHasRelativeAltitude); void exitCoordinateHasRelativeAltitudeChanged (bool exitCoordinateHasRelativeAltitude);
......
...@@ -18,6 +18,7 @@ Rectangle { ...@@ -18,6 +18,7 @@ Rectangle {
height: editorLoader.visible ? (editorLoader.y + editorLoader.height + (_margin * 2)) : (commandPicker.y + commandPicker.height + _margin / 2) height: editorLoader.visible ? (editorLoader.y + editorLoader.height + (_margin * 2)) : (commandPicker.y + commandPicker.height + _margin / 2)
color: _currentItem ? qgcPal.missionItemEditor : qgcPal.windowShade color: _currentItem ? qgcPal.missionItemEditor : qgcPal.windowShade
radius: _radius radius: _radius
opacity: _currentItem ? 1.0 : 0.7
property var map ///< Map control property var map ///< Map control
property var masterController property var masterController
...@@ -70,16 +71,27 @@ Rectangle { ...@@ -70,16 +71,27 @@ Rectangle {
} }
} }
/* Rectangle {
Trying no sequence numbers in ui
QGCLabel {
id: label
anchors.verticalCenter: commandPicker.verticalCenter anchors.verticalCenter: commandPicker.verticalCenter
anchors.leftMargin: _margin anchors.leftMargin: _margin
anchors.left: parent.left anchors.left: parent.left
text: missionItem.homePosition ? "P" : missionItem.sequenceNumber width: readyForSaveLabel.contentHeight
color: _outerTextColor height: width
}*/ border.width: 1
border.color: "red"
color: "white"
radius: width / 2
visible: missionItem.readyForSaveState !== VisualMissionItem.ReadyForSave
QGCLabel {
id: readyForSaveLabel
anchors.centerIn: parent
//: Indicator in Plan view to show mission item is not ready for save/send
text: qsTr("?")
color: "red"
font.pointSize: ScreenTools.smallFontPointSize
}
}
QGCColoredImage { QGCColoredImage {
id: hamburger id: hamburger
......
/****************************************************************************
*
* (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.
*
****************************************************************************/
import QtQuick 2.3
import QtQuick.Controls 2.11
import QtQuick.Layouts 1.2
import QGroundControl 1.0
import QGroundControl.ScreenTools 1.0
import QGroundControl.Controls 1.0
import QGroundControl.Palette 1.0
Item {
id: _root
property var planMasterController
property var mapControl
property real _radius: ScreenTools.defaultFontPixelWidth / 2
property real _margins: ScreenTools.defaultFontPixelWidth
function _mapCenter() {
var centerPoint = Qt.point(mapControl.centerViewport.left + (mapControl.centerViewport.width / 2), mapControl.centerViewport.top + (mapControl.centerViewport.height / 2))
return mapControl.toCoordinate(centerPoint, false /* clipToViewPort */)
}
QGCPalette { id: qgcPal; colorGroupEnabled: enabled }
Rectangle {
anchors.fill: parent
radius: _radius
color: "white"
opacity: 0.75
}
// Close Icon
QGCColoredImage {
anchors.margins: ScreenTools.defaultFontPixelWidth / 2
anchors.top: parent.top
anchors.right: parent.right
width: ScreenTools.defaultFontPixelHeight
height: width
sourceSize.height: width
source: "/res/XDelete.svg"
fillMode: Image.PreserveAspectFit
mipmap: true
smooth: true
color: "black"
QGCMouseArea {
fillItem: parent
onClicked: _root.visible = false
}
}
QGCLabel {
id: title
anchors.left: parent.left
anchors.right: parent.right
horizontalAlignment: Text.AlignHCenter
text: qsTr("Create Plan")
color: "black"
}
QGCFlickable {
id: flickable
anchors.margins: _margins
anchors.top: title.bottom
anchors.bottom: parent.bottom
anchors.left: parent.left
anchors.right: parent.right
contentHeight: creatorFlow.height
contentWidth: creatorFlow.width
Flow {
id: creatorFlow
width: flickable.width
spacing: _margins
Repeater {
model: _planMasterController.planCreators
Rectangle {
id: button
width: ScreenTools.defaultFontPixelHeight * 10
height: width
color: button.pressed || button.highlighted ? qgcPal.buttonHighlight : qgcPal.button
property bool highlighted: mouseArea.containsMouse
property bool pressed: mouseArea.pressed
Image {
anchors.margins: _margins
anchors.left: parent.left
anchors.right: parent.right
anchors.verticalCenter: parent.verticalCenter
source: object.imageResource
fillMode: Image.PreserveAspectFit
mipmap: true
}
QGCLabel {
anchors.margins: _margins
anchors.bottom: parent.bottom
anchors.left: parent.left
anchors.right: parent.right
horizontalAlignment: Text.AlignHCenter
text: object.name
color: button.pressed || button.highlighted ? qgcPal.buttonHighlightText : qgcPal.buttonText
}
QGCMouseArea {
id: mouseArea
anchors.fill: parent
hoverEnabled: true
preventStealing: true
onClicked: { object.createPlan(_mapCenter()); _root.visible = false }
}
}
}
}
}
}
...@@ -32,11 +32,10 @@ Item { ...@@ -32,11 +32,10 @@ Item {
property bool planControlColapsed: false property bool planControlColapsed: false
readonly property int _decimalPlaces: 8 readonly property int _decimalPlaces: 8
readonly property real _horizontalMargin: ScreenTools.defaultFontPixelWidth * 0.5
readonly property real _margin: ScreenTools.defaultFontPixelHeight * 0.5 readonly property real _margin: ScreenTools.defaultFontPixelHeight * 0.5
readonly property real _toolsTopMargin: ScreenTools.defaultFontPixelHeight * 0.5
readonly property real _radius: ScreenTools.defaultFontPixelWidth * 0.5 readonly property real _radius: ScreenTools.defaultFontPixelWidth * 0.5
readonly property real _rightPanelWidth: Math.min(parent.width / 3, ScreenTools.defaultFontPixelWidth * 30) readonly property real _rightPanelWidth: Math.min(parent.width / 3, ScreenTools.defaultFontPixelWidth * 30)
readonly property real _toolButtonTopMargin: ScreenTools.defaultFontPixelHeight * 0.5
readonly property var _defaultVehicleCoordinate: QtPositioning.coordinate(37.803784, -122.462276) readonly property var _defaultVehicleCoordinate: QtPositioning.coordinate(37.803784, -122.462276)
readonly property bool _waypointsOnlyMode: QGroundControl.corePlugin.options.missionWaypointsOnly readonly property bool _waypointsOnlyMode: QGroundControl.corePlugin.options.missionWaypointsOnly
...@@ -405,7 +404,7 @@ Item { ...@@ -405,7 +404,7 @@ Item {
planView: true planView: true
// This is the center rectangle of the map which is not obscured by tools // This is the center rectangle of the map which is not obscured by tools
property rect centerViewport: Qt.rect(_leftToolWidth, 0, editorMap.width - _leftToolWidth - _rightToolWidth, mapScale.y) property rect centerViewport: Qt.rect(_leftToolWidth + _margin, _toolsTopMargin, editorMap.width - _leftToolWidth - _rightToolWidth - (_margin * 2), mapScale.y - _margin - _toolsTopMargin)
property real _leftToolWidth: toolStrip.x + toolStrip.width property real _leftToolWidth: toolStrip.x + toolStrip.width
property real _rightToolWidth: rightPanel.width + rightPanel.anchors.rightMargin property real _rightToolWidth: rightPanel.width + rightPanel.anchors.rightMargin
...@@ -455,6 +454,18 @@ Item { ...@@ -455,6 +454,18 @@ Item {
} }
} }
PlanStartOverlay {
id: startOverlay
x: editorMap.centerViewport.left
y: editorMap.centerViewport.top
width: editorMap.centerViewport.width
height: editorMap.centerViewport.height
z: QGroundControl.zOrderMapItems + 2
visible: !_planMasterController.containsItems
planMasterController: _planMasterController
mapControl: editorMap
}
// Add the mission item visuals to the map // Add the mission item visuals to the map
Repeater { Repeater {
model: _editingLayer == _layerMission ? _missionController.visualItems : undefined model: _editingLayer == _layerMission ? _missionController.visualItems : undefined
...@@ -571,7 +582,7 @@ Item { ...@@ -571,7 +582,7 @@ Item {
id: toolStrip id: toolStrip
anchors.leftMargin: ScreenTools.defaultFontPixelWidth * 2 anchors.leftMargin: ScreenTools.defaultFontPixelWidth * 2
anchors.left: parent.left anchors.left: parent.left
anchors.topMargin: ScreenTools.defaultFontPixelHeight * 0.5 anchors.topMargin: _toolsTopMargin
anchors.top: parent.top anchors.top: parent.top
z: QGroundControl.zOrderWidgets z: QGroundControl.zOrderWidgets
maxHeight: mapScale.y - toolStrip.y maxHeight: mapScale.y - toolStrip.y
...@@ -670,7 +681,7 @@ Item { ...@@ -670,7 +681,7 @@ Item {
// Right Panel Controls // Right Panel Controls
Item { Item {
anchors.fill: rightPanel anchors.fill: rightPanel
anchors.topMargin: _toolButtonTopMargin anchors.topMargin: _toolsTopMargin
DeadMouseArea { DeadMouseArea {
anchors.fill: parent anchors.fill: parent
} }
...@@ -917,6 +928,7 @@ Item { ...@@ -917,6 +928,7 @@ Item {
_planMasterController.removeAllFromVehicle() _planMasterController.removeAllFromVehicle()
} }
_missionController.setCurrentPlanViewIndex(0, true) _missionController.setCurrentPlanViewIndex(0, true)
startOverlay.visible = true
hideDialog() hideDialog()
} }
} }
...@@ -929,6 +941,7 @@ Item { ...@@ -929,6 +941,7 @@ Item {
function accept() { function accept() {
_planMasterController.removeAllFromVehicle() _planMasterController.removeAllFromVehicle()
_missionController.setCurrentPlanViewIndex(0, true) _missionController.setCurrentPlanViewIndex(0, true)
startOverlay.visible = true
hideDialog() hideDialog()
} }
} }
......
...@@ -467,6 +467,7 @@ QGCApplication::~QGCApplication() ...@@ -467,6 +467,7 @@ QGCApplication::~QGCApplication()
void QGCApplication::_initCommon() void QGCApplication::_initCommon()
{ {
static const char* kRefOnly = "Reference only"; static const char* kRefOnly = "Reference only";
static const char* kQGroundControl = "QGroundControl";
static const char* kQGCControllers = "QGroundControl.Controllers"; static const char* kQGCControllers = "QGroundControl.Controllers";
static const char* kQGCVehicle = "QGroundControl.Vehicle"; static const char* kQGCVehicle = "QGroundControl.Vehicle";
...@@ -478,7 +479,6 @@ void QGCApplication::_initCommon() ...@@ -478,7 +479,6 @@ void QGCApplication::_initCommon()
qmlRegisterType<QGCMapPalette> ("QGroundControl.Palette", 1, 0, "QGCMapPalette"); qmlRegisterType<QGCMapPalette> ("QGroundControl.Palette", 1, 0, "QGCMapPalette");
qmlRegisterUncreatableType<Vehicle> (kQGCVehicle, 1, 0, "Vehicle", kRefOnly); qmlRegisterUncreatableType<Vehicle> (kQGCVehicle, 1, 0, "Vehicle", kRefOnly);
qmlRegisterUncreatableType<MissionItem> (kQGCVehicle, 1, 0, "MissionItem", kRefOnly);
qmlRegisterUncreatableType<MissionManager> (kQGCVehicle, 1, 0, "MissionManager", kRefOnly); qmlRegisterUncreatableType<MissionManager> (kQGCVehicle, 1, 0, "MissionManager", kRefOnly);
qmlRegisterUncreatableType<ParameterManager> (kQGCVehicle, 1, 0, "ParameterManager", kRefOnly); qmlRegisterUncreatableType<ParameterManager> (kQGCVehicle, 1, 0, "ParameterManager", kRefOnly);
qmlRegisterUncreatableType<VehicleObjectAvoidance> (kQGCVehicle, 1, 0, "VehicleObjectAvoidance", kRefOnly); qmlRegisterUncreatableType<VehicleObjectAvoidance> (kQGCVehicle, 1, 0, "VehicleObjectAvoidance", kRefOnly);
...@@ -489,19 +489,19 @@ void QGCApplication::_initCommon() ...@@ -489,19 +489,19 @@ void QGCApplication::_initCommon()
qmlRegisterUncreatableType<MissionController> (kQGCControllers, 1, 0, "MissionController", kRefOnly); qmlRegisterUncreatableType<MissionController> (kQGCControllers, 1, 0, "MissionController", kRefOnly);
qmlRegisterUncreatableType<GeoFenceController> (kQGCControllers, 1, 0, "GeoFenceController", kRefOnly); qmlRegisterUncreatableType<GeoFenceController> (kQGCControllers, 1, 0, "GeoFenceController", kRefOnly);
qmlRegisterUncreatableType<RallyPointController> (kQGCControllers, 1, 0, "RallyPointController", kRefOnly); qmlRegisterUncreatableType<RallyPointController> (kQGCControllers, 1, 0, "RallyPointController", kRefOnly);
qmlRegisterUncreatableType<VisualMissionItem> (kQGCControllers, 1, 0, "VisualMissionItem", kRefOnly);
qmlRegisterUncreatableType<CoordinateVector> ("QGroundControl", 1, 0, "CoordinateVector", kRefOnly); qmlRegisterUncreatableType<MissionItem> (kQGroundControl, 1, 0, "MissionItem", kRefOnly);
qmlRegisterUncreatableType<QmlObjectListModel> ("QGroundControl", 1, 0, "QmlObjectListModel", kRefOnly); qmlRegisterUncreatableType<VisualMissionItem> (kQGroundControl, 1, 0, "VisualMissionItem", kRefOnly);
qmlRegisterUncreatableType<MissionCommandTree> ("QGroundControl", 1, 0, "MissionCommandTree", kRefOnly); qmlRegisterUncreatableType<CoordinateVector> (kQGroundControl, 1, 0, "CoordinateVector", kRefOnly);
qmlRegisterUncreatableType<CameraCalc> ("QGroundControl", 1, 0, "CameraCalc", kRefOnly); qmlRegisterUncreatableType<QmlObjectListModel> (kQGroundControl, 1, 0, "QmlObjectListModel", kRefOnly);
qmlRegisterUncreatableType<LogReplayLink> ("QGroundControl", 1, 0, "LogReplayLink", kRefOnly); qmlRegisterUncreatableType<MissionCommandTree> (kQGroundControl, 1, 0, "MissionCommandTree", kRefOnly);
qmlRegisterUncreatableType<CameraCalc> (kQGroundControl, 1, 0, "CameraCalc", kRefOnly);
qmlRegisterUncreatableType<LogReplayLink> (kQGroundControl, 1, 0, "LogReplayLink", kRefOnly);
qmlRegisterType<LogReplayLinkController> (kQGroundControl, 1, 0, "LogReplayLinkController");
#if defined(QGC_ENABLE_PAIRING) #if defined(QGC_ENABLE_PAIRING)
qmlRegisterUncreatableType<PairingManager> ("QGroundControl", 1, 0, "PairingManager", kRefOnly); qmlRegisterUncreatableType<PairingManager> (kQGroundControl, 1, 0, "PairingManager", kRefOnly);
#endif #endif
qmlRegisterType<LogReplayLinkController> ("QGroundControl", 1, 0, "LogReplayLinkController");
qmlRegisterUncreatableType<AutoPilotPlugin> ("QGroundControl.AutoPilotPlugin", 1, 0, "AutoPilotPlugin", kRefOnly); qmlRegisterUncreatableType<AutoPilotPlugin> ("QGroundControl.AutoPilotPlugin", 1, 0, "AutoPilotPlugin", kRefOnly);
qmlRegisterUncreatableType<VehicleComponent> ("QGroundControl.AutoPilotPlugin", 1, 0, "VehicleComponent", kRefOnly); qmlRegisterUncreatableType<VehicleComponent> ("QGroundControl.AutoPilotPlugin", 1, 0, "VehicleComponent", kRefOnly);
qmlRegisterUncreatableType<JoystickManager> ("QGroundControl.JoystickManager", 1, 0, "JoystickManager", kRefOnly); qmlRegisterUncreatableType<JoystickManager> ("QGroundControl.JoystickManager", 1, 0, "JoystickManager", kRefOnly);
......
...@@ -40,6 +40,7 @@ ParameterEditor 1.0 ParameterEditor.qml ...@@ -40,6 +40,7 @@ ParameterEditor 1.0 ParameterEditor.qml
ParameterEditorDialog 1.0 ParameterEditorDialog.qml ParameterEditorDialog 1.0 ParameterEditorDialog.qml
PIDTuning 1.0 PIDTuning.qml PIDTuning 1.0 PIDTuning.qml
PlanEditToolbar 1.0 PlanEditToolbar.qml PlanEditToolbar 1.0 PlanEditToolbar.qml
PlanStartOverlay 1.0 PlanStartOverlay.qml
PreFlightCheckButton 1.0 PreFlightCheckButton.qml PreFlightCheckButton 1.0 PreFlightCheckButton.qml
PreFlightCheckGroup 1.0 PreFlightCheckGroup.qml PreFlightCheckGroup 1.0 PreFlightCheckGroup.qml
PreFlightCheckModel 1.0 PreFlightCheckModel.qml PreFlightCheckModel 1.0 PreFlightCheckModel.qml
......
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