Unverified Commit ba32528d authored by Don Gagne's avatar Don Gagne Committed by GitHub

Merge pull request #8026 from DonLakeFlyer/TakeoffTool

Plan: Takeoff tool and Takeoff item support
parents 9d216588 8667cde0
......@@ -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 \
......
......@@ -152,6 +152,7 @@
<file alias="QGroundControl/Controls/StructureScanMapVisual.qml">src/PlanView/StructureScanMapVisual.qml</file>
<file alias="QGroundControl/Controls/SubMenuButton.qml">src/QmlControls/SubMenuButton.qml</file>
<file alias="QGroundControl/Controls/SurveyMapVisual.qml">src/PlanView/SurveyMapVisual.qml</file>
<file alias="QGroundControl/Controls/TakeoffItemMapVisual.qml">src/PlanView/TakeoffItemMapVisual.qml</file>
<file alias="QGroundControl/Controls/ToolStrip.qml">src/QmlControls/ToolStrip.qml</file>
<file alias="QGroundControl/Controls/TransectStyleComplexItemStats.qml">src/PlanView/TransectStyleComplexItemStats.qml</file>
<file alias="QGroundControl/Controls/TransectStyleMapVisuals.qml">src/PlanView/TransectStyleMapVisuals.qml</file>
......
......@@ -203,7 +203,7 @@ QGCCameraManager::_findCamera(int id)
}
}
}
qWarning() << "Camera component id not found:" << id;
//qWarning() << "Camera component id not found:" << id;
return nullptr;
}
......
......@@ -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)
......
This diff is collapsed.
This diff is collapsed.
......@@ -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<MissionSettingsItem*>(0);
SimpleMissionItem* simpleItem = visualItems->value<SimpleMissionItem*>(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)
{
......
......@@ -36,8 +36,6 @@ private slots:
void _testLoadJsonSectionAvailable(void);
void _testEmptyVehicleAPM(void);
void _testEmptyVehiclePX4(void);
void _testAddWayppointAPM(void);
void _testAddWayppointPX4(void);
private:
#if 0
......
......@@ -21,8 +21,6 @@
QGC_LOGGING_CATEGORY(MissionSettingsComplexItemLog, "MissionSettingsComplexItemLog")
const char* MissionSettingsItem::jsonComplexItemTypeValue = "MissionSettings";
const char* MissionSettingsItem::_plannedHomePositionAltitudeName = "PlannedHomePositionAltitude";
QMap<QString, FactMetaData*> MissionSettingsItem::_metaDataMap;
......@@ -30,12 +28,8 @@ QMap<QString, FactMetaData*> 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; i<items.count(); i++) {
MissionItem* item = items[i];
......@@ -222,25 +216,54 @@ void MissionSettingsItem::_setDirty(void)
setDirty(true);
}
void MissionSettingsItem::setHomePositionFromVehicle(const QGeoCoordinate& coordinate)
void MissionSettingsItem::_setCoordinateWorker(const QGeoCoordinate& coordinate)
{
_plannedHomePositionFromVehicle = true;
setCoordinate(coordinate);
if (_plannedHomePositionCoordinate != coordinate) {
_plannedHomePositionCoordinate = coordinate;
emit coordinateChanged(coordinate);
emit exitCoordinateChanged(coordinate);
_plannedHomePositionAltitudeFact.setRawValue(coordinate.altitude());
}
}
void MissionSettingsItem::setCoordinate(const QGeoCoordinate& coordinate)
void MissionSettingsItem::setHomePositionFromVehicle(Vehicle* vehicle)
{
if (_plannedHomePositionCoordinate != coordinate) {
// If the user hasn't moved the planned home position manually we use the value from the vehicle
if (!_plannedHomePositionMovedByUser) {
QGeoCoordinate coordinate = vehicle->homePosition();
// 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");
}
......@@ -48,8 +48,14 @@ public:
/// @return true: Mission end action was added
bool addMissionEndAction(QList<MissionItem*>& 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<MissionItem*>& 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<QString, FactMetaData*> _metaDataMap;
......
......@@ -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
......
......@@ -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<MAV_CMD>(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<MissionItem*>& 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;
......
/****************************************************************************
*
* (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 <QStringList>
#include <QDebug>
#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;
}
/****************************************************************************
*
* (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 "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<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(); }
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;
};
......@@ -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";
......
......@@ -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);
......
......@@ -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
......
......@@ -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])
}
......
......@@ -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
}
......
/****************************************************************************
*
* (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 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)
}
}
}
}
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