diff --git a/qgroundcontrol.pro b/qgroundcontrol.pro index 66e6579673b6c7160b90dc161ad43395cedaedb0..92c56b84130f4a52994903adf708d3006371a6eb 100644 --- a/qgroundcontrol.pro +++ b/qgroundcontrol.pro @@ -243,7 +243,10 @@ FORMS += src/ui/MainWindow.ui \ src/ui/mission/QGCMissionConditionDelay.ui \ src/ui/mission/QGCMissionNavLoiterUnlim.ui \ src/ui/mission/QGCMissionNavLoiterTurns.ui \ - src/ui/mission/QGCMissionNavLoiterTime.ui + src/ui/mission/QGCMissionNavLoiterTime.ui \ + src/ui/mission/QGCMissionNavReturnToLaunch.ui \ + src/ui/mission/QGCMissionNavLand.ui \ + src/ui/mission/QGCMissionNavTakeoff.ui INCLUDEPATH += src \ src/ui \ src/ui/linechart \ @@ -371,7 +374,10 @@ HEADERS += src/MG.h \ src/ui/mission/QGCMissionConditionDelay.h \ src/ui/mission/QGCMissionNavLoiterUnlim.h \ src/ui/mission/QGCMissionNavLoiterTurns.h \ - src/ui/mission/QGCMissionNavLoiterTime.h + src/ui/mission/QGCMissionNavLoiterTime.h \ + src/ui/mission/QGCMissionNavReturnToLaunch.h \ + src/ui/mission/QGCMissionNavLand.h \ + src/ui/mission/QGCMissionNavTakeoff.h # Google Earth is only supported on Mac OS and Windows with Visual Studio Compiler macx|macx-g++|macx-g++42|win32-msvc2008|win32-msvc2010::HEADERS += src/ui/map3D/QGCGoogleEarthView.h @@ -508,7 +514,10 @@ SOURCES += src/main.cc \ src/ui/mission/QGCMissionConditionDelay.cc \ src/ui/mission/QGCMissionNavLoiterUnlim.cc \ src/ui/mission/QGCMissionNavLoiterTurns.cc \ - src/ui/mission/QGCMissionNavLoiterTime.cc + src/ui/mission/QGCMissionNavLoiterTime.cc \ + src/ui/mission/QGCMissionNavReturnToLaunch.cc \ + src/ui/mission/QGCMissionNavLand.cc \ + src/ui/mission/QGCMissionNavTakeoff.cc # Enable Google Earth only on Mac OS and Windows with Visual Studio compiler macx|macx-g++|macx-g++42|win32-msvc2008|win32-msvc2010::SOURCES += src/ui/map3D/QGCGoogleEarthView.cc diff --git a/src/ui/WaypointEditableView.cc b/src/ui/WaypointEditableView.cc index 039515dfa667184be4ba106ab882ad56a5f5f7c3..24499c12dfce6ac242780b7acb1057b5233ab2d3 100644 --- a/src/ui/WaypointEditableView.cc +++ b/src/ui/WaypointEditableView.cc @@ -25,6 +25,9 @@ #include "QGCMissionNavLoiterUnlim.h" #include "QGCMissionNavLoiterTurns.h" #include "QGCMissionNavLoiterTime.h" +#include "QGCMissionNavReturnToLaunch.h" +#include "QGCMissionNavLand.h" +#include "QGCMissionNavTakeoff.h" #include "QGCMissionConditionDelay.h" #include "QGCMissionDoJump.h" #include "QGCMissionOther.h" @@ -50,6 +53,9 @@ WaypointEditableView::WaypointEditableView(Waypoint* wp, QWidget* parent) : MissionNavLoiterUnlimWidget = NULL; MissionNavLoiterTurnsWidget = NULL; MissionNavLoiterTimeWidget = NULL; + MissionNavReturnToLaunchWidget = NULL; + MissionNavLandWidget = NULL; + MissionNavTakeoffWidget = NULL; MissionDoJumpWidget = NULL; MissionConditionDelayWidget = NULL; MissionOtherWidget = NULL; @@ -130,9 +136,12 @@ void WaypointEditableView::updateActionView(int action) if(MissionNavLoiterUnlimWidget) MissionNavLoiterUnlimWidget->hide(); if(MissionNavLoiterTurnsWidget) MissionNavLoiterTurnsWidget->hide(); if(MissionNavLoiterTimeWidget) MissionNavLoiterTimeWidget->hide(); - if(MissionOtherWidget) MissionOtherWidget->hide(); + if(MissionNavReturnToLaunchWidget) MissionNavReturnToLaunchWidget->hide(); + if(MissionNavLandWidget) MissionNavLandWidget->hide(); + if(MissionNavTakeoffWidget) MissionNavTakeoffWidget->hide(); if(MissionConditionDelayWidget) MissionConditionDelayWidget->hide(); if(MissionDoJumpWidget) MissionDoJumpWidget->hide(); + if(MissionOtherWidget) MissionOtherWidget->hide(); //Show only the correct one if (viewMode != QGC_WAYPOINTEDITABLEVIEW_MODE_DIRECT_EDITING) @@ -151,8 +160,14 @@ void WaypointEditableView::updateActionView(int action) if(MissionNavLoiterTimeWidget) MissionNavLoiterTimeWidget->show(); break; case MAV_CMD_NAV_RETURN_TO_LAUNCH: + if(MissionNavReturnToLaunchWidget) MissionNavReturnToLaunchWidget->show(); + break; case MAV_CMD_NAV_LAND: + if(MissionNavLandWidget) MissionNavLandWidget->show(); + break; case MAV_CMD_NAV_TAKEOFF: + if(MissionNavTakeoffWidget) MissionNavTakeoffWidget->show(); + break; case MAV_CMD_CONDITION_DELAY: if(MissionConditionDelayWidget) MissionConditionDelayWidget->show(); break; @@ -227,8 +242,26 @@ void WaypointEditableView::initializeActionView(int actionID) } break; case MAV_CMD_NAV_RETURN_TO_LAUNCH: + if (!MissionNavReturnToLaunchWidget) + { + MissionNavReturnToLaunchWidget = new QGCMissionNavReturnToLaunch(this); + m_ui->customActionWidget->layout()->addWidget(MissionNavReturnToLaunchWidget); + } + break; case MAV_CMD_NAV_LAND: + if (!MissionNavLandWidget) + { + MissionNavLandWidget = new QGCMissionNavLand(this); + m_ui->customActionWidget->layout()->addWidget(MissionNavLandWidget); + } + break; case MAV_CMD_NAV_TAKEOFF: + if (!MissionNavTakeoffWidget) + { + MissionNavTakeoffWidget = new QGCMissionNavTakeoff(this); + m_ui->customActionWidget->layout()->addWidget(MissionNavTakeoffWidget); + } + break; case MAV_CMD_CONDITION_DELAY: if (!MissionConditionDelayWidget) { diff --git a/src/ui/WaypointEditableView.h b/src/ui/WaypointEditableView.h index 425e62fbaccb28d4fba5fb2cb4dd1975ba7c3746..05753c571391d9fb33ce502be643d71200e70a51 100644 --- a/src/ui/WaypointEditableView.h +++ b/src/ui/WaypointEditableView.h @@ -50,6 +50,9 @@ class QGCMissionNavWaypoint; class QGCMissionNavLoiterUnlim; class QGCMissionNavLoiterTurns; class QGCMissionNavLoiterTime; +class QGCMissionNavReturnToLaunch; +class QGCMissionNavLand; +class QGCMissionNavTakeoff; class QGCMissionDoJump; class QGCMissionConditionDelay; class QGCMissionOther; @@ -99,6 +102,9 @@ protected: QGCMissionNavLoiterUnlim* MissionNavLoiterUnlimWidget; QGCMissionNavLoiterTurns* MissionNavLoiterTurnsWidget; QGCMissionNavLoiterTime* MissionNavLoiterTimeWidget; + QGCMissionNavReturnToLaunch* MissionNavReturnToLaunchWidget; + QGCMissionNavLand* MissionNavLandWidget; + QGCMissionNavTakeoff* MissionNavTakeoffWidget; QGCMissionDoJump* MissionDoJumpWidget; QGCMissionConditionDelay* MissionConditionDelayWidget; QGCMissionOther* MissionOtherWidget; diff --git a/src/ui/mission/QGCMissionConditionDelay.ui b/src/ui/mission/QGCMissionConditionDelay.ui index 82524b7a5f1e4077cd9da4fcacdcb4e69bdc7ec5..2fc8980db63858e497dc6aa6666af854e7fcdd56 100644 --- a/src/ui/mission/QGCMissionConditionDelay.ui +++ b/src/ui/mission/QGCMissionConditionDelay.ui @@ -18,7 +18,7 @@ - 200 + 0 0 diff --git a/src/ui/mission/QGCMissionDoJump.ui b/src/ui/mission/QGCMissionDoJump.ui index 088bf08c7a88baad444aa1c7cbce31cf575eb79a..1fe1e4dd246a094c9f6d71a9b3162c996185a7ac 100644 --- a/src/ui/mission/QGCMissionDoJump.ui +++ b/src/ui/mission/QGCMissionDoJump.ui @@ -18,7 +18,7 @@ - 200 + 0 0 diff --git a/src/ui/mission/QGCMissionNavLand.cc b/src/ui/mission/QGCMissionNavLand.cc new file mode 100644 index 0000000000000000000000000000000000000000..3f6bca227f351eb2ad30f4a7463938f011c48819 --- /dev/null +++ b/src/ui/mission/QGCMissionNavLand.cc @@ -0,0 +1,68 @@ +#include "QGCMissionNavLand.h" +#include "ui_QGCMissionNavLand.h" +#include "WaypointEditableView.h" + +QGCMissionNavLand::QGCMissionNavLand(WaypointEditableView* WEV) : + QWidget(WEV), + ui(new Ui::QGCMissionNavLand) +{ + ui->setupUi(this); + this->WEV = WEV; + + //Using UI to change WP: + //connect(this->ui->holdTimeSpinBox, SIGNAL(valueChanged(double)),WEV,SLOT(changedParam1(double))); + //connect(this->ui->acceptanceSpinBox, SIGNAL(valueChanged(double)),WEV,SLOT(changedParam2(double))); + //connect(this->ui->param3SpinBox, SIGNAL(valueChanged(double)),WEV,SLOT(changedParam3(double))); + connect(this->ui->yawSpinBox, SIGNAL(valueChanged(double)),WEV,SLOT(changedParam4(double))); + connect(this->ui->posNSpinBox, SIGNAL(valueChanged(double)),WEV,SLOT(changedParam5(double)));//NED + connect(this->ui->posESpinBox, SIGNAL(valueChanged(double)),WEV,SLOT(changedParam6(double))); + connect(this->ui->posDSpinBox, SIGNAL(valueChanged(double)),WEV,SLOT(changedParam7(double))); + connect(this->ui->latSpinBox, SIGNAL(valueChanged(double)),WEV,SLOT(changedParam5(double)));//Global + connect(this->ui->lonSpinBox, SIGNAL(valueChanged(double)),WEV,SLOT(changedParam6(double))); + connect(this->ui->altSpinBox, SIGNAL(valueChanged(double)),WEV,SLOT(changedParam7(double))); + + //Reading WP to update UI: + connect(WEV,SIGNAL(frameBroadcast(MAV_FRAME)),this,SLOT(updateFrame(MAV_FRAME))); + //connect(WEV,SIGNAL(param1Broadcast(double)),this->ui->holdTimeSpinBox,SLOT(setValue(double))); + //connect(WEV,SIGNAL(param2Broadcast(double)),this->ui->acceptanceSpinBox,SLOT(setValue(double))); + //connect(WEV,SIGNAL(param3Broadcast(double)),this->ui->param3SpinBox,SLOT(setValue(double))); + connect(WEV,SIGNAL(param4Broadcast(double)),this->ui->yawSpinBox,SLOT(setValue(double))); + connect(WEV,SIGNAL(param5Broadcast(double)),this->ui->posNSpinBox,SLOT(setValue(double)));//NED + connect(WEV,SIGNAL(param6Broadcast(double)),this->ui->posESpinBox,SLOT(setValue(double))); + connect(WEV,SIGNAL(param7Broadcast(double)),this->ui->posDSpinBox,SLOT(setValue(double))); + connect(WEV,SIGNAL(param5Broadcast(double)),this->ui->latSpinBox,SLOT(setValue(double)));//Global + connect(WEV,SIGNAL(param6Broadcast(double)),this->ui->lonSpinBox,SLOT(setValue(double))); + connect(WEV,SIGNAL(param7Broadcast(double)),this->ui->altSpinBox,SLOT(setValue(double))); +} + +void QGCMissionNavLand::updateFrame(MAV_FRAME frame) +{ + switch(frame) + { + case MAV_FRAME_LOCAL_ENU: + case MAV_FRAME_LOCAL_NED: + this->ui->posNSpinBox->show(); + this->ui->posESpinBox->show(); + this->ui->posDSpinBox->show(); + this->ui->latSpinBox->hide(); + this->ui->lonSpinBox->hide(); + this->ui->altSpinBox->hide(); + break; + case MAV_FRAME_GLOBAL: + case MAV_FRAME_GLOBAL_RELATIVE_ALT: + this->ui->posNSpinBox->hide(); + this->ui->posESpinBox->hide(); + this->ui->posDSpinBox->hide(); + this->ui->latSpinBox->show(); + this->ui->lonSpinBox->show(); + this->ui->altSpinBox->show(); + break; + default: + break; + } +} + +QGCMissionNavLand::~QGCMissionNavLand() +{ + delete ui; +} diff --git a/src/ui/mission/QGCMissionNavLand.h b/src/ui/mission/QGCMissionNavLand.h new file mode 100644 index 0000000000000000000000000000000000000000..5dfc0f323dccceb50b5cab1669ed930265f96dc3 --- /dev/null +++ b/src/ui/mission/QGCMissionNavLand.h @@ -0,0 +1,29 @@ +#ifndef QGCMISSIONNAVLAND_H +#define QGCMISSIONNAVLAND_H + +#include +#include "WaypointEditableView.h" + +namespace Ui { + class QGCMissionNavLand; +} + +class QGCMissionNavLand : public QWidget +{ + Q_OBJECT + +public: + explicit QGCMissionNavLand(WaypointEditableView* WEV); + ~QGCMissionNavLand(); + +public slots: + void updateFrame(MAV_FRAME); + +protected: + WaypointEditableView* WEV; + +private: + Ui::QGCMissionNavLand *ui; +}; + +#endif // QGCMISSIONNAVLAND_H diff --git a/src/ui/mission/QGCMissionNavLand.ui b/src/ui/mission/QGCMissionNavLand.ui new file mode 100644 index 0000000000000000000000000000000000000000..264283fb3f0a72c6ff36c182b7f26fbc08c04664 --- /dev/null +++ b/src/ui/mission/QGCMissionNavLand.ui @@ -0,0 +1,319 @@ + + + QGCMissionNavLand + + + + 0 + 0 + 2208 + 37 + + + + + 0 + 0 + + + + + 0 + 0 + + + + Form + + + + + + + 5 + + + 0 + + + + + + 0 + 0 + + + + Qt::WheelFocus + + + Position X coordinate + + + Position X corrdinate + + + false + + + true + + + true + + + false + + + N + + + m + + + -10000.000000000000000 + + + 10000.000000000000000 + + + 0.050000000000000 + + + + + + + + 0 + 0 + + + + Qt::WheelFocus + + + Position Y/Longitude coordinate + + + Position Y/Longitude coordinate + + + false + + + E + + + m + + + -10000.000000000000000 + + + 10000.000000000000000 + + + 0.050000000000000 + + + 0.000000000000000 + + + + + + + + 0 + 0 + + + + Qt::WheelFocus + + + Position Z coordinate (local frame, negative) + + + + + + false + + + D + + + m + + + -10000.000000000000000 + + + 10000.000000000000000 + + + 0.050000000000000 + + + + + + + + 0 + 0 + + + + Qt::WheelFocus + + + Latitude in degrees + + + Latitude in degrees + + + false + + + lat + + + ° + + + 7 + + + -90.000000000000000 + + + 90.000000000000000 + + + 0.000010000000000 + + + + + + + + 0 + 0 + + + + Qt::WheelFocus + + + Longitude in degrees + + + Longitude in degrees + + + false + + + lon + + + ° + + + 7 + + + -180.000000000000000 + + + 180.000000000000000 + + + 0.000010000000000 + + + + + + + + 0 + 0 + + + + Altitude in meters + + + Altitude in meters + + + false + + + alt + + + m + + + 2 + + + -100000.000000000000000 + + + 100000.000000000000000 + + + + + + + + 0 + 0 + + + + Qt::StrongFocus + + + Rotary wing only: Desired yaw angle at waypoint + + + Rotary wing only: Desired yaw angle at waypoint + + + true + + + false + + + + + + ° + + + 0 + + + -180.000000000000000 + + + 180.000000000000000 + + + + + + + + diff --git a/src/ui/mission/QGCMissionNavLoiterTime.ui b/src/ui/mission/QGCMissionNavLoiterTime.ui index 9d456cef2be7370475f16d5c1aff284f7e91af5d..3fb94202e56ea3811c50d9e0ed2d77b190ac4d37 100644 --- a/src/ui/mission/QGCMissionNavLoiterTime.ui +++ b/src/ui/mission/QGCMissionNavLoiterTime.ui @@ -18,7 +18,7 @@ - 200 + 0 0 diff --git a/src/ui/mission/QGCMissionNavLoiterTurns.ui b/src/ui/mission/QGCMissionNavLoiterTurns.ui index d4587a00d0151528fa04d34a3667658c97336ba5..b3c1dd90a25bda6f5526391e3921c629d2fbd7aa 100644 --- a/src/ui/mission/QGCMissionNavLoiterTurns.ui +++ b/src/ui/mission/QGCMissionNavLoiterTurns.ui @@ -18,7 +18,7 @@ - 200 + 0 0 diff --git a/src/ui/mission/QGCMissionNavLoiterUnlim.ui b/src/ui/mission/QGCMissionNavLoiterUnlim.ui index c41381d455d7a07f2672d3386814f625d5a4c96d..c9fde6709dfd3922bd783fc2c2499492c2ee2e6f 100644 --- a/src/ui/mission/QGCMissionNavLoiterUnlim.ui +++ b/src/ui/mission/QGCMissionNavLoiterUnlim.ui @@ -18,7 +18,7 @@ - 200 + 0 0 diff --git a/src/ui/mission/QGCMissionNavReturnToLaunch.cc b/src/ui/mission/QGCMissionNavReturnToLaunch.cc new file mode 100644 index 0000000000000000000000000000000000000000..5e698c4d58f70d498b7401f86e8dce23b29f064c --- /dev/null +++ b/src/ui/mission/QGCMissionNavReturnToLaunch.cc @@ -0,0 +1,16 @@ +#include "QGCMissionNavReturnToLaunch.h" +#include "ui_QGCMissionNavReturnToLaunch.h" +#include "WaypointEditableView.h" + +QGCMissionNavReturnToLaunch::QGCMissionNavReturnToLaunch(WaypointEditableView* WEV) : + QWidget(WEV), + ui(new Ui::QGCMissionNavReturnToLaunch) +{ + ui->setupUi(this); + this->WEV = WEV; +} + +QGCMissionNavReturnToLaunch::~QGCMissionNavReturnToLaunch() +{ + delete ui; +} diff --git a/src/ui/mission/QGCMissionNavReturnToLaunch.h b/src/ui/mission/QGCMissionNavReturnToLaunch.h new file mode 100644 index 0000000000000000000000000000000000000000..7e061454e789cbfa7652c3431296a2c80a1b1353 --- /dev/null +++ b/src/ui/mission/QGCMissionNavReturnToLaunch.h @@ -0,0 +1,26 @@ +#ifndef QGCMISSIONNAVRETURNTOLAUNCH_H +#define QGCMISSIONNAVRETURNTOLAUNCH_H + +#include +#include "WaypointEditableView.h" + +namespace Ui { + class QGCMissionNavReturnToLaunch; +} + +class QGCMissionNavReturnToLaunch : public QWidget +{ + Q_OBJECT + +public: + explicit QGCMissionNavReturnToLaunch(WaypointEditableView* WEV); + ~QGCMissionNavReturnToLaunch(); + +protected: + WaypointEditableView* WEV; + +private: + Ui::QGCMissionNavReturnToLaunch *ui; +}; + +#endif // QGCMISSIONNAVRETURNTOLAUNCH_H diff --git a/src/ui/mission/QGCMissionNavReturnToLaunch.ui b/src/ui/mission/QGCMissionNavReturnToLaunch.ui new file mode 100644 index 0000000000000000000000000000000000000000..87bc7186d9953d2e5270db46893091fc9f0d20d6 --- /dev/null +++ b/src/ui/mission/QGCMissionNavReturnToLaunch.ui @@ -0,0 +1,52 @@ + + + QGCMissionNavReturnToLaunch + + + + 0 + 0 + 258 + 37 + + + + + 0 + 0 + + + + + 0 + 0 + + + + Form + + + + + + + 5 + + + 0 + + + + + No Parameters + + + Qt::AlignCenter + + + + + + + + diff --git a/src/ui/mission/QGCMissionNavTakeoff.cc b/src/ui/mission/QGCMissionNavTakeoff.cc new file mode 100644 index 0000000000000000000000000000000000000000..386cb65d7c68d76198119dfd42f845bc06a311ee --- /dev/null +++ b/src/ui/mission/QGCMissionNavTakeoff.cc @@ -0,0 +1,68 @@ +#include "QGCMissionNavTakeoff.h" +#include "ui_QGCMissionNavTakeoff.h" +#include "WaypointEditableView.h" + +QGCMissionNavTakeoff::QGCMissionNavTakeoff(WaypointEditableView* WEV) : + QWidget(WEV), + ui(new Ui::QGCMissionNavTakeoff) + { + ui->setupUi(this); + this->WEV = WEV; + + //Using UI to change WP: + connect(this->ui->minPitchSpinBox, SIGNAL(valueChanged(double)),WEV,SLOT(changedParam1(double))); + //connect(this->ui->acceptanceSpinBox, SIGNAL(valueChanged(double)),WEV,SLOT(changedParam2(double))); + //connect(this->ui->param3SpinBox, SIGNAL(valueChanged(double)),WEV,SLOT(changedParam3(double))); + connect(this->ui->yawSpinBox, SIGNAL(valueChanged(double)),WEV,SLOT(changedParam4(double))); + connect(this->ui->posNSpinBox, SIGNAL(valueChanged(double)),WEV,SLOT(changedParam5(double)));//NED + connect(this->ui->posESpinBox, SIGNAL(valueChanged(double)),WEV,SLOT(changedParam6(double))); + connect(this->ui->posDSpinBox, SIGNAL(valueChanged(double)),WEV,SLOT(changedParam7(double))); + connect(this->ui->latSpinBox, SIGNAL(valueChanged(double)),WEV,SLOT(changedParam5(double)));//Global + connect(this->ui->lonSpinBox, SIGNAL(valueChanged(double)),WEV,SLOT(changedParam6(double))); + connect(this->ui->altSpinBox, SIGNAL(valueChanged(double)),WEV,SLOT(changedParam7(double))); + + //Reading WP to update UI: + connect(WEV,SIGNAL(frameBroadcast(MAV_FRAME)),this,SLOT(updateFrame(MAV_FRAME))); + connect(WEV,SIGNAL(param1Broadcast(double)),this->ui->minPitchSpinBox,SLOT(setValue(double))); + //connect(WEV,SIGNAL(param2Broadcast(double)),this->ui->acceptanceSpinBox,SLOT(setValue(double))); + //connect(WEV,SIGNAL(param3Broadcast(double)),this->ui->param3SpinBox,SLOT(setValue(double))); + connect(WEV,SIGNAL(param4Broadcast(double)),this->ui->yawSpinBox,SLOT(setValue(double))); + connect(WEV,SIGNAL(param5Broadcast(double)),this->ui->posNSpinBox,SLOT(setValue(double)));//NED + connect(WEV,SIGNAL(param6Broadcast(double)),this->ui->posESpinBox,SLOT(setValue(double))); + connect(WEV,SIGNAL(param7Broadcast(double)),this->ui->posDSpinBox,SLOT(setValue(double))); + connect(WEV,SIGNAL(param5Broadcast(double)),this->ui->latSpinBox,SLOT(setValue(double)));//Global + connect(WEV,SIGNAL(param6Broadcast(double)),this->ui->lonSpinBox,SLOT(setValue(double))); + connect(WEV,SIGNAL(param7Broadcast(double)),this->ui->altSpinBox,SLOT(setValue(double))); + } + +void QGCMissionNavTakeoff::updateFrame(MAV_FRAME frame) +{ + switch(frame) + { + case MAV_FRAME_LOCAL_ENU: + case MAV_FRAME_LOCAL_NED: + this->ui->posNSpinBox->show(); + this->ui->posESpinBox->show(); + this->ui->posDSpinBox->show(); + this->ui->latSpinBox->hide(); + this->ui->lonSpinBox->hide(); + this->ui->altSpinBox->hide(); + break; + case MAV_FRAME_GLOBAL: + case MAV_FRAME_GLOBAL_RELATIVE_ALT: + this->ui->posNSpinBox->hide(); + this->ui->posESpinBox->hide(); + this->ui->posDSpinBox->hide(); + this->ui->latSpinBox->show(); + this->ui->lonSpinBox->show(); + this->ui->altSpinBox->show(); + break; + default: + break; + } +} + +QGCMissionNavTakeoff::~QGCMissionNavTakeoff() +{ + delete ui; +} diff --git a/src/ui/mission/QGCMissionNavTakeoff.h b/src/ui/mission/QGCMissionNavTakeoff.h new file mode 100644 index 0000000000000000000000000000000000000000..198ccfc493780c75253718ea38d2e523e0a8f8c2 --- /dev/null +++ b/src/ui/mission/QGCMissionNavTakeoff.h @@ -0,0 +1,29 @@ +#ifndef QGCMISSIONNAVTAKEOFF_H +#define QGCMISSIONNAVTAKEOFF_H + +#include +#include "WaypointEditableView.h" + +namespace Ui { + class QGCMissionNavTakeoff; +} + +class QGCMissionNavTakeoff : public QWidget +{ + Q_OBJECT + +public: + explicit QGCMissionNavTakeoff(WaypointEditableView* WEV); + ~QGCMissionNavTakeoff(); + +public slots: + void updateFrame(MAV_FRAME); + +protected: + WaypointEditableView* WEV; + +private: + Ui::QGCMissionNavTakeoff *ui; +}; + +#endif // QGCMISSIONNAVTAKEOFF_H diff --git a/src/ui/mission/QGCMissionNavTakeoff.ui b/src/ui/mission/QGCMissionNavTakeoff.ui new file mode 100644 index 0000000000000000000000000000000000000000..7536c844f439a0a340da0edf5250feb21cbbf1d6 --- /dev/null +++ b/src/ui/mission/QGCMissionNavTakeoff.ui @@ -0,0 +1,353 @@ + + + QGCMissionNavTakeoff + + + + 0 + 0 + 2208 + 37 + + + + + 0 + 0 + + + + + 0 + 0 + + + + Form + + + + + + + 5 + + + 0 + + + + + + 0 + 0 + + + + Qt::WheelFocus + + + Position X coordinate + + + Position X corrdinate + + + false + + + true + + + true + + + false + + + N + + + m + + + -10000.000000000000000 + + + 10000.000000000000000 + + + 0.050000000000000 + + + + + + + + 0 + 0 + + + + Qt::WheelFocus + + + Position Y/Longitude coordinate + + + Position Y/Longitude coordinate + + + false + + + E + + + m + + + -10000.000000000000000 + + + 10000.000000000000000 + + + 0.050000000000000 + + + 0.000000000000000 + + + + + + + + 0 + 0 + + + + Qt::WheelFocus + + + Position Z coordinate (local frame, negative) + + + + + + false + + + D + + + m + + + -10000.000000000000000 + + + 10000.000000000000000 + + + 0.050000000000000 + + + + + + + + 0 + 0 + + + + Qt::WheelFocus + + + Latitude in degrees + + + Latitude in degrees + + + false + + + lat + + + ° + + + 7 + + + -90.000000000000000 + + + 90.000000000000000 + + + 0.000010000000000 + + + + + + + + 0 + 0 + + + + Qt::WheelFocus + + + Longitude in degrees + + + Longitude in degrees + + + false + + + lon + + + ° + + + 7 + + + -180.000000000000000 + + + 180.000000000000000 + + + 0.000010000000000 + + + + + + + + 0 + 0 + + + + Altitude in meters + + + Altitude in meters + + + false + + + alt + + + m + + + 2 + + + -100000.000000000000000 + + + 100000.000000000000000 + + + + + + + + 0 + 0 + + + + Qt::StrongFocus + + + Rotary wing only: Desired yaw angle at waypoint + + + Rotary wing only: Desired yaw angle at waypoint + + + true + + + false + + + + + + ° + + + 0 + + + -180.000000000000000 + + + 180.000000000000000 + + + + + + + + 0 + 0 + + + + Minimum Pitch + + + Minimum Pitch + + + false + + + ° + + + 0 + + + -90.000000000000000 + + + 90.000000000000000 + + + 0.000000000000000 + + + + + + + + diff --git a/src/ui/mission/QGCMissionNavWaypoint.ui b/src/ui/mission/QGCMissionNavWaypoint.ui index 5c502e12bc20c0c9fe7ca32eb8a4fc74e2b9cc7e..b10a0854275af60a2fa6b4564591bf69c3361b1f 100644 --- a/src/ui/mission/QGCMissionNavWaypoint.ui +++ b/src/ui/mission/QGCMissionNavWaypoint.ui @@ -18,7 +18,7 @@ - 200 + 0 0 diff --git a/src/ui/mission/QGCMissionOther.ui b/src/ui/mission/QGCMissionOther.ui index 7ef0ea209d7daf0e1166bf3ee27c18dd2974db9c..54d27eec5cc7649bd10816232cab8a6f53fa5dc8 100644 --- a/src/ui/mission/QGCMissionOther.ui +++ b/src/ui/mission/QGCMissionOther.ui @@ -10,6 +10,18 @@ 27 + + + 0 + 0 + + + + + 0 + 0 + + Form