diff --git a/qgroundcontrol.pro b/qgroundcontrol.pro
index 74ff318dbdd9b4c5409b07bc5250c2c6e17557e1..471c6dc367a3c7aac527352ba388718703506f71 100644
--- a/qgroundcontrol.pro
+++ b/qgroundcontrol.pro
@@ -623,6 +623,7 @@ HEADERS += \
src/MissionManager/StructureScanPlanCreator.h \
src/MissionManager/SurveyComplexItem.h \
src/MissionManager/SurveyPlanCreator.h \
+ src/MissionManager/TakeoffMissionItem.h \
src/MissionManager/TransectStyleComplexItem.h \
src/MissionManager/VisualMissionItem.h \
src/PositionManager/PositionManager.h \
@@ -853,6 +854,7 @@ SOURCES += \
src/MissionManager/StructureScanPlanCreator.cc \
src/MissionManager/SurveyComplexItem.cc \
src/MissionManager/SurveyPlanCreator.cc \
+ src/MissionManager/TakeoffMissionItem.cc \
src/MissionManager/TransectStyleComplexItem.cc \
src/MissionManager/VisualMissionItem.cc \
src/PositionManager/PositionManager.cpp \
diff --git a/qgroundcontrol.qrc b/qgroundcontrol.qrc
index fb2a636586da75ea2b0e38636b630e257f343181..fa5de8820d750c470cb0ed60f455d4e204c89937 100644
--- a/qgroundcontrol.qrc
+++ b/qgroundcontrol.qrc
@@ -152,6 +152,7 @@
src/PlanView/StructureScanMapVisual.qml
src/QmlControls/SubMenuButton.qml
src/PlanView/SurveyMapVisual.qml
+ src/PlanView/TakeoffItemMapVisual.qml
src/QmlControls/ToolStrip.qml
src/PlanView/TransectStyleComplexItemStats.qml
src/PlanView/TransectStyleMapVisuals.qml
diff --git a/src/Camera/QGCCameraManager.cc b/src/Camera/QGCCameraManager.cc
index 90293e7eaa6ec14bed305c062ce9944464c5d7c2..97d3c915f5babe4cb33aa191b71fbedbfc4e2c73 100644
--- a/src/Camera/QGCCameraManager.cc
+++ b/src/Camera/QGCCameraManager.cc
@@ -203,7 +203,7 @@ QGCCameraManager::_findCamera(int id)
}
}
}
- qWarning() << "Camera component id not found:" << id;
+ //qWarning() << "Camera component id not found:" << id;
return nullptr;
}
diff --git a/src/FlightMap/MapItems/MissionItemIndicator.qml b/src/FlightMap/MapItems/MissionItemIndicator.qml
index ab2232e21083240a358a49ab7107fa1399e561c7..f3c58f3a69469720eb3e96933f5b9ac4bec93d02 100644
--- a/src/FlightMap/MapItems/MissionItemIndicator.qml
+++ b/src/FlightMap/MapItems/MissionItemIndicator.qml
@@ -32,7 +32,6 @@ MapQuickItem {
id: _label
checked: _isCurrentItem
label: missionItem ? missionItem.abbreviation : ""
- //index: missionItem ? missionItem.sequenceNumber : 0
gimbalYaw: missionItem.missionGimbalYaw
vehicleYaw: missionItem.missionVehicleYaw
showGimbalYaw: !isNaN(missionItem.missionGimbalYaw)
diff --git a/src/MissionManager/MissionController.cc b/src/MissionManager/MissionController.cc
index 2b96a09c85778dde83bc3da75a7b74c32a8708b1..c33d018cc1b03901fed2856d465e181029a01cf1 100644
--- a/src/MissionManager/MissionController.cc
+++ b/src/MissionManager/MissionController.cc
@@ -30,6 +30,7 @@
#include "PlanMasterController.h"
#include "KML.h"
#include "QGCCorePlugin.h"
+#include "TakeoffMissionItem.h"
#define UPDATE_TIMEOUT 5000 ///< How often we check for bounding box changes
@@ -139,7 +140,7 @@ void MissionController::_init(void)
{
// We start with an empty mission
_visualItems = new QmlObjectListModel(this);
- _addMissionSettings(_visualItems, false /* addToCenter */);
+ _addMissionSettings(_visualItems);
_initAllVisualItems();
}
@@ -160,6 +161,12 @@ void MissionController::_newMissionItemsAvailableFromVehicle(bool removeAllReque
// - A load from vehicle was manually requested
// - The initial automatic load from a vehicle completed and the current editor is empty
+ _deinitAllVisualItems();
+ _visualItems->deleteLater();
+ _visualItems = nullptr;
+ _settingsItem = nullptr;
+ _updateContainsItems(); // This will clear containsItems which will be set again below. This will re-pop Start Mission confirmation.
+
QmlObjectListModel* newControllerMissionItems = new QmlObjectListModel(this);
const QList& newMissionItems = _missionManager->missionItems();
qCDebug(MissionControllerLog) << "loading from vehicle: count"<< newMissionItems.count();
@@ -167,37 +174,32 @@ void MissionController::_newMissionItemsAvailableFromVehicle(bool removeAllReque
_missionItemCount = newMissionItems.count();
emit missionItemCountChanged(_missionItemCount);
- int i = 0;
- if (_controllerVehicle->firmwarePlugin()->sendHomePositionToVehicle() && newMissionItems.count() != 0) {
+ MissionSettingsItem* settingsItem = _addMissionSettings(newControllerMissionItems);
+
+ int i=0;
+ if (_controllerVehicle->firmwarePlugin()->sendHomePositionToVehicle() && newMissionItems.count() != 0 && !_flyView) {
// First item is fake home position
- _addMissionSettings(newControllerMissionItems, false /* addToCenter */);
- MissionSettingsItem* settingsItem = newControllerMissionItems->value(0);
- if (!settingsItem) {
- qWarning() << "First item is not settings item";
- return;
- }
MissionItem* fakeHomeItem = newMissionItems[0];
if (fakeHomeItem->coordinate().latitude() != 0 || fakeHomeItem->coordinate().longitude() != 0) {
- settingsItem->setCoordinate(fakeHomeItem->coordinate());
+ _settingsItem->setInitialHomePosition(fakeHomeItem->coordinate());
}
i = 1;
}
for (; i < newMissionItems.count(); i++) {
const MissionItem* missionItem = newMissionItems[i];
- newControllerMissionItems->append(new SimpleMissionItem(_controllerVehicle, _flyView, *missionItem, this));
+ SimpleMissionItem* simpleItem = new SimpleMissionItem(_controllerVehicle, _flyView, *missionItem, this);
+ if (TakeoffMissionItem::isTakeoffCommand(static_cast(simpleItem->command()))) {
+ // This needs to be a TakeoffMissionItem
+ TakeoffMissionItem* takeoffItem = new TakeoffMissionItem(*missionItem, _controllerVehicle, _flyView, settingsItem, this);
+ simpleItem->deleteLater();
+ simpleItem = takeoffItem;
+ }
+ newControllerMissionItems->append(simpleItem);
}
- _deinitAllVisualItems();
- _visualItems->deleteLater();
- _settingsItem = nullptr;
- _visualItems = nullptr;
- _updateContainsItems(); // This will clear containsItems which will be set again below. This will re-pop Start Mission confirmation.
_visualItems = newControllerMissionItems;
-
- if (!_controllerVehicle->firmwarePlugin()->sendHomePositionToVehicle() || _visualItems->count() == 0) {
- _addMissionSettings(_visualItems, !_flyView && _visualItems->count() > 0 /* addToCenter */);
- }
+ _settingsItem = settingsItem;
MissionController::_scanForAdditionalSettings(_visualItems, _controllerVehicle);
@@ -357,12 +359,44 @@ VisualMissionItem* MissionController::insertSimpleMissionItem(QGeoCoordinate coo
newItem->setCoordinate(coordinate);
newItem->setCommand(MAV_CMD_NAV_WAYPOINT);
_initVisualItem(newItem);
- if (_visualItems->count() == 1 && (_controllerVehicle->fixedWing() || _controllerVehicle->vtol() || _controllerVehicle->multiRotor())) {
- MAV_CMD takeoffCmd = _controllerVehicle->vtol() ? MAV_CMD_NAV_VTOL_TAKEOFF : MAV_CMD_NAV_TAKEOFF;
- if (_controllerVehicle->firmwarePlugin()->supportedMissionCommands().contains(takeoffCmd)) {
- newItem->setCommand(takeoffCmd);
+
+ if (newItem->specifiesAltitude()) {
+ double prevAltitude;
+ int prevAltitudeMode;
+
+ if (_findPreviousAltitude(visualItemIndex, &prevAltitude, &prevAltitudeMode)) {
+ newItem->altitude()->setRawValue(prevAltitude);
+ newItem->setAltitudeMode(static_cast(prevAltitudeMode));
}
}
+ newItem->setMissionFlightStatus(_missionFlightStatus);
+ 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
+ _recalcAllWithClickCoordinate(coordinate);
+
+ if (makeCurrentItem) {
+ setCurrentPlanViewIndex(newItem->sequenceNumber(), true);
+ }
+
+ return newItem;
+}
+
+VisualMissionItem* MissionController::insertTakeoffItem(QGeoCoordinate coordinate, int visualItemIndex, bool makeCurrentItem)
+{
+ int sequenceNumber = _nextSequenceNumber();
+ TakeoffMissionItem * newItem = new TakeoffMissionItem(_controllerVehicle->vtol() ? MAV_CMD_NAV_VTOL_TAKEOFF : MAV_CMD_NAV_TAKEOFF, _controllerVehicle, _flyView, _settingsItem, this);
+ newItem->setSequenceNumber(sequenceNumber);
+ if (!newItem->coordinate().isValid()) {
+ newItem->setCoordinate(coordinate);
+ }
+ newItem->setWizardMode(true);
+ _initVisualItem(newItem);
+
if (newItem->specifiesAltitude()) {
double prevAltitude;
int prevAltitudeMode;
@@ -552,8 +586,7 @@ void MissionController::removeMissionItem(int index)
bool rollSupported = false;
bool pitchSupported = false;
bool yawSupported = false;
- MissionSettingsItem* settingsItem = _visualItems->value(0);
- CameraSection* cameraSection = settingsItem->cameraSection();
+ CameraSection* cameraSection = _settingsItem->cameraSection();
if (_controllerVehicle->firmwarePlugin()->hasGimbal(_controllerVehicle, rollSupported, pitchSupported, yawSupported) && pitchSupported) {
if (cameraSection->specifyGimbal() && cameraSection->gimbalPitch()->rawValue().toDouble() == -90.0 && cameraSection->gimbalYaw()->rawValue().toDouble() == 0.0) {
cameraSection->setSpecifyGimbal(false);
@@ -577,7 +610,7 @@ void MissionController::removeAll(void)
_visualItems->deleteLater();
_settingsItem = nullptr;
_visualItems = new QmlObjectListModel(this);
- _addMissionSettings(_visualItems, false /* addToCenter */);
+ _addMissionSettings(_visualItems);
_initAllVisualItems();
setDirty(true);
_resetMissionFlightStatus();
@@ -625,6 +658,17 @@ bool MissionController::_loadJsonMissionFileV1(const QJsonObject& json, QmlObjec
int nextSequenceNumber = 1; // Start with 1 since home is in 0
QJsonArray itemArray(json[_jsonItemsKey].toArray());
+ MissionSettingsItem* settingsItem = _addMissionSettings(visualItems);
+ if (json.contains(_jsonPlannedHomePositionKey)) {
+ SimpleMissionItem* item = new SimpleMissionItem(_controllerVehicle, _flyView, visualItems);
+ if (item->load(json[_jsonPlannedHomePositionKey].toObject(), 0, errorString)) {
+ settingsItem->setInitialHomePositionFromUser(item->coordinate());
+ item->deleteLater();
+ } else {
+ return false;
+ }
+ }
+
qCDebug(MissionControllerLog) << "Json load: simple item loop start simpleItemCount:ComplexItemCount" << itemArray.count() << surveyItems.count();
do {
qCDebug(MissionControllerLog) << "Json load: simple item loop nextSimpleItemIndex:nextComplexItemIndex:nextSequenceNumber" << nextSimpleItemIndex << nextComplexItemIndex << nextSequenceNumber;
@@ -654,6 +698,13 @@ bool MissionController::_loadJsonMissionFileV1(const QJsonObject& json, QmlObjec
const QJsonObject itemObject = itemValue.toObject();
SimpleMissionItem* item = new SimpleMissionItem(_controllerVehicle, _flyView, visualItems);
if (item->load(itemObject, itemObject["id"].toInt(), errorString)) {
+ if (TakeoffMissionItem::isTakeoffCommand(item->mavCommand())) {
+ // This needs to be a TakeoffMissionItem
+ TakeoffMissionItem* takeoffItem = new TakeoffMissionItem(_controllerVehicle, _flyView, _settingsItem, visualItems);
+ takeoffItem->load(itemObject, itemObject["id"].toInt(), errorString);
+ item->deleteLater();
+ item = takeoffItem;
+ }
qCDebug(MissionControllerLog) << "Json load: adding simple item expectedSequence:actualSequence" << nextSequenceNumber << item->sequenceNumber();
nextSequenceNumber = item->lastSequenceNumber() + 1;
visualItems->append(item);
@@ -663,21 +714,6 @@ bool MissionController::_loadJsonMissionFileV1(const QJsonObject& json, QmlObjec
}
} while (nextSimpleItemIndex < itemArray.count() || nextComplexItemIndex < surveyItems.count());
- if (json.contains(_jsonPlannedHomePositionKey)) {
- SimpleMissionItem* item = new SimpleMissionItem(_controllerVehicle, _flyView, visualItems);
-
- if (item->load(json[_jsonPlannedHomePositionKey].toObject(), 0, errorString)) {
- MissionSettingsItem* settingsItem = new MissionSettingsItem(_controllerVehicle, _flyView, visualItems);
- settingsItem->setCoordinate(item->coordinate());
- visualItems->insert(0, settingsItem);
- item->deleteLater();
- } else {
- return false;
- }
- } else {
- _addMissionSettings(visualItems, true /* addToCenter */);
- }
-
return true;
}
@@ -719,9 +755,9 @@ bool MissionController::_loadJsonMissionFileV2(const QJsonObject& json, QmlObjec
if (!JsonHelper::loadGeoCoordinate(json[_jsonPlannedHomePositionKey], true /* altitudeRequired */, homeCoordinate, errorString)) {
return false;
}
- MissionSettingsItem* settingsItem = new MissionSettingsItem(_controllerVehicle, _flyView, visualItems);
- settingsItem->setCoordinate(homeCoordinate);
- visualItems->insert(0, settingsItem);
+ _settingsItem = new MissionSettingsItem(_controllerVehicle, _flyView, visualItems);
+ _settingsItem->setCoordinate(homeCoordinate);
+ visualItems->insert(0, _settingsItem);
qCDebug(MissionControllerLog) << "plannedHomePosition" << homeCoordinate;
// Read mission items
@@ -750,6 +786,13 @@ bool MissionController::_loadJsonMissionFileV2(const QJsonObject& json, QmlObjec
if (itemType == VisualMissionItem::jsonTypeSimpleItemValue) {
SimpleMissionItem* simpleItem = new SimpleMissionItem(_controllerVehicle, _flyView, visualItems);
if (simpleItem->load(itemObject, nextSequenceNumber, errorString)) {
+ if (TakeoffMissionItem::isTakeoffCommand(static_cast(simpleItem->command()))) {
+ // This needs to be a TakeoffMissionItem
+ TakeoffMissionItem* takeoffItem = new TakeoffMissionItem(_controllerVehicle, _flyView, _settingsItem, this);
+ takeoffItem->load(itemObject, nextSequenceNumber, errorString);
+ simpleItem->deleteLater();
+ simpleItem = takeoffItem;
+ }
qCDebug(MissionControllerLog) << "Loading simple item: nextSequenceNumber:command" << nextSequenceNumber << simpleItem->command();
nextSequenceNumber = simpleItem->lastSequenceNumber() + 1;
visualItems->append(simpleItem);
@@ -801,15 +844,6 @@ bool MissionController::_loadJsonMissionFileV2(const QJsonObject& json, QmlObjec
nextSequenceNumber = corridorItem->lastSequenceNumber() + 1;
qCDebug(MissionControllerLog) << "Corridor Scan load complete: nextSequenceNumber" << nextSequenceNumber;
visualItems->append(corridorItem);
- } else if (complexItemType == MissionSettingsItem::jsonComplexItemTypeValue) {
- qCDebug(MissionControllerLog) << "Loading Mission Settings: nextSequenceNumber" << nextSequenceNumber;
- MissionSettingsItem* settingsItem = new MissionSettingsItem(_controllerVehicle, _flyView, visualItems);
- if (!settingsItem->load(itemObject, nextSequenceNumber++, errorString)) {
- return false;
- }
- nextSequenceNumber = settingsItem->lastSequenceNumber() + 1;
- qCDebug(MissionControllerLog) << "Mission Settings load complete: nextSequenceNumber" << nextSequenceNumber;
- visualItems->append(settingsItem);
} else {
errorString = tr("Unsupported complex item type: %1").arg(complexItemType);
}
@@ -891,17 +925,21 @@ bool MissionController::_loadTextMissionFile(QTextStream& stream, QmlObjectListM
}
if (versionOk) {
- // Start with planned home in center
- _addMissionSettings(visualItems, true /* addToCenter */);
- MissionSettingsItem* settingsItem = visualItems->value(0);
+ MissionSettingsItem* settingsItem = _addMissionSettings(visualItems);
while (!stream.atEnd()) {
SimpleMissionItem* item = new SimpleMissionItem(_controllerVehicle, _flyView, visualItems);
-
if (item->load(stream)) {
if (firstItem && plannedHomePositionInFile) {
- settingsItem->setCoordinate(item->coordinate());
+ _settingsItem->setInitialHomePositionFromUser(item->coordinate());
} else {
+ if (TakeoffMissionItem::isTakeoffCommand(static_cast(item->command()))) {
+ // This needs to be a TakeoffMissionItem
+ TakeoffMissionItem* takeoffItem = new TakeoffMissionItem(_controllerVehicle, _flyView, settingsItem, visualItems);
+ takeoffItem->load(stream);
+ item->deleteLater();
+ item = takeoffItem;
+ }
visualItems->append(item);
}
firstItem = false;
@@ -939,7 +977,9 @@ void MissionController::_initLoadedVisualItems(QmlObjectListModel* loadedVisualI
_visualItems = loadedVisualItems;
if (_visualItems->count() == 0) {
- _addMissionSettings(_visualItems, true /* addToCenter */);
+ _addMissionSettings(_visualItems);
+ } else {
+ _settingsItem = _visualItems->value(0);
}
MissionController::_scanForAdditionalSettings(_visualItems, _controllerVehicle);
@@ -1631,7 +1671,7 @@ void MissionController::_setPlannedHomePositionFromFirstCoordinate(const QGeoCoo
if (firstCoordinate.isValid()) {
QGeoCoordinate plannedHomeCoord = firstCoordinate.atDistanceAndAzimuth(30, 0);
plannedHomeCoord.setAltitude(0);
- _settingsItem->setCoordinate(plannedHomeCoord);
+ _settingsItem->setInitialHomePositionFromUser(plannedHomeCoord);
}
}
@@ -1658,18 +1698,16 @@ void MissionController::_initAllVisualItems(void)
{
// Setup home position at index 0
- _settingsItem = qobject_cast(_visualItems->get(0));
if (!_settingsItem) {
- qWarning() << "First item not MissionSettingsItem";
- return;
- }
- if (!_flyView) {
- _settingsItem->setIsCurrentItem(true);
+ qWarning() << "_initAllVisualItems _settingsItem should already be set";
+ _settingsItem = qobject_cast(_visualItems->get(0));
+ if (!_settingsItem) {
+ qWarning() << "First item not MissionSettingsItem";
+ return;
+ }
}
- if (_managerVehicle->homePosition().isValid()) {
- _settingsItem->setCoordinate(_managerVehicle->homePosition());
- }
+ _settingsItem->setHomePositionFromVehicle(_managerVehicle);
connect(_settingsItem, &MissionSettingsItem::coordinateChanged, this, &MissionController::_recalcAll);
connect(_settingsItem, &MissionSettingsItem::missionEndRTLChanged, this, &MissionController::_recalcAll);
@@ -1689,6 +1727,10 @@ void MissionController::_initAllVisualItems(void)
emit containsItemsChanged(containsItems());
emit plannedHomePositionChanged(plannedHomePosition());
+ if (!_flyView) {
+ setCurrentPlanViewIndex(0, true);
+ }
+
setDirty(false);
}
@@ -1781,21 +1823,21 @@ void MissionController::managerVehicleChanged(Vehicle* managerVehicle)
connect(_managerVehicle, &Vehicle::vehicleTypeChanged, this, &MissionController::complexMissionItemNamesChanged);
if (!_masterController->offline()) {
- _managerVehicleHomePositionChanged(_managerVehicle->homePosition());
+ _managerVehicleHomePositionChanged();
}
emit complexMissionItemNamesChanged();
emit resumeMissionIndexChanged();
}
-void MissionController::_managerVehicleHomePositionChanged(const QGeoCoordinate& homePosition)
+void MissionController::_managerVehicleHomePositionChanged(void)
{
if (_visualItems) {
bool currentDirtyBit = dirty();
MissionSettingsItem* settingsItem = qobject_cast(_visualItems->get(0));
if (settingsItem) {
- settingsItem->setHomePositionFromVehicle(homePosition);
+ settingsItem->setHomePositionFromVehicle(_managerVehicle);
} else {
qWarning() << "First item is not MissionSettingsItem";
}
@@ -1861,48 +1903,55 @@ double MissionController::_normalizeLon(double lon)
}
/// Add the Mission Settings complex item to the front of the items
-void MissionController::_addMissionSettings(QmlObjectListModel* visualItems, bool addToCenter)
+MissionSettingsItem* MissionController::_addMissionSettings(QmlObjectListModel* visualItems)
{
+ qCDebug(MissionControllerLog) << "_addMissionSettings";
+
MissionSettingsItem* settingsItem = new MissionSettingsItem(_controllerVehicle, _flyView, visualItems);
+ visualItems->insert(0, settingsItem);
+ settingsItem->setHomePositionFromVehicle(_managerVehicle);
- qCDebug(MissionControllerLog) << "_addMissionSettings addToCenter" << addToCenter;
+ if (visualItems == _visualItems) {
+ _settingsItem = settingsItem;
+ }
- visualItems->insert(0, settingsItem);
+ return settingsItem;
+}
- if (addToCenter) {
- if (visualItems->count() > 1) {
- double north = 0.0;
- double south = 0.0;
- double east = 0.0;
- double west = 0.0;
- bool firstCoordSet = false;
-
- for (int i=1; icount(); i++) {
- VisualMissionItem* item = qobject_cast(visualItems->get(i));
- if (item->specifiesCoordinate()) {
- if (firstCoordSet) {
- double lat = _normalizeLat(item->coordinate().latitude());
- double lon = _normalizeLon(item->coordinate().longitude());
- north = fmax(north, lat);
- south = fmin(south, lat);
- east = fmax(east, lon);
- west = fmin(west, lon);
- } else {
- firstCoordSet = true;
- north = _normalizeLat(item->coordinate().latitude());
- south = north;
- east = _normalizeLon(item->coordinate().longitude());
- west = east;
- }
+void MissionController::_centerHomePositionOnMissionItems(QmlObjectListModel *visualItems)
+{
+ qCDebug(MissionControllerLog) << "_centerHomePositionOnMissionItems";
+
+ if (visualItems->count() > 1) {
+ double north = 0.0;
+ double south = 0.0;
+ double east = 0.0;
+ double west = 0.0;
+ bool firstCoordSet = false;
+
+ for (int i=1; icount(); i++) {
+ VisualMissionItem* item = qobject_cast(visualItems->get(i));
+ if (item->specifiesCoordinate()) {
+ if (firstCoordSet) {
+ double lat = _normalizeLat(item->coordinate().latitude());
+ double lon = _normalizeLon(item->coordinate().longitude());
+ north = fmax(north, lat);
+ south = fmin(south, lat);
+ east = fmax(east, lon);
+ west = fmin(west, lon);
+ } else {
+ firstCoordSet = true;
+ north = _normalizeLat(item->coordinate().latitude());
+ south = north;
+ east = _normalizeLon(item->coordinate().longitude());
+ west = east;
}
}
+ }
- if (firstCoordSet) {
- settingsItem->setCoordinate(QGeoCoordinate((south + ((north - south) / 2)) - 90.0, (west + ((east - west) / 2)) - 180.0, 0.0));
- }
+ if (firstCoordSet) {
+ _settingsItem->setInitialHomePositionFromUser(QGeoCoordinate((south + ((north - south) / 2)) - 90.0, (west + ((east - west) / 2)) - 180.0, 0.0));
}
- } else if (_managerVehicle->homePosition().isValid()) {
- settingsItem->setCoordinate(_managerVehicle->homePosition());
}
}
@@ -2133,13 +2182,28 @@ VisualMissionItem* MissionController::currentPlanViewItem(void) const
void MissionController::setCurrentPlanViewIndex(int sequenceNumber, bool force)
{
- if(_visualItems && (force || sequenceNumber != _currentPlanViewIndex)) {
+ if (_visualItems && (force || sequenceNumber != _currentPlanViewIndex)) {
_splitSegment = nullptr;
_currentPlanViewItem = nullptr;
_currentPlanViewIndex = -1;
+ _isInsertTakeoffValid = true;
+
for (int i = 0; i < _visualItems->count(); i++) {
VisualMissionItem* pVI = qobject_cast(_visualItems->get(i));
- if (pVI && pVI->sequenceNumber() == sequenceNumber) {
+
+ if (sequenceNumber != 0 && pVI->sequenceNumber() <= sequenceNumber) {
+ if (pVI->specifiesCoordinate() && !pVI->isStandaloneCoordinate()) {
+ // Coordinate based flight commands prior to where the takeoff would be inserted
+ _isInsertTakeoffValid = false;
+ }
+ }
+
+ if (qobject_cast(pVI)) {
+ // Already contains a takeoff command
+ _isInsertTakeoffValid = false;
+ }
+
+ if (pVI->sequenceNumber() == sequenceNumber) {
pVI->setIsCurrentItem(true);
_currentPlanViewItem = pVI;
_currentPlanViewIndex = sequenceNumber;
@@ -2160,9 +2224,11 @@ void MissionController::setCurrentPlanViewIndex(int sequenceNumber, bool force)
pVI->setIsCurrentItem(false);
}
}
+
emit currentPlanViewIndexChanged();
emit currentPlanViewItemChanged();
emit splitSegmentChanged();
+ emit isInsertTakeoffValidChanged();
}
}
diff --git a/src/MissionManager/MissionController.h b/src/MissionManager/MissionController.h
index 39eb1f50e50ec2b46a58139abcccb3a0728778f2..0c9f073352bb9ba8e205fc4913b62cc29931bacd 100644
--- a/src/MissionManager/MissionController.h
+++ b/src/MissionManager/MissionController.h
@@ -7,9 +7,7 @@
*
****************************************************************************/
-
-#ifndef MissionController_H
-#define MissionController_H
+#pragma once
#include "PlanElementController.h"
#include "QmlObjectListModel.h"
@@ -28,6 +26,7 @@ class AppSettings;
class MissionManager;
class SimpleMissionItem;
class ComplexMissionItem;
+class MissionSettingsItem;
class QDomDocument;
Q_DECLARE_LOGGING_CATEGORY(MissionControllerLog)
@@ -67,38 +66,33 @@ public:
int batteriesRequired; ///< -1 for not supported
} MissionFlightStatus_t;
- Q_PROPERTY(QmlObjectListModel* visualItems READ visualItems NOTIFY visualItemsChanged)
- Q_PROPERTY(QmlObjectListModel* waypointLines READ waypointLines CONSTANT) ///< Used by Plan view only for interactive editing
- Q_PROPERTY(QVariantList waypointPath READ waypointPath NOTIFY waypointPathChanged) ///< Used by Fly view only for static display
- Q_PROPERTY(QmlObjectListModel* directionArrows READ directionArrows CONSTANT)
- Q_PROPERTY(QStringList complexMissionItemNames READ complexMissionItemNames NOTIFY complexMissionItemNamesChanged)
- Q_PROPERTY(QGeoCoordinate plannedHomePosition READ plannedHomePosition NOTIFY plannedHomePositionChanged)
- Q_PROPERTY(CoordinateVector* splitSegment MEMBER _splitSegment NOTIFY splitSegmentChanged) ///< Segment which show show + split ui element
-
- Q_PROPERTY(double progressPct READ progressPct NOTIFY progressPctChanged)
-
- Q_PROPERTY(int missionItemCount READ missionItemCount NOTIFY missionItemCountChanged) ///< True mission item command count (only valid in Fly View)
- Q_PROPERTY(int currentMissionIndex READ currentMissionIndex NOTIFY currentMissionIndexChanged)
- Q_PROPERTY(int resumeMissionIndex READ resumeMissionIndex NOTIFY resumeMissionIndexChanged) ///< Returns the item index two which a mission should be resumed. -1 indicates resume mission not available.
-
- Q_PROPERTY(int currentPlanViewIndex READ currentPlanViewIndex NOTIFY currentPlanViewIndexChanged)
- Q_PROPERTY(VisualMissionItem* currentPlanViewItem READ currentPlanViewItem NOTIFY currentPlanViewItemChanged)
-
- Q_PROPERTY(double missionDistance READ missionDistance NOTIFY missionDistanceChanged)
- Q_PROPERTY(double missionTime READ missionTime NOTIFY missionTimeChanged)
- Q_PROPERTY(double missionHoverDistance READ missionHoverDistance NOTIFY missionHoverDistanceChanged)
- Q_PROPERTY(double missionCruiseDistance READ missionCruiseDistance NOTIFY missionCruiseDistanceChanged)
- Q_PROPERTY(double missionHoverTime READ missionHoverTime NOTIFY missionHoverTimeChanged)
- Q_PROPERTY(double missionCruiseTime READ missionCruiseTime NOTIFY missionCruiseTimeChanged)
- Q_PROPERTY(double missionMaxTelemetry READ missionMaxTelemetry NOTIFY missionMaxTelemetryChanged)
-
- Q_PROPERTY(int batteryChangePoint READ batteryChangePoint NOTIFY batteryChangePointChanged)
- Q_PROPERTY(int batteriesRequired READ batteriesRequired NOTIFY batteriesRequiredChanged)
- Q_PROPERTY(QGCGeoBoundingCube* travelBoundingCube READ travelBoundingCube NOTIFY missionBoundingCubeChanged)
-
+ Q_PROPERTY(QmlObjectListModel* visualItems READ visualItems NOTIFY visualItemsChanged)
+ Q_PROPERTY(QmlObjectListModel* waypointLines READ waypointLines CONSTANT) ///< Used by Plan view only for interactive editing
+ Q_PROPERTY(QVariantList waypointPath READ waypointPath NOTIFY waypointPathChanged) ///< Used by Fly view only for static display
+ Q_PROPERTY(QmlObjectListModel* directionArrows READ directionArrows CONSTANT)
+ Q_PROPERTY(QStringList complexMissionItemNames READ complexMissionItemNames NOTIFY complexMissionItemNamesChanged)
+ Q_PROPERTY(QGeoCoordinate plannedHomePosition READ plannedHomePosition NOTIFY plannedHomePositionChanged)
+ Q_PROPERTY(CoordinateVector* splitSegment MEMBER _splitSegment NOTIFY splitSegmentChanged) ///< Segment which show show + split ui element
+ Q_PROPERTY(double progressPct READ progressPct NOTIFY progressPctChanged)
+ Q_PROPERTY(int missionItemCount READ missionItemCount NOTIFY missionItemCountChanged) ///< True mission item command count (only valid in Fly View)
+ Q_PROPERTY(int currentMissionIndex READ currentMissionIndex NOTIFY currentMissionIndexChanged)
+ Q_PROPERTY(int resumeMissionIndex READ resumeMissionIndex NOTIFY resumeMissionIndexChanged) ///< Returns the item index two which a mission should be resumed. -1 indicates resume mission not available.
+ Q_PROPERTY(int currentPlanViewIndex READ currentPlanViewIndex NOTIFY currentPlanViewIndexChanged)
+ Q_PROPERTY(VisualMissionItem* currentPlanViewItem READ currentPlanViewItem NOTIFY currentPlanViewItemChanged)
+ Q_PROPERTY(double missionDistance READ missionDistance NOTIFY missionDistanceChanged)
+ Q_PROPERTY(double missionTime READ missionTime NOTIFY missionTimeChanged)
+ Q_PROPERTY(double missionHoverDistance READ missionHoverDistance NOTIFY missionHoverDistanceChanged)
+ Q_PROPERTY(double missionCruiseDistance READ missionCruiseDistance NOTIFY missionCruiseDistanceChanged)
+ Q_PROPERTY(double missionHoverTime READ missionHoverTime NOTIFY missionHoverTimeChanged)
+ Q_PROPERTY(double missionCruiseTime READ missionCruiseTime NOTIFY missionCruiseTimeChanged)
+ Q_PROPERTY(double missionMaxTelemetry READ missionMaxTelemetry NOTIFY missionMaxTelemetryChanged)
+ Q_PROPERTY(int batteryChangePoint READ batteryChangePoint NOTIFY batteryChangePointChanged)
+ Q_PROPERTY(int batteriesRequired READ batteriesRequired NOTIFY batteriesRequiredChanged)
+ Q_PROPERTY(QGCGeoBoundingCube* travelBoundingCube READ travelBoundingCube NOTIFY missionBoundingCubeChanged)
Q_PROPERTY(QString surveyComplexItemName READ surveyComplexItemName CONSTANT)
Q_PROPERTY(QString corridorScanComplexItemName READ corridorScanComplexItemName CONSTANT)
Q_PROPERTY(QString structureScanComplexItemName READ structureScanComplexItemName CONSTANT)
+ Q_PROPERTY(bool isInsertTakeoffValid MEMBER _isInsertTakeoffValid NOTIFY isInsertTakeoffValidChanged) ///< true: Takeoff tool should be enabled
Q_INVOKABLE void removeMissionItem(int index);
@@ -109,6 +103,13 @@ public:
/// @return Newly created item
Q_INVOKABLE VisualMissionItem* insertSimpleMissionItem(QGeoCoordinate coordinate, int visualItemIndex, bool makeCurrentItem = false);
+ /// Add a new takeoff item to the list
+ /// @param coordinate: Coordinate for item
+ /// @param visualItemIndex: index to insert at, -1 for end of list
+ /// @param makeCurrentItem: true: Make this item the current item
+ /// @return Newly created item
+ Q_INVOKABLE VisualMissionItem* insertTakeoffItem(QGeoCoordinate coordinate, int visualItemIndex, bool makeCurrentItem = false);
+
/// Add a new ROI mission item to the list
/// @param coordinate: Coordinate for item
/// @param visualItemIndex: index to insert at, -1 for end of list
@@ -191,6 +192,7 @@ public:
QString surveyComplexItemName (void) const { return patternSurveyName; }
QString corridorScanComplexItemName (void) const { return patternCorridorScanName; }
QString structureScanComplexItemName(void) const { return patternStructureScanName; }
+ bool isInsertTakeoffValid (void) const;
int missionItemCount (void) const { return _missionItemCount; }
int currentMissionIndex (void) const;
@@ -242,11 +244,12 @@ signals:
void currentPlanViewItemChanged (void);
void missionBoundingCubeChanged (void);
void missionItemCountChanged (int missionItemCount);
+ void isInsertTakeoffValidChanged (void);
private slots:
void _newMissionItemsAvailableFromVehicle(bool removeAllRequested);
void _itemCommandChanged(void);
- void _managerVehicleHomePositionChanged(const QGeoCoordinate& homePosition);
+ void _managerVehicleHomePositionChanged(void);
void _inProgressChanged(bool inProgress);
void _currentMissionIndexChanged(int sequenceNumber);
void _recalcWaypointLines(void);
@@ -275,7 +278,8 @@ private:
bool _findPreviousAltitude(int newIndex, double* prevAltitude, int* prevAltitudeMode);
static double _normalizeLat(double lat);
static double _normalizeLon(double lon);
- void _addMissionSettings(QmlObjectListModel* visualItems, bool addToCenter);
+ MissionSettingsItem* _addMissionSettings(QmlObjectListModel* visualItems);
+ void _centerHomePositionOnMissionItems(QmlObjectListModel* visualItems);
bool _loadJsonMissionFile(const QByteArray& bytes, QmlObjectListModel* visualItems, QString& errorString);
bool _loadJsonMissionFileV1(const QJsonObject& json, QmlObjectListModel* visualItems, QString& errorString);
bool _loadJsonMissionFileV2(const QJsonObject& json, QmlObjectListModel* visualItems, QString& errorString);
@@ -316,6 +320,7 @@ private:
QGCGeoBoundingCube _travelBoundingCube;
QGeoCoordinate _takeoffCoordinate;
CoordinateVector* _splitSegment;
+ bool _isInsertTakeoffValid = true;
static const char* _settingsGroup;
@@ -335,5 +340,3 @@ private:
static const int _missionFileVersion;
};
-
-#endif
diff --git a/src/MissionManager/MissionControllerTest.cc b/src/MissionManager/MissionControllerTest.cc
index effced1e7205cc95445fca08cdb2a483815ffc32..0540fa90ffef6895a0c9b1fedad65c217fb0069b 100644
--- a/src/MissionManager/MissionControllerTest.cc
+++ b/src/MissionManager/MissionControllerTest.cc
@@ -111,51 +111,6 @@ void MissionControllerTest::_testEmptyVehicleAPM(void)
_testEmptyVehicleWorker(MAV_AUTOPILOT_ARDUPILOTMEGA);
}
-void MissionControllerTest::_testAddWaypointWorker(MAV_AUTOPILOT firmwareType)
-{
- _initForFirmwareType(firmwareType);
-
- QGeoCoordinate coordinate(37.803784, -122.462276);
-
- _missionController->insertSimpleMissionItem(coordinate, _missionController->visualItems()->count());
-
- QmlObjectListModel* visualItems = _missionController->visualItems();
- QVERIFY(visualItems);
-
- QCOMPARE(visualItems->count(), 2);
-
- MissionSettingsItem* settingsItem = visualItems->value(0);
- SimpleMissionItem* simpleItem = visualItems->value(1);
- QVERIFY(settingsItem);
- QVERIFY(simpleItem);
-
- QCOMPARE((MAV_CMD)simpleItem->command(), MAV_CMD_NAV_TAKEOFF);
- QCOMPARE(simpleItem->childItems()->count(), 0);
-
- // Planned home position should always be set after first item
- QVERIFY(settingsItem->coordinate().isValid());
-
- // ArduPilot takeoff command has no coordinate, so should be child item
- QCOMPARE(settingsItem->childItems()->count(), firmwareType == MAV_AUTOPILOT_ARDUPILOTMEGA ? 1 : 0);
-
- // Check waypoint line from home to takeoff
- int expectedLineCount = firmwareType == MAV_AUTOPILOT_ARDUPILOTMEGA ? 0 : 1;
- QmlObjectListModel* waypointLines = _missionController->waypointLines();
- QVERIFY(waypointLines);
- QCOMPARE(waypointLines->count(), expectedLineCount);
-}
-
-void MissionControllerTest::_testAddWayppointAPM(void)
-{
- _testAddWaypointWorker(MAV_AUTOPILOT_ARDUPILOTMEGA);
-}
-
-
-void MissionControllerTest::_testAddWayppointPX4(void)
-{
- _testAddWaypointWorker(MAV_AUTOPILOT_PX4);
-}
-
#if 0
void MissionControllerTest::_testOfflineToOnlineWorker(MAV_AUTOPILOT firmwareType)
{
diff --git a/src/MissionManager/MissionControllerTest.h b/src/MissionManager/MissionControllerTest.h
index 88a4ec6e034a87a334591d3c04ce3c641093d3be..fda248dffe0ca71be4adc99aeb3e2bd3026c0997 100644
--- a/src/MissionManager/MissionControllerTest.h
+++ b/src/MissionManager/MissionControllerTest.h
@@ -36,8 +36,6 @@ private slots:
void _testLoadJsonSectionAvailable(void);
void _testEmptyVehicleAPM(void);
void _testEmptyVehiclePX4(void);
- void _testAddWayppointAPM(void);
- void _testAddWayppointPX4(void);
private:
#if 0
diff --git a/src/MissionManager/MissionSettingsItem.cc b/src/MissionManager/MissionSettingsItem.cc
index e816d9de645f813b971770ab845e2d8a15ef285a..fec7b71839d24f4a9572672f5d6afdc7d4b91088 100644
--- a/src/MissionManager/MissionSettingsItem.cc
+++ b/src/MissionManager/MissionSettingsItem.cc
@@ -21,8 +21,6 @@
QGC_LOGGING_CATEGORY(MissionSettingsComplexItemLog, "MissionSettingsComplexItemLog")
-const char* MissionSettingsItem::jsonComplexItemTypeValue = "MissionSettings";
-
const char* MissionSettingsItem::_plannedHomePositionAltitudeName = "PlannedHomePositionAltitude";
QMap MissionSettingsItem::_metaDataMap;
@@ -30,12 +28,8 @@ QMap MissionSettingsItem::_metaDataMap;
MissionSettingsItem::MissionSettingsItem(Vehicle* vehicle, bool flyView, QObject* parent)
: ComplexMissionItem (vehicle, flyView, parent)
, _plannedHomePositionAltitudeFact (0, _plannedHomePositionAltitudeName, FactMetaData::valueTypeDouble)
- , _plannedHomePositionFromVehicle (false)
- , _missionEndRTL (false)
, _cameraSection (vehicle)
, _speedSection (vehicle)
- , _sequenceNumber (0)
- , _dirty (false)
{
_editorQml = "qrc:/qml/MissionSettingsEditor.qml";
@@ -95,7 +89,7 @@ void MissionSettingsItem::save(QJsonArray& missionItems)
appendMissionItems(items, this);
- // First item show be planned home position, we are not responsible for save/load
+ // First item should be planned home position, we are not responsible for save/load
// Remaining items we just output as is
for (int i=1; ihomePosition();
// ArduPilot tends to send crap home positions at initial vehicle boot, discard them
if (coordinate.isValid() && (coordinate.latitude() != 0 || coordinate.longitude() != 0)) {
- _plannedHomePositionCoordinate = coordinate;
- emit coordinateChanged(coordinate);
- emit exitCoordinateChanged(coordinate);
- _plannedHomePositionAltitudeFact.setRawValue(coordinate.altitude());
+ _plannedHomePositionFromVehicle = true;
+ _setCoordinateWorker(coordinate);
}
}
}
+void MissionSettingsItem::setInitialHomePosition(const QGeoCoordinate& coordinate)
+{
+ _plannedHomePositionMovedByUser = false;
+ _plannedHomePositionFromVehicle = false;
+ _setCoordinateWorker(coordinate);
+}
+
+void MissionSettingsItem::setInitialHomePositionFromUser(const QGeoCoordinate& coordinate)
+{
+ _plannedHomePositionMovedByUser = true;
+ _plannedHomePositionFromVehicle = false;
+ _setCoordinateWorker(coordinate);
+}
+
+
+void MissionSettingsItem::setCoordinate(const QGeoCoordinate& coordinate)
+{
+ if (coordinate != this->coordinate()) {
+ // The user is moving the planned home position manually. Stop tracking vehicle home position.
+ _plannedHomePositionMovedByUser = true;
+ _plannedHomePositionFromVehicle = false;
+ _setCoordinateWorker(coordinate);
+ }
+}
+
void MissionSettingsItem::_setDirtyAndUpdateLastSequenceNumber(void)
{
emit lastSequenceNumberChanged(lastSequenceNumber());
@@ -301,5 +324,5 @@ void MissionSettingsItem::_setHomeAltFromTerrain(double terrainAltitude)
QString MissionSettingsItem::abbreviation(void) const
{
- return _flyView ? tr("H") : tr("Planned Home");
+ return _flyView ? tr("H") : tr("Launch");
}
diff --git a/src/MissionManager/MissionSettingsItem.h b/src/MissionManager/MissionSettingsItem.h
index 935cade386139205839ffd1b49258fa32ccf6e31..9c576d5b15ebc64fbb7ea1293789d73c675f919c 100644
--- a/src/MissionManager/MissionSettingsItem.h
+++ b/src/MissionManager/MissionSettingsItem.h
@@ -48,8 +48,14 @@ public:
/// @return true: Mission end action was added
bool addMissionEndAction(QList& items, int seqNum, QObject* missionItemParent);
- /// Called to updaet home position coordinate when it comes from a connected vehicle
- void setHomePositionFromVehicle(const QGeoCoordinate& coordinate);
+ /// Called to update home position coordinate when it comes from a connected vehicle
+ void setHomePositionFromVehicle(Vehicle* vehicle);
+
+ // Called to set the initial home position. Vehicle can still update home position after this.
+ void setInitialHomePosition(const QGeoCoordinate& coordinate);
+
+ // Called to set the initial home position specified by user. Vehicle will no longer affect home position.
+ void setInitialHomePositionFromUser(const QGeoCoordinate& coordinate);
// Overrides from ComplexMissionItem
@@ -75,7 +81,7 @@ public:
double specifiedGimbalYaw (void) final;
double specifiedGimbalPitch (void) final;
void appendMissionItems (QList& items, QObject* missionItemParent) final;
- void applyNewAltitude (double newAltitude) final { Q_UNUSED(newAltitude); /* no action */ }
+ void applyNewAltitude (double /*newAltitude*/) final { /* no action */ }
double specifiedFlightSpeed (void) final;
double additionalTimeDelay (void) const final { return 0; }
@@ -84,12 +90,10 @@ public:
bool exitCoordinateSameAsEntry (void) const final { return true; }
void setDirty (bool dirty) final;
- void setCoordinate (const QGeoCoordinate& coordinate) final;
+ void setCoordinate (const QGeoCoordinate& coordinate) final; // Should only be called if the end user is moving
void setSequenceNumber (int sequenceNumber) final;
void save (QJsonArray& missionItems) final;
- static const char* jsonComplexItemTypeValue;
-
signals:
void specifyMissionFlightSpeedChanged (bool specifyMissionFlightSpeed);
void missionEndRTLChanged (bool missionEndRTL);
@@ -100,16 +104,17 @@ private slots:
void _sectionDirtyChanged (bool dirty);
void _updateAltitudeInCoordinate (QVariant value);
void _setHomeAltFromTerrain (double terrainAltitude);
+ void _setCoordinateWorker (const QGeoCoordinate& coordinate);
private:
QGeoCoordinate _plannedHomePositionCoordinate; // Does not include altitude
Fact _plannedHomePositionAltitudeFact;
- bool _plannedHomePositionFromVehicle;
- bool _missionEndRTL;
+ int _sequenceNumber = 0;
+ bool _plannedHomePositionFromVehicle = false;
+ bool _plannedHomePositionMovedByUser = false;
+ bool _missionEndRTL = false;
CameraSection _cameraSection;
SpeedSection _speedSection;
- int _sequenceNumber;
- bool _dirty;
static QMap _metaDataMap;
diff --git a/src/MissionManager/SimpleMissionItem.cc b/src/MissionManager/SimpleMissionItem.cc
index d66a3ce621233675fc8dd505d2bc46080ccf4108..a276bc7f663bd73b6e7cf95bb0ba9407531c8b9b 100644
--- a/src/MissionManager/SimpleMissionItem.cc
+++ b/src/MissionManager/SimpleMissionItem.cc
@@ -146,37 +146,6 @@ SimpleMissionItem::SimpleMissionItem(Vehicle* vehicle, bool flyView, const Missi
setDirty(false);
}
-SimpleMissionItem::SimpleMissionItem(const SimpleMissionItem& other, bool flyView, QObject* parent)
- : VisualMissionItem (other, flyView, parent)
- , _missionItem (other._vehicle)
- , _rawEdit (false)
- , _dirty (false)
- , _ignoreDirtyChangeSignals (false)
- , _speedSection (nullptr)
- , _cameraSection (nullptr)
- , _commandTree (qgcApp()->toolbox()->missionCommandTree())
- , _supportedCommandFact (0, "Command:", FactMetaData::valueTypeUint32)
- , _altitudeMode (other._altitudeMode)
- , _altitudeFact (0, "Altitude", FactMetaData::valueTypeDouble)
- , _amslAltAboveTerrainFact (qQNaN(), "Alt above terrain", FactMetaData::valueTypeDouble)
- , _param1MetaData (FactMetaData::valueTypeDouble)
- , _param2MetaData (FactMetaData::valueTypeDouble)
- , _param3MetaData (FactMetaData::valueTypeDouble)
- , _param4MetaData (FactMetaData::valueTypeDouble)
- , _syncingHeadingDegreesAndParam4 (false)
-{
- _editorQml = QStringLiteral("qrc:/qml/SimpleItemEditor.qml");
-
- _altitudeFact.setRawValue(other._altitudeFact.rawValue());
- _amslAltAboveTerrainFact.setRawValue(other._amslAltAboveTerrainFact.rawValue());
-
- _setupMetaData();
- _connectSignals();
- _updateOptionalSections();
- _rebuildFacts();
- setDirty(false);
-}
-
void SimpleMissionItem::_connectSignals(void)
{
// Connect to change signals to track dirty state
diff --git a/src/MissionManager/SimpleMissionItem.h b/src/MissionManager/SimpleMissionItem.h
index c839e4c50665a9e642e81e888060a5e42f820e81..4c2c544b43bfec77d3e9b90f6eb20650e77d823b 100644
--- a/src/MissionManager/SimpleMissionItem.h
+++ b/src/MissionManager/SimpleMissionItem.h
@@ -26,7 +26,7 @@ class SimpleMissionItem : public VisualMissionItem
public:
SimpleMissionItem(Vehicle* vehicle, bool flyView, QObject* parent);
SimpleMissionItem(Vehicle* vehicle, bool flyView, const MissionItem& missionItem, QObject* parent);
- SimpleMissionItem(const SimpleMissionItem& other, bool flyView, QObject* parent);
+ //SimpleMissionItem(const SimpleMissionItem& other, bool flyView, QObject* parent);
~SimpleMissionItem();
@@ -64,7 +64,8 @@ public:
// Property accesors
QString category (void) const;
- int command(void) const { return _missionItem._commandFact.cookedValue().toInt(); }
+ int command (void) const { return _missionItem._commandFact.cookedValue().toInt(); }
+ MAV_CMD mavCommand (void) const { return static_cast(command()); }
bool friendlyEditAllowed (void) const;
bool rawEdit (void) const;
bool specifiesAltitude (void) const;
@@ -92,14 +93,14 @@ public:
void setAzimuth (double azimuth);
void setDistance (double distance);
- bool load(QTextStream &loadStream);
- bool load(const QJsonObject& json, int sequenceNumber, QString& errorString);
+ virtual bool load(QTextStream &loadStream);
+ virtual bool load(const QJsonObject& json, int sequenceNumber, QString& errorString);
MissionItem& missionItem(void) { return _missionItem; }
const MissionItem& missionItem(void) const { return _missionItem; }
// Overrides from VisualMissionItem
- bool dirty (void) const final { return _dirty; }
+ bool dirty (void) const override { return _dirty; }
bool isSimpleItem (void) const final { return true; }
bool isStandaloneCoordinate (void) const final;
bool specifiesCoordinate (void) const final;
@@ -110,10 +111,10 @@ public:
QGeoCoordinate coordinate (void) const final { return _missionItem.coordinate(); }
QGeoCoordinate exitCoordinate (void) const final { return coordinate(); }
int sequenceNumber (void) const final { return _missionItem.sequenceNumber(); }
- double specifiedFlightSpeed (void) final;
- double specifiedGimbalYaw (void) final;
- double specifiedGimbalPitch (void) final;
- QString mapVisualQML (void) const final { return QStringLiteral("SimpleItemMapVisual.qml"); }
+ double specifiedFlightSpeed (void) override;
+ double specifiedGimbalYaw (void) override;
+ double specifiedGimbalPitch (void) override;
+ QString mapVisualQML (void) const override { return QStringLiteral("SimpleItemMapVisual.qml"); }
void appendMissionItems (QList& items, QObject* missionItemParent) final;
void applyNewAltitude (double newAltitude) final;
void setMissionFlightStatus (MissionController::MissionFlightStatus_t& missionFlightStatus) final;
@@ -125,7 +126,7 @@ public:
bool exitCoordinateSameAsEntry (void) const final { return true; }
void setDirty (bool dirty) final;
- void setCoordinate (const QGeoCoordinate& coordinate) final;
+ void setCoordinate (const QGeoCoordinate& coordinate) override;
void setSequenceNumber (int sequenceNumber) final;
int lastSequenceNumber (void) const final;
void save (QJsonArray& missionItems) final;
diff --git a/src/MissionManager/TakeoffMissionItem.cc b/src/MissionManager/TakeoffMissionItem.cc
new file mode 100644
index 0000000000000000000000000000000000000000..5faa12316a74b4f089377890761ba3cfcb80f9b3
--- /dev/null
+++ b/src/MissionManager/TakeoffMissionItem.cc
@@ -0,0 +1,125 @@
+/****************************************************************************
+ *
+ * (c) 2009-2016 QGROUNDCONTROL PROJECT
+ *
+ * QGroundControl is licensed according to the terms in the file
+ * COPYING.md in the root of the source code directory.
+ *
+ ****************************************************************************/
+
+#include
+#include
+
+#include "TakeoffMissionItem.h"
+#include "FirmwarePluginManager.h"
+#include "QGCApplication.h"
+#include "JsonHelper.h"
+#include "MissionCommandTree.h"
+#include "MissionCommandUIInfo.h"
+#include "QGroundControlQmlGlobal.h"
+#include "SettingsManager.h"
+
+TakeoffMissionItem::TakeoffMissionItem(Vehicle* vehicle, bool flyView, MissionSettingsItem* settingsItem, QObject* parent)
+ : SimpleMissionItem (vehicle, flyView, parent)
+ , _settingsItem (settingsItem)
+{
+ _init();
+}
+
+TakeoffMissionItem::TakeoffMissionItem(MAV_CMD takeoffCmd, Vehicle* vehicle, bool flyView, MissionSettingsItem* settingsItem, QObject* parent)
+ : SimpleMissionItem (vehicle, flyView, parent)
+ , _settingsItem (settingsItem)
+{
+ setCommand(takeoffCmd);
+ _init();
+}
+
+TakeoffMissionItem::TakeoffMissionItem(const MissionItem& missionItem, Vehicle* vehicle, bool flyView, MissionSettingsItem* settingsItem, QObject* parent)
+ : SimpleMissionItem (vehicle, flyView, missionItem, parent)
+ , _settingsItem (settingsItem)
+{
+ _init();
+}
+
+TakeoffMissionItem::~TakeoffMissionItem()
+{
+
+}
+
+void TakeoffMissionItem::_init(void)
+{
+ _editorQml = QStringLiteral("qrc:/qml/SimpleItemEditor.qml");
+
+ if (_settingsItem->coordinate().isValid()) {
+ // Either the user has set a Launch location or it came from a connected vehicle.
+ // Use it as starting point.
+ setCoordinate(_settingsItem->coordinate());
+ }
+ connect(_settingsItem, &MissionSettingsItem::coordinateChanged, this, &TakeoffMissionItem::launchCoordinateChanged);
+
+ _initLaunchTakeoffAtSameLocation();
+
+ setDirty(false);
+}
+
+void TakeoffMissionItem::setLaunchTakeoffAtSameLocation(bool launchTakeoffAtSameLocation)
+{
+ if (launchTakeoffAtSameLocation != _launchTakeoffAtSameLocation) {
+ _launchTakeoffAtSameLocation = launchTakeoffAtSameLocation;
+ if (_launchTakeoffAtSameLocation) {
+ setLaunchCoordinate(coordinate());
+ }
+ emit launchTakeoffAtSameLocationChanged(_launchTakeoffAtSameLocation);
+ setDirty(true);
+ }
+}
+
+void TakeoffMissionItem::setCoordinate(const QGeoCoordinate& coordinate)
+{
+ if (this->coordinate().isValid() || !_vehicle->fixedWing()) {
+ if (coordinate != this->coordinate()) {
+ if (_launchTakeoffAtSameLocation) {
+ setLaunchCoordinate(coordinate);
+ }
+ SimpleMissionItem::setCoordinate(coordinate);
+ }
+ } else {
+ // First time setup for fixed wing
+ if (!launchCoordinate().isValid()) {
+ setLaunchCoordinate(coordinate);
+ }
+ SimpleMissionItem::setCoordinate(launchCoordinate().atDistanceAndAzimuth(60, 0));
+ }
+}
+
+bool TakeoffMissionItem::isTakeoffCommand(MAV_CMD command)
+{
+ return command == MAV_CMD_NAV_TAKEOFF || command == MAV_CMD_NAV_VTOL_TAKEOFF;
+}
+
+void TakeoffMissionItem::_initLaunchTakeoffAtSameLocation(void)
+{
+ if (_vehicle->fixedWing()) {
+ setLaunchTakeoffAtSameLocation(!specifiesCoordinate());
+ } else {
+ setLaunchTakeoffAtSameLocation(coordinate().latitude() == _settingsItem->coordinate().latitude() && coordinate().longitude() == _settingsItem->coordinate().longitude());
+ }
+}
+
+bool TakeoffMissionItem::load(QTextStream &loadStream)
+{
+ bool success = SimpleMissionItem::load(loadStream);
+ if (success) {
+ _initLaunchTakeoffAtSameLocation();
+ }
+ return success;
+}
+
+bool TakeoffMissionItem::load(const QJsonObject& json, int sequenceNumber, QString& errorString)
+{
+ bool success = SimpleMissionItem::load(json, sequenceNumber, errorString);
+ if (success) {
+ _initLaunchTakeoffAtSameLocation();
+ }
+ return success;
+}
diff --git a/src/MissionManager/TakeoffMissionItem.h b/src/MissionManager/TakeoffMissionItem.h
new file mode 100644
index 0000000000000000000000000000000000000000..f42617d45ff87419dce65778808805408c013ec9
--- /dev/null
+++ b/src/MissionManager/TakeoffMissionItem.h
@@ -0,0 +1,63 @@
+/****************************************************************************
+ *
+ * (c) 2009-2016 QGROUNDCONTROL PROJECT
+ *
+ * QGroundControl is licensed according to the terms in the file
+ * COPYING.md in the root of the source code directory.
+ *
+ ****************************************************************************/
+
+#pragma once
+
+#include "SimpleMissionItem.h"
+#include "MissionSettingsItem.h"
+
+/// Takeoff mission item is a special case of a SimpleMissionItem which supports Launch Location display/editing
+/// which is tied to home position.
+class TakeoffMissionItem : public SimpleMissionItem
+{
+ Q_OBJECT
+
+public:
+ TakeoffMissionItem(Vehicle* vehicle, bool flyView, MissionSettingsItem* settingsItem, QObject* parent);
+ TakeoffMissionItem(MAV_CMD takeoffCmd, Vehicle* vehicle, bool flyView, MissionSettingsItem* settingsItem, QObject* parent);
+ TakeoffMissionItem(const MissionItem& missionItem, Vehicle* vehicle, bool flyView, MissionSettingsItem* settingsItem, QObject* parent);
+
+ Q_PROPERTY(QGeoCoordinate launchCoordinate READ launchCoordinate WRITE setLaunchCoordinate NOTIFY launchCoordinateChanged)
+ Q_PROPERTY(bool launchTakeoffAtSameLocation READ launchTakeoffAtSameLocation WRITE setLaunchTakeoffAtSameLocation NOTIFY launchTakeoffAtSameLocationChanged)
+
+ QGeoCoordinate launchCoordinate (void) const { return _settingsItem->coordinate(); }
+ bool launchTakeoffAtSameLocation (void) const { return _launchTakeoffAtSameLocation; }
+
+ void setLaunchCoordinate (const QGeoCoordinate& launchCoordinate) { _settingsItem->setCoordinate(launchCoordinate); }
+ void setLaunchTakeoffAtSameLocation (bool launchTakeoffAtSameLocation);
+
+ static bool isTakeoffCommand(MAV_CMD command);
+
+ ~TakeoffMissionItem();
+
+ // Overrides from VisualMissionItem
+ void setCoordinate (const QGeoCoordinate& coordinate) override;
+ bool isTakeoffItem (void) const final { return true; }
+ double specifiedFlightSpeed (void) final { return std::numeric_limits::quiet_NaN(); }
+ double specifiedGimbalYaw (void) final { return std::numeric_limits::quiet_NaN(); }
+ double specifiedGimbalPitch (void) final { return std::numeric_limits::quiet_NaN(); }
+ QString mapVisualQML (void) const override { return QStringLiteral("TakeoffItemMapVisual.qml"); }
+
+ // Overrides from SimpleMissionItem
+ bool load(QTextStream &loadStream) final;
+ bool load(const QJsonObject& json, int sequenceNumber, QString& errorString) final;
+
+ //void setDirty(bool dirty) final;
+
+signals:
+ void launchCoordinateChanged (const QGeoCoordinate& launchCoordinate);
+ void launchTakeoffAtSameLocationChanged (bool launchTakeoffAtSameLocation);
+
+private:
+ void _init(void);
+ void _initLaunchTakeoffAtSameLocation(void);
+
+ MissionSettingsItem* _settingsItem;
+ bool _launchTakeoffAtSameLocation = true;
+};
diff --git a/src/MissionManager/VisualMissionItem.cc b/src/MissionManager/VisualMissionItem.cc
index 75aafb23374be78e57880ee9be6d857ffbf992d8..9141f349e0da31933535606abcec058e5d4556df 100644
--- a/src/MissionManager/VisualMissionItem.cc
+++ b/src/MissionManager/VisualMissionItem.cc
@@ -16,6 +16,7 @@
#include "QGCApplication.h"
#include "JsonHelper.h"
#include "TerrainQuery.h"
+#include "TakeoffMissionItem.h"
const char* VisualMissionItem::jsonTypeKey = "type";
const char* VisualMissionItem::jsonTypeSimpleItemValue = "SimpleItem";
diff --git a/src/MissionManager/VisualMissionItem.h b/src/MissionManager/VisualMissionItem.h
index 5d9459f953a60de8fe59460a85d565c81545f24b..d83dee180ac1d017568b6fb2ad0d6756efbf94ad 100644
--- a/src/MissionManager/VisualMissionItem.h
+++ b/src/MissionManager/VisualMissionItem.h
@@ -65,6 +65,7 @@ public:
Q_PROPERTY(bool isStandaloneCoordinate READ isStandaloneCoordinate NOTIFY isStandaloneCoordinateChanged) ///< true: Waypoint line does not go through item
Q_PROPERTY(bool specifiesAltitudeOnly READ specifiesAltitudeOnly NOTIFY specifiesAltitudeOnlyChanged) ///< true: Item has altitude only, no full coordinate
Q_PROPERTY(bool isSimpleItem READ isSimpleItem NOTIFY isSimpleItemChanged) ///< Simple or Complex MissionItem
+ Q_PROPERTY(bool isTakeoffItem READ isTakeoffItem NOTIFY isTakeoffItemChanged) ///< true: Takeoff item special case
Q_PROPERTY(QString editorQml MEMBER _editorQml CONSTANT) ///< Qml code for editing this item
Q_PROPERTY(QString mapVisualQML READ mapVisualQML CONSTANT) ///< QMl code for map visuals
Q_PROPERTY(QmlObjectListModel* childItems READ childItems CONSTANT)
@@ -120,6 +121,7 @@ public:
virtual bool dirty (void) const = 0;
virtual bool isSimpleItem (void) const = 0;
+ virtual bool isTakeoffItem (void) const { return false; }
virtual bool isStandaloneCoordinate (void) const = 0;
virtual bool specifiesCoordinate (void) const = 0;
virtual bool specifiesAltitudeOnly (void) const = 0;
@@ -194,6 +196,7 @@ signals:
void isCurrentItemChanged (bool isCurrentItem);
void sequenceNumberChanged (int sequenceNumber);
void isSimpleItemChanged (bool isSimpleItem);
+ void isTakeoffItemChanged (bool isTakeoffItem);
void specifiesCoordinateChanged (void);
void isStandaloneCoordinateChanged (void);
void specifiesAltitudeOnlyChanged (void);
diff --git a/src/PlanView/MissionItemEditor.qml b/src/PlanView/MissionItemEditor.qml
index a6119058eb20f1af427d6774aef4f641c5c94596..3c43cde6d97016a57438bb444b9dea794ee5afaa 100644
--- a/src/PlanView/MissionItemEditor.qml
+++ b/src/PlanView/MissionItemEditor.qml
@@ -252,7 +252,7 @@ Rectangle {
id: commandLabel
anchors.leftMargin: ScreenTools.comboBoxPadding
anchors.fill: commandPicker
- visible: !missionItem.isCurrentItem || !missionItem.isSimpleItem || _waypointsOnlyMode
+ visible: (!missionItem.isCurrentItem || !missionItem.isSimpleItem || _waypointsOnlyMode) && !missionItem.isTakeoffItem
verticalAlignment: Text.AlignVCenter
text: missionItem.commandName
color: _outerTextColor
diff --git a/src/PlanView/PlanView.qml b/src/PlanView/PlanView.qml
index 21a6d3ce298d8571ff388ef53b183292786a7e92..71aa7b06975c213e17714663a1dfaaf9aa13a04e 100644
--- a/src/PlanView/PlanView.qml
+++ b/src/PlanView/PlanView.qml
@@ -60,18 +60,22 @@ Item {
readonly property int _layerRallyPoints: 3
readonly property string _armedVehicleUploadPrompt: qsTr("Vehicle is currently armed. Do you want to upload the mission to the vehicle?")
- function addComplexItem(complexItemName) {
+ function mapCenter() {
var coordinate = editorMap.center
coordinate.latitude = coordinate.latitude.toFixed(_decimalPlaces)
coordinate.longitude = coordinate.longitude.toFixed(_decimalPlaces)
coordinate.altitude = coordinate.altitude.toFixed(_decimalPlaces)
+ return coordinate
+ }
+
+ function addComplexItem(complexItemName) {
var next_index = _missionController.visualItemIndexFromSequenceNumber(_missionController.currentPlanViewIndex)+1
if(next_index ==1 && _missionController.visualItems.count >1){
console.log(next_index, _missionController.visualItems.count)
- insertComplexMissionItem(complexItemName, coordinate, next_index+1)
+ insertComplexMissionItem(complexItemName, mapCenter(), next_index+1)
}
else if(next_index <= _missionController.visualItems.count){
- insertComplexMissionItem(complexItemName, coordinate, next_index)
+ insertComplexMissionItem(complexItemName, mapCenter(), next_index)
}
}
@@ -618,7 +622,13 @@ Item {
z: QGroundControl.zOrderWidgets
maxHeight: mapScale.y - toolStrip.y
- property int fileButtonIndex: 1
+ readonly property int flyButtonIndex: 0
+ readonly property int fileButtonIndex: 1
+ readonly property int takeoffButtonIndex: 2
+ readonly property int waypointButtonIndex: 3
+ readonly property int roiButtonIndex: 4
+ readonly property int patternButtonIndex: 5
+ readonly property int centerButtonIndex: 6
property bool _isRally: _editingLayer == _layerRallyPoints
@@ -638,6 +648,12 @@ Item {
alternateIconSource:"/qmlimages/MapSyncChanged.svg",
dropPanelComponent: syncDropPanel
},
+ {
+ name: qsTr("Takeoff"),
+ iconSource: "/res/takeoff.svg",
+ buttonEnabled: _missionController.isInsertTakeoffValid,
+ buttonVisible: _editingLayer == _layerMission
+ },
{
name: _editingLayer == _layerRallyPoints ? qsTr("Rally Point") : qsTr("Waypoint"),
iconSource: "/qmlimages/MapAddMission.svg",
@@ -671,10 +687,13 @@ Item {
onClicked: {
switch (index) {
- case 0:
+ case flyButtonIndex:
mainWindow.showFlyView()
- break;
- case 2:
+ break
+ case takeoffButtonIndex:
+ _missionController.insertTakeoffItem(mapCenter(), _missionController.currentMissionIndex, true /* makeCurrentItem */)
+ break
+ case waypointButtonIndex:
if(_addWaypointOnClick) {
//-- Toggle it off
_addWaypointOnClick = false
@@ -685,11 +704,11 @@ Item {
_addROIOnClick = false
}
break
- case 3:
+ case roiButtonIndex:
_addROIOnClick = checked
_addWaypointOnClick = false
break
- case 4:
+ case patternButtonIndex:
if (_singleComplexItem) {
addComplexItem(_missionController.complexMissionItemNames[0])
}
diff --git a/src/PlanView/SimpleItemEditor.qml b/src/PlanView/SimpleItemEditor.qml
index 0406f621c9ab7e486296e75d286ed4b3b6ee63ce..a94b26de73fe3a4a509b01c0f14a51bede02a8bd 100644
--- a/src/PlanView/SimpleItemEditor.qml
+++ b/src/PlanView/SimpleItemEditor.qml
@@ -66,13 +66,14 @@ Rectangle {
visible: missionItem.wizardMode
QGCLabel {
- text: qsTr("Adjust the initial launch location by selecting 'P' and dragging it to the correct location.")
+ text: qsTr("Adjust the initial launch location by dragging 'L' indicator to the desired location.")
Layout.fillWidth: true
wrapMode: Text.WordWrap
+ visible: !missionItem.launchTakeoffAtSameLocation
}
QGCLabel {
- text: qsTr("Adjust the takeoff completion location by dragging it to the correct location.")
+ text: qsTr("Adjust the takeoff %1 location by dragging 'T' indicator to the desired location.").arg(missionItem.launchTakeoffAtSameLocation ? "" : qsTr("completion "))
Layout.fillWidth: true
wrapMode: Text.WordWrap
}
diff --git a/src/PlanView/TakeoffItemMapVisual.qml b/src/PlanView/TakeoffItemMapVisual.qml
new file mode 100644
index 0000000000000000000000000000000000000000..6c38cbeee0b2fca6044178c38950deb05446f49a
--- /dev/null
+++ b/src/PlanView/TakeoffItemMapVisual.qml
@@ -0,0 +1,130 @@
+/****************************************************************************
+ *
+ * (c) 2009-2016 QGROUNDCONTROL PROJECT
+ *
+ * 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 1.2
+import QtLocation 5.3
+import QtPositioning 5.3
+
+import QGroundControl 1.0
+import QGroundControl.ScreenTools 1.0
+import QGroundControl.Palette 1.0
+import QGroundControl.Controls 1.0
+import QGroundControl.FlightMap 1.0
+
+/// Simple Mission Item visuals
+Item {
+ id: _root
+
+ property var map ///< Map control to place item in
+ property var vehicle ///< Vehicle associated with this item
+
+ property var _missionItem: object
+ property var _takeoffIndicatorItem
+ property var _launchIndicatorItem
+
+ signal clicked(int sequenceNumber)
+
+ function addCommonVisuals() {
+ if (_objMgrCommonVisuals.empty) {
+ _takeoffIndicatorItem = _objMgrCommonVisuals.createObject(takeoffIndicatorComponent, map, true /* addToMap */)
+ _launchIndicatorItem = _objMgrCommonVisuals.createObject(launchIndicatorComponent, map, true /* addToMap */)
+ }
+ }
+
+ function addEditingVisuals() {
+ if (_objMgrEditingVisuals.empty) {
+ _objMgrEditingVisuals.createObjects([ takeoffDragComponent, launchDragComponent ], map, false /* addToMap */)
+ }
+ }
+
+ QGCDynamicObjectManager { id: _objMgrCommonVisuals }
+ QGCDynamicObjectManager { id: _objMgrEditingVisuals }
+
+ Component.onCompleted: {
+ addCommonVisuals()
+ if (_missionItem.isCurrentItem && map.planView) {
+ addEditingVisuals()
+ }
+ }
+
+ Connections {
+ target: _missionItem
+
+ onIsCurrentItemChanged: {
+ if (_missionItem.isCurrentItem && map.planView) {
+ addEditingVisuals()
+ } else {
+ _objMgrEditingVisuals.destroyObjects()
+ }
+ }
+ }
+
+ Component {
+ id: takeoffDragComponent
+
+ MissionItemIndicatorDrag {
+ mapControl: _root.map
+ itemIndicator: _takeoffIndicatorItem
+ itemCoordinate: _missionItem.specifiesCoordinate ? _missionItem.coordinate : _missionItem.launchCoordinate
+
+ onItemCoordinateChanged: {
+ if (_missionItem.specifiesCoordinate) {
+ _missionItem.coordinate = itemCoordinate
+ } else {
+ _missionItem.launchCoordinate = itemCoordinate
+ }
+ }
+ }
+ }
+
+ Component {
+ id: launchDragComponent
+
+ MissionItemIndicatorDrag {
+ mapControl: _root.map
+ itemIndicator: _launchIndicatorItem
+ itemCoordinate: _missionItem.launchCoordinate
+ visible: !_missionItem.launchTakeoffAtSameLocation
+
+ onItemCoordinateChanged: _missionItem.launchCoordinate = itemCoordinate
+ }
+ }
+
+ Component {
+ id: takeoffIndicatorComponent
+
+ MissionItemIndicator {
+ coordinate: _missionItem.specifiesCoordinate ? _missionItem.coordinate : _missionItem.launchCoordinate
+ z: QGroundControl.zOrderMapItems
+ missionItem: _missionItem
+ sequenceNumber: _missionItem.sequenceNumber
+ onClicked: _root.clicked(_missionItem.sequenceNumber)
+ }
+ }
+
+ Component {
+ id: launchIndicatorComponent
+
+ MapQuickItem {
+ coordinate: _missionItem.launchCoordinate
+ anchorPoint.x: sourceItem.anchorPointX
+ anchorPoint.y: sourceItem.anchorPointY
+ visible: !_missionItem.launchTakeoffAtSameLocation
+
+ sourceItem:
+ MissionItemIndexLabel {
+ checked: _missionItem.isCurrentItem
+ label: qsTr("Launch")
+ highlightSelected: true
+ onClicked: _root.clicked(_missionItem.sequenceNumber)
+ }
+ }
+ }
+}