diff --git a/qgroundcontrol.pro b/qgroundcontrol.pro index 653d46b2b6826c4ff7bb24e22f495978d7846d3a..66e6579673b6c7160b90dc161ad43395cedaedb0 100644 --- a/qgroundcontrol.pro +++ b/qgroundcontrol.pro @@ -224,12 +224,9 @@ FORMS += src/ui/MainWindow.ui \ src/ui/designer/QGCCommandButton.ui \ src/ui/QGCMAVLinkLogPlayer.ui \ src/ui/QGCWaypointListMulti.ui \ - src/ui/mission/QGCCustomWaypointAction.ui \ src/ui/QGCUDPLinkConfiguration.ui \ src/ui/QGCSettingsWidget.ui \ src/ui/UASControlParameters.ui \ - src/ui/mission/QGCMissionDoWidget.ui \ - src/ui/mission/QGCMissionConditionWidget.ui \ src/ui/map/QGCMapTool.ui \ src/ui/map/QGCMapToolBar.ui \ src/ui/QGCMAVLinkInspector.ui \ @@ -241,7 +238,12 @@ FORMS += src/ui/MainWindow.ui \ src/ui/QGCPluginHost.ui \ src/ui/firmwareupdate/QGCPX4FirmwareUpdate.ui \ src/ui/mission/QGCMissionOther.ui \ - src/ui/mission/QGCMissionNavWaypoint.ui + src/ui/mission/QGCMissionNavWaypoint.ui \ + src/ui/mission/QGCMissionDoJump.ui \ + src/ui/mission/QGCMissionConditionDelay.ui \ + src/ui/mission/QGCMissionNavLoiterUnlim.ui \ + src/ui/mission/QGCMissionNavLoiterTurns.ui \ + src/ui/mission/QGCMissionNavLoiterTime.ui INCLUDEPATH += src \ src/ui \ src/ui/linechart \ @@ -343,8 +345,6 @@ HEADERS += src/MG.h \ src/ui/QGCUDPLinkConfiguration.h \ src/ui/QGCSettingsWidget.h \ src/ui/uas/UASControlParameters.h \ - src/ui/mission/QGCMissionDoWidget.h \ - src/ui/mission/QGCMissionConditionWidget.h \ src/uas/QGCUASParamManager.h \ src/ui/map/QGCMapWidget.h \ src/ui/map/MAV2DIcon.h \ @@ -366,7 +366,12 @@ HEADERS += src/MG.h \ src/ui/QGCPluginHost.h \ src/ui/firmwareupdate/QGCPX4FirmwareUpdate.h \ src/ui/mission/QGCMissionOther.h \ - src/ui/mission/QGCMissionNavWaypoint.h + src/ui/mission/QGCMissionNavWaypoint.h \ + src/ui/mission/QGCMissionDoJump.h \ + src/ui/mission/QGCMissionConditionDelay.h \ + src/ui/mission/QGCMissionNavLoiterUnlim.h \ + src/ui/mission/QGCMissionNavLoiterTurns.h \ + src/ui/mission/QGCMissionNavLoiterTime.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 @@ -480,8 +485,6 @@ SOURCES += src/main.cc \ src/ui/QGCUDPLinkConfiguration.cc \ src/ui/QGCSettingsWidget.cc \ src/ui/uas/UASControlParameters.cpp \ - src/ui/mission/QGCMissionDoWidget.cc \ - src/ui/mission/QGCMissionConditionWidget.cc \ src/uas/QGCUASParamManager.cc \ src/ui/map/QGCMapWidget.cc \ src/ui/map/MAV2DIcon.cc \ @@ -500,7 +503,12 @@ SOURCES += src/main.cc \ src/ui/QGCPluginHost.cc \ src/ui/firmwareupdate/QGCPX4FirmwareUpdate.cc \ src/ui/mission/QGCMissionOther.cc \ - src/ui/mission/QGCMissionNavWaypoint.cc + src/ui/mission/QGCMissionNavWaypoint.cc \ + src/ui/mission/QGCMissionDoJump.cc \ + src/ui/mission/QGCMissionConditionDelay.cc \ + src/ui/mission/QGCMissionNavLoiterUnlim.cc \ + src/ui/mission/QGCMissionNavLoiterTurns.cc \ + src/ui/mission/QGCMissionNavLoiterTime.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 ebee017e9d6a7f0a7f4a12b4760cc35f3240c680..039515dfa667184be4ba106ab882ad56a5f5f7c3 100644 --- a/src/ui/WaypointEditableView.cc +++ b/src/ui/WaypointEditableView.cc @@ -19,13 +19,14 @@ #include "WaypointEditableView.h" #include "ui_WaypointEditableView.h" -#include "ui_QGCCustomWaypointAction.h" -#include "ui_QGCMissionDoWidget.h" -#include "ui_QGCMissionOther.h" + #include "QGCMissionNavWaypoint.h" -#include "QGCMissionDoWidget.h" -#include "QGCMissionConditionWidget.h" +#include "QGCMissionNavLoiterUnlim.h" +#include "QGCMissionNavLoiterTurns.h" +#include "QGCMissionNavLoiterTime.h" +#include "QGCMissionConditionDelay.h" +#include "QGCMissionDoJump.h" #include "QGCMissionOther.h" @@ -42,10 +43,13 @@ WaypointEditableView::WaypointEditableView(Waypoint* wp, QWidget* parent) : // CUSTOM COMMAND WIDGET QHBoxLayout *layout = new QHBoxLayout; layout->setSpacing(2); - layout->setContentsMargins(4, 4 ,4 ,4); + layout->setContentsMargins(4, 0 ,4 ,0); m_ui->customActionWidget->setLayout(layout); MissionNavWaypointWidget = NULL; + MissionNavLoiterUnlimWidget = NULL; + MissionNavLoiterTurnsWidget = NULL; + MissionNavLoiterTimeWidget = NULL; MissionDoJumpWidget = NULL; MissionConditionDelayWidget = NULL; MissionOtherWidget = NULL; @@ -72,10 +76,10 @@ WaypointEditableView::WaypointEditableView(Waypoint* wp, QWidget* parent) : m_ui->comboBox_frame->addItem("Mission",MAV_FRAME_MISSION); // Initialize view correctly - updateActionView(wp->getAction()); - - // Read values and set user interface + int actionID = wp->getAction(); + initializeActionView(actionID); updateValues(); + updateActionView(actionID); // Check for mission frame if (wp->getFrame() == MAV_FRAME_MISSION) @@ -120,9 +124,12 @@ void WaypointEditableView::changedAutoContinue(int state) } void WaypointEditableView::updateActionView(int action) -{ +{ //Hide all if(MissionNavWaypointWidget) MissionNavWaypointWidget->hide(); + if(MissionNavLoiterUnlimWidget) MissionNavLoiterUnlimWidget->hide(); + if(MissionNavLoiterTurnsWidget) MissionNavLoiterTurnsWidget->hide(); + if(MissionNavLoiterTimeWidget) MissionNavLoiterTimeWidget->hide(); if(MissionOtherWidget) MissionOtherWidget->hide(); if(MissionConditionDelayWidget) MissionConditionDelayWidget->hide(); if(MissionDoJumpWidget) MissionDoJumpWidget->hide(); @@ -131,21 +138,30 @@ void WaypointEditableView::updateActionView(int action) if (viewMode != QGC_WAYPOINTEDITABLEVIEW_MODE_DIRECT_EDITING) { switch(action) { - case MAV_CMD_NAV_TAKEOFF: - case MAV_CMD_NAV_LAND: - case MAV_CMD_NAV_RETURN_TO_LAUNCH: + case MAV_CMD_NAV_WAYPOINT: + if(MissionNavWaypointWidget) MissionNavWaypointWidget->show(); + break; case MAV_CMD_NAV_LOITER_UNLIM: + if(MissionNavLoiterUnlimWidget) MissionNavLoiterUnlimWidget->show(); + break; case MAV_CMD_NAV_LOITER_TURNS: + if(MissionNavLoiterTurnsWidget) MissionNavLoiterTurnsWidget->show(); + break; case MAV_CMD_NAV_LOITER_TIME: + if(MissionNavLoiterTimeWidget) MissionNavLoiterTimeWidget->show(); break; - case MAV_CMD_NAV_WAYPOINT: - if(MissionNavWaypointWidget) MissionNavWaypointWidget->show(); + case MAV_CMD_NAV_RETURN_TO_LAUNCH: + case MAV_CMD_NAV_LAND: + case MAV_CMD_NAV_TAKEOFF: + case MAV_CMD_CONDITION_DELAY: + if(MissionConditionDelayWidget) MissionConditionDelayWidget->show(); break; case MAV_CMD_DO_JUMP: if(MissionDoJumpWidget) MissionDoJumpWidget->show(); break; default: if(MissionOtherWidget) MissionOtherWidget->show(); + viewMode = QGC_WAYPOINTEDITABLEVIEW_MODE_DIRECT_EDITING; break; } } @@ -160,59 +176,83 @@ void WaypointEditableView::updateActionView(int action) */ void WaypointEditableView::changedAction(int index) { - MAV_FRAME cur_frame = (MAV_FRAME) m_ui->comboBox_frame->itemData(m_ui->comboBox_frame->currentIndex()).toUInt(); // set waypoint action - int actionIndex = m_ui->comboBox_action->itemData(index).toUInt(); - if (actionIndex < MAV_CMD_ENUM_END && actionIndex >= 0) { - MAV_CMD action = (MAV_CMD) actionIndex; + int actionID = m_ui->comboBox_action->itemData(index).toUInt(); + if (actionID == QVariant::Invalid || actionID == MAV_CMD_ENUM_END) + { + viewMode = QGC_WAYPOINTEDITABLEVIEW_MODE_DIRECT_EDITING; + } + else //(actionID < MAV_CMD_ENUM_END && actionID >= 0) + { + viewMode = QGC_WAYPOINTEDITABLEVIEW_MODE_DEFAULT; + MAV_CMD action = (MAV_CMD) actionID; wp->setAction(action); } + // change the view + initializeActionView(actionID); + updateValues(); + updateActionView(actionID); +} - // Expose ui based on action - // Change to mission frame - // if action is unknown - viewMode = QGC_WAYPOINTEDITABLEVIEW_MODE_DEFAULT; - switch(actionIndex) { - case MAV_CMD_NAV_TAKEOFF: - case MAV_CMD_NAV_LAND: - case MAV_CMD_NAV_RETURN_TO_LAUNCH: - case MAV_CMD_NAV_LOITER_UNLIM: - case MAV_CMD_NAV_LOITER_TURNS: - case MAV_CMD_NAV_LOITER_TIME: - updateActionView(actionIndex); - break; - +void WaypointEditableView::initializeActionView(int actionID) +{ + //initialize a new action-widget, if needed. + switch(actionID) { case MAV_CMD_NAV_WAYPOINT: if (!MissionNavWaypointWidget) { MissionNavWaypointWidget = new QGCMissionNavWaypoint(this); m_ui->customActionWidget->layout()->addWidget(MissionNavWaypointWidget); } - updateActionView(actionIndex); break; - - case MAV_CMD_DO_JUMP: + case MAV_CMD_NAV_LOITER_UNLIM: + if (!MissionNavLoiterUnlimWidget) + { + MissionNavLoiterUnlimWidget = new QGCMissionNavLoiterUnlim(this); + m_ui->customActionWidget->layout()->addWidget(MissionNavLoiterUnlimWidget); + } + break; + case MAV_CMD_NAV_LOITER_TURNS: + if (!MissionNavLoiterTurnsWidget) + { + MissionNavLoiterTurnsWidget = new QGCMissionNavLoiterTurns(this); + m_ui->customActionWidget->layout()->addWidget(MissionNavLoiterTurnsWidget); + } + break; + case MAV_CMD_NAV_LOITER_TIME: + if (!MissionNavLoiterTimeWidget) + { + MissionNavLoiterTimeWidget = new QGCMissionNavLoiterTime(this); + m_ui->customActionWidget->layout()->addWidget(MissionNavLoiterTimeWidget); + } + break; + case MAV_CMD_NAV_RETURN_TO_LAUNCH: + case MAV_CMD_NAV_LAND: + case MAV_CMD_NAV_TAKEOFF: + case MAV_CMD_CONDITION_DELAY: + if (!MissionConditionDelayWidget) + { + MissionConditionDelayWidget = new QGCMissionConditionDelay(this); + m_ui->customActionWidget->layout()->addWidget(MissionConditionDelayWidget); + } + break; + case MAV_CMD_DO_JUMP: if (!MissionDoJumpWidget) { - MissionDoJumpWidget = new QGCMissionDoWidget(this); + MissionDoJumpWidget = new QGCMissionDoJump(this); m_ui->customActionWidget->layout()->addWidget(MissionDoJumpWidget); } - updateActionView(actionIndex); break; case MAV_CMD_ENUM_END: default: - // Switch to mission frame - viewMode = QGC_WAYPOINTEDITABLEVIEW_MODE_DIRECT_EDITING; if (!MissionOtherWidget) { MissionOtherWidget = new QGCMissionOther(this); m_ui->customActionWidget->layout()->addWidget(MissionOtherWidget); } - updateActionView(actionIndex); break; } - updateValues(); } void WaypointEditableView::deleted(QObject* waypoint) @@ -299,7 +339,7 @@ void WaypointEditableView::updateValues() QDoubleSpinBox* spin = dynamic_cast(m_ui->customActionWidget->children().at(j)); if (spin) { - qDebug() << "DEACTIVATED SPINBOX #" << j; + //qDebug() << "DEACTIVATED SPINBOX #" << j; spin->blockSignals(true); } else @@ -334,32 +374,20 @@ void WaypointEditableView::updateValues() // Update action MAV_CMD action = wp->getAction(); int action_index = m_ui->comboBox_action->findData(action); - // Set to "Other" action if it was -1 - if (action_index == -1) - { - action_index = m_ui->comboBox_action->findData(MAV_CMD_ENUM_END); - } - - // Only update if changed if (m_ui->comboBox_action->currentIndex() != action_index) { - // If action is unknown, set direct editing mode - if (wp->getAction() < 0 || wp->getAction() > MAV_CMD_NAV_TAKEOFF)//FIXME condition should not depend on NAV_TAKEOFF + if (viewMode != QGC_WAYPOINTEDITABLEVIEW_MODE_DIRECT_EDITING) { - //changeViewMode(QGC_WAYPOINTEDITABLEVIEW_MODE_DIRECT_EDITING); - } - else - { - if (viewMode != QGC_WAYPOINTEDITABLEVIEW_MODE_DIRECT_EDITING) + // Set to "Other" action if it was -1 + if (action_index == -1) { - // Action ID known, update - m_ui->comboBox_action->setCurrentIndex(action_index); - updateActionView(action); + action_index = m_ui->comboBox_action->findData(MAV_CMD_ENUM_END); + viewMode = QGC_WAYPOINTEDITABLEVIEW_MODE_DIRECT_EDITING; } + m_ui->comboBox_action->setCurrentIndex(action_index); } } - emit commandBroadcast(wp->getAction()); emit frameBroadcast(wp->getFrame()); emit param1Broadcast(wp->getParam1()); diff --git a/src/ui/WaypointEditableView.h b/src/ui/WaypointEditableView.h index 1d7bf6d8a0d29ede009ce693ab461858e29c5855..425e62fbaccb28d4fba5fb2cb4dd1975ba7c3746 100644 --- a/src/ui/WaypointEditableView.h +++ b/src/ui/WaypointEditableView.h @@ -27,7 +27,7 @@ This file is part of the QGROUNDCONTROL project * @author Lorenz Meier * @author Benjamin Knecht * @author Petri Tanskanen - * + * @author Alex Trofimov */ #ifndef WAYPOINTEDITABLEVIEW_H @@ -46,12 +46,14 @@ namespace Ui { class WaypointEditableView; } -//class Ui_QGCCustomWaypointAction; -//class Ui_QGCMissionDoWidget; class QGCMissionNavWaypoint; -class QGCMissionDoWidget; -class QGCMissionConditionWidget; +class QGCMissionNavLoiterUnlim; +class QGCMissionNavLoiterTurns; +class QGCMissionNavLoiterTime; +class QGCMissionDoJump; +class QGCMissionConditionDelay; class QGCMissionOther; + class WaypointEditableView : public QWidget { Q_OBJECT @@ -72,6 +74,7 @@ public slots: void changedAutoContinue(int); void changedFrame(int state); void updateActionView(int action); + void initializeActionView(int action); void changedCurrent(int); void updateValues(void); @@ -90,13 +93,16 @@ protected slots: protected: virtual void changeEvent(QEvent *e); Waypoint* wp; - // Special widgets extendending the - // waypoint view to mission capabilities + QGC_WAYPOINTEDITABLEVIEW_MODE viewMode; + // Widgets for every mission element QGCMissionNavWaypoint* MissionNavWaypointWidget; - QGCMissionDoWidget* MissionDoJumpWidget; - QGCMissionConditionWidget* MissionConditionDelayWidget; + QGCMissionNavLoiterUnlim* MissionNavLoiterUnlimWidget; + QGCMissionNavLoiterTurns* MissionNavLoiterTurnsWidget; + QGCMissionNavLoiterTime* MissionNavLoiterTimeWidget; + QGCMissionDoJump* MissionDoJumpWidget; + QGCMissionConditionDelay* MissionConditionDelayWidget; QGCMissionOther* MissionOtherWidget; - QGC_WAYPOINTEDITABLEVIEW_MODE viewMode; + private: Ui::WaypointEditableView *m_ui; diff --git a/src/ui/mission/QGCCustomWaypointAction.ui b/src/ui/mission/QGCCustomWaypointAction.ui deleted file mode 100644 index f890e3319289c2b1dff08aff5fa70508844189f9..0000000000000000000000000000000000000000 --- a/src/ui/mission/QGCCustomWaypointAction.ui +++ /dev/null @@ -1,164 +0,0 @@ - - - QGCCustomWaypointAction - - - - 0 - 0 - 1228 - 27 - - - - Form - - - - 5 - - - 0 - - - - - MAV_CMD id - - - MAV_CMD id - - - CMD - - - 0 - - - 255 - - - 0 - - - - - - - P1 - - - 7 - - - -2147483647.000000000000000 - - - 2147483647.000000000000000 - - - - - - - - - - P2 - - - 7 - - - -2147483647.000000000000000 - - - 2147483647.000000000000000 - - - - - - - P3 - - - 7 - - - -2147483647.000000000000000 - - - 2147483647.000000000000000 - - - - - - - P4 - - - 7 - - - -2147483647.000000000000000 - - - 2147483647.000000000000000 - - - - - - - P5 - - - 7 - - - -2147483647.000000000000000 - - - 2147483647.000000000000000 - - - - - - - P6 - - - 7 - - - -2147483647.000000000000000 - - - 2147483647.000000000000000 - - - - - - - P7 - - - 7 - - - -2147483647.000000000000000 - - - 2147483647.000000000000000 - - - - - - - - diff --git a/src/ui/mission/QGCMissionConditionDelay.cc b/src/ui/mission/QGCMissionConditionDelay.cc new file mode 100644 index 0000000000000000000000000000000000000000..2e1908ac2ce0481f934a15b4ec513156b64d0fd9 --- /dev/null +++ b/src/ui/mission/QGCMissionConditionDelay.cc @@ -0,0 +1,22 @@ +#include "QGCMissionConditionDelay.h" +#include "ui_QGCMissionConditionDelay.h" +#include "WaypointEditableView.h" + +QGCMissionConditionDelay::QGCMissionConditionDelay(WaypointEditableView* WEV) : + QWidget(WEV), + ui(new Ui::QGCMissionConditionDelay) +{ + ui->setupUi(this); + this->WEV = WEV; + + //Using UI to change WP: + connect(this->ui->param1SpinBox, SIGNAL(valueChanged(double)),WEV,SLOT(changedParam1(double))); + + //Reading WP to update UI: + connect(WEV,SIGNAL(param1Broadcast(double)),this->ui->param1SpinBox,SLOT(setValue(double))); +} + +QGCMissionConditionDelay::~QGCMissionConditionDelay() +{ + delete ui; +} diff --git a/src/ui/mission/QGCMissionConditionDelay.h b/src/ui/mission/QGCMissionConditionDelay.h new file mode 100644 index 0000000000000000000000000000000000000000..b9d2af900965b88b73d130b822e8453c49eef7f0 --- /dev/null +++ b/src/ui/mission/QGCMissionConditionDelay.h @@ -0,0 +1,26 @@ +#ifndef QGCMISSIONCONDITIONDELAY_H +#define QGCMISSIONCONDITIONDELAY_H + +#include +#include "WaypointEditableView.h" + +namespace Ui { + class QGCMissionConditionDelay; +} + +class QGCMissionConditionDelay : public QWidget +{ + Q_OBJECT + +public: + explicit QGCMissionConditionDelay(WaypointEditableView* WEV); + ~QGCMissionConditionDelay(); + +protected: + WaypointEditableView* WEV; + +private: + Ui::QGCMissionConditionDelay *ui; +}; + +#endif // QGCMISSIONCONDITIONDELAY_H diff --git a/src/ui/mission/QGCMissionConditionDelay.ui b/src/ui/mission/QGCMissionConditionDelay.ui new file mode 100644 index 0000000000000000000000000000000000000000..82524b7a5f1e4077cd9da4fcacdcb4e69bdc7ec5 --- /dev/null +++ b/src/ui/mission/QGCMissionConditionDelay.ui @@ -0,0 +1,91 @@ + + + QGCMissionConditionDelay + + + + 0 + 0 + 448 + 37 + + + + + 0 + 0 + + + + + 200 + 0 + + + + Form + + + + + + + 5 + + + 0 + + + + + + 0 + 0 + + + + Qt::WheelFocus + + + Delay duration + + + Delay duration + + + false + + + true + + + true + + + false + + + Duration: + + + s + + + 2 + + + 0.000000000000000 + + + 100000.000000000000000 + + + 1.000000000000000 + + + + + + + + diff --git a/src/ui/mission/QGCMissionConditionWidget.cc b/src/ui/mission/QGCMissionConditionWidget.cc deleted file mode 100644 index f0c9f25e0679e8a4f1541367b3bba960f6532678..0000000000000000000000000000000000000000 --- a/src/ui/mission/QGCMissionConditionWidget.cc +++ /dev/null @@ -1,14 +0,0 @@ -#include "QGCMissionConditionWidget.h" -#include "ui_QGCMissionConditionWidget.h" - -QGCMissionConditionWidget::QGCMissionConditionWidget(QWidget *parent) : - QWidget(parent), - ui(new Ui::QGCMissionConditionWidget) -{ - ui->setupUi(this); -} - -QGCMissionConditionWidget::~QGCMissionConditionWidget() -{ - delete ui; -} diff --git a/src/ui/mission/QGCMissionConditionWidget.h b/src/ui/mission/QGCMissionConditionWidget.h deleted file mode 100644 index c65c5515702f56d9d31adbbe21f510573022e049..0000000000000000000000000000000000000000 --- a/src/ui/mission/QGCMissionConditionWidget.h +++ /dev/null @@ -1,23 +0,0 @@ -#ifndef QGCMISSIONCONDITIONWIDGET_H -#define QGCMISSIONCONDITIONWIDGET_H - -#include - -namespace Ui -{ -class QGCMissionConditionWidget; -} - -class QGCMissionConditionWidget : public QWidget -{ - Q_OBJECT - -public: - explicit QGCMissionConditionWidget(QWidget *parent = 0); - ~QGCMissionConditionWidget(); - -private: - Ui::QGCMissionConditionWidget *ui; -}; - -#endif // QGCMISSIONCONDITIONWIDGET_H diff --git a/src/ui/mission/QGCMissionConditionWidget.ui b/src/ui/mission/QGCMissionConditionWidget.ui deleted file mode 100644 index e02caba49606a3f51fbf10d61ee48876e9e7eadf..0000000000000000000000000000000000000000 --- a/src/ui/mission/QGCMissionConditionWidget.ui +++ /dev/null @@ -1,145 +0,0 @@ - - - QGCMissionConditionWidget - - - - 0 - 0 - 1260 - 31 - - - - Form - - - - 4 - - - 0 - - - - - delay: - - - s - - - 50000.000000000000000 - - - 5.000000000000000 - - - - - - - rate: - - - m/s - - - 200.000000000000000 - - - 0.500000000000000 - - - - - - - finish altitude: - - - m - - - -100.000000000000000 - - - 1000000.000000000000000 - - - - - - - distance to next wp: - - - m/s - - - 50000.000000000000000 - - - - - - - heading: - - - ° - - - - - - - turn rate: - - - °/s - - - 1000.000000000000000 - - - 15.000000000000000 - - - - - - - 1 - - - - left/counter-clockwise - - - - - right/clockwise - - - - - - - - - compass direction - - - - - offset from current heading - - - - - - - - - diff --git a/src/ui/mission/QGCMissionDoJump.cc b/src/ui/mission/QGCMissionDoJump.cc new file mode 100644 index 0000000000000000000000000000000000000000..e6080938dcf68e19027b6226200e3bcddbb22a53 --- /dev/null +++ b/src/ui/mission/QGCMissionDoJump.cc @@ -0,0 +1,24 @@ +#include "QGCMissionDoJump.h" +#include "ui_QGCMissionDoJump.h" +#include "WaypointEditableView.h" + +QGCMissionDoJump::QGCMissionDoJump(WaypointEditableView* WEV) : + QWidget(WEV), + ui(new Ui::QGCMissionDoJump) +{ + ui->setupUi(this); + this->WEV = WEV; + + //Using UI to change WP: + connect(this->ui->param1SpinBox, SIGNAL(valueChanged(double)),WEV,SLOT(changedParam1(double))); + connect(this->ui->param2SpinBox, SIGNAL(valueChanged(double)),WEV,SLOT(changedParam2(double))); + + //Reading WP to update UI: + connect(WEV,SIGNAL(param1Broadcast(double)),this->ui->param1SpinBox,SLOT(setValue(double))); + connect(WEV,SIGNAL(param2Broadcast(double)),this->ui->param2SpinBox,SLOT(setValue(double))); +} + +QGCMissionDoJump::~QGCMissionDoJump() +{ + delete ui; +} diff --git a/src/ui/mission/QGCMissionDoJump.h b/src/ui/mission/QGCMissionDoJump.h new file mode 100644 index 0000000000000000000000000000000000000000..d5d602946a78fae265129caf4324156118c563d2 --- /dev/null +++ b/src/ui/mission/QGCMissionDoJump.h @@ -0,0 +1,26 @@ +#ifndef QGCMISSIONDOJUMP_H +#define QGCMISSIONDOJUMP_H + +#include +#include "WaypointEditableView.h" + +namespace Ui { + class QGCMissionDoJump; +} + +class QGCMissionDoJump : public QWidget +{ + Q_OBJECT + +public: + explicit QGCMissionDoJump(WaypointEditableView* WEV); + ~QGCMissionDoJump(); + +protected: + WaypointEditableView* WEV; + +private: + Ui::QGCMissionDoJump *ui; +}; + +#endif // QGCMISSIONDOJUMP_H diff --git a/src/ui/mission/QGCMissionDoJump.ui b/src/ui/mission/QGCMissionDoJump.ui new file mode 100644 index 0000000000000000000000000000000000000000..088bf08c7a88baad444aa1c7cbce31cf575eb79a --- /dev/null +++ b/src/ui/mission/QGCMissionDoJump.ui @@ -0,0 +1,134 @@ + + + QGCMissionDoJump + + + + 0 + 0 + 448 + 37 + + + + + 0 + 0 + + + + + 200 + 0 + + + + Form + + + + + + + 5 + + + 0 + + + + + + 0 + 0 + + + + Qt::WheelFocus + + + Mission element ID to jump to + + + Mission element ID to jump to + + + false + + + true + + + true + + + false + + + Jump to index + + + + + + 0 + + + 0.000000000000000 + + + 10000.000000000000000 + + + 1.000000000000000 + + + + + + + + 0 + 0 + + + + Qt::WheelFocus + + + Maximal number of jumps + + + Maximal number of jumps + + + false + + + + + + time(s) + + + 0 + + + 0.000000000000000 + + + 10000.000000000000000 + + + 1.000000000000000 + + + 1.000000000000000 + + + + + + + + diff --git a/src/ui/mission/QGCMissionDoWidget.cc b/src/ui/mission/QGCMissionDoWidget.cc deleted file mode 100644 index a309109357af471fe24dcc85c712168a2d80c629..0000000000000000000000000000000000000000 --- a/src/ui/mission/QGCMissionDoWidget.cc +++ /dev/null @@ -1,14 +0,0 @@ -#include "QGCMissionDoWidget.h" -#include "ui_QGCMissionDoWidget.h" - -QGCMissionDoWidget::QGCMissionDoWidget(QWidget *parent) : - QWidget(parent), - ui(new Ui::QGCMissionDoWidget) -{ - ui->setupUi(this); -} - -QGCMissionDoWidget::~QGCMissionDoWidget() -{ - delete ui; -} diff --git a/src/ui/mission/QGCMissionDoWidget.h b/src/ui/mission/QGCMissionDoWidget.h deleted file mode 100644 index 9b00b8ebfa4b1a4862e04afbcdba6bfb24ee7d02..0000000000000000000000000000000000000000 --- a/src/ui/mission/QGCMissionDoWidget.h +++ /dev/null @@ -1,23 +0,0 @@ -#ifndef QGCMISSIONDOWIDGET_H -#define QGCMISSIONDOWIDGET_H - -#include - -namespace Ui -{ -class QGCMissionDoWidget; -} - -class QGCMissionDoWidget : public QWidget -{ - Q_OBJECT - -public: - explicit QGCMissionDoWidget(QWidget *parent = 0); - ~QGCMissionDoWidget(); - -private: - Ui::QGCMissionDoWidget *ui; -}; - -#endif // QGCMISSIONDOWIDGET_H diff --git a/src/ui/mission/QGCMissionDoWidget.ui b/src/ui/mission/QGCMissionDoWidget.ui deleted file mode 100644 index c17cbccc5efa2025447196894122938ec07f8dc2..0000000000000000000000000000000000000000 --- a/src/ui/mission/QGCMissionDoWidget.ui +++ /dev/null @@ -1,56 +0,0 @@ - - - QGCMissionDoWidget - - - - 0 - 0 - 632 - 27 - - - - Form - - - - 5 - - - 0 - - - - - - - - - - - list index to jump to: - - - 5000 - - - - - - - times - - - repeat - - - 1000 - - - - - - - - diff --git a/src/ui/mission/QGCMissionNavLoiterTime.cc b/src/ui/mission/QGCMissionNavLoiterTime.cc new file mode 100644 index 0000000000000000000000000000000000000000..e7c7db01b37e0df9274e162795815f01e88a0c1f --- /dev/null +++ b/src/ui/mission/QGCMissionNavLoiterTime.cc @@ -0,0 +1,68 @@ +#include "QGCMissionNavLoiterTime.h" +#include "ui_QGCMissionNavLoiterTime.h" +#include "WaypointEditableView.h" + +QGCMissionNavLoiterTime::QGCMissionNavLoiterTime(WaypointEditableView* WEV) : + QWidget(WEV), + ui(new Ui::QGCMissionNavLoiterTime) +{ + ui->setupUi(this); + this->WEV = WEV; + + //Using UI to change WP: + connect(this->ui->timeSpinBox, SIGNAL(valueChanged(double)),WEV,SLOT(changedParam1(double))); + //connect(this->ui->acceptanceSpinBox, SIGNAL(valueChanged(double)),WEV,SLOT(changedParam2(double))); + connect(this->ui->radSpinBox, 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->timeSpinBox,SLOT(setValue(double))); + //connect(WEV,SIGNAL(param2Broadcast(double)),this->ui->acceptanceSpinBox,SLOT(setValue(double))); + connect(WEV,SIGNAL(param3Broadcast(double)),this->ui->radSpinBox,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 QGCMissionNavLoiterTime::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; + } +} + +QGCMissionNavLoiterTime::~QGCMissionNavLoiterTime() +{ + delete ui; +} diff --git a/src/ui/mission/QGCMissionNavLoiterTime.h b/src/ui/mission/QGCMissionNavLoiterTime.h new file mode 100644 index 0000000000000000000000000000000000000000..9f8619698cd29e6553aaae238e8faaf18694dd29 --- /dev/null +++ b/src/ui/mission/QGCMissionNavLoiterTime.h @@ -0,0 +1,29 @@ +#ifndef QGCMISSIONNAVLOITERTIME_H +#define QGCMISSIONNAVLOITERTIME_H + +#include +#include "WaypointEditableView.h" + +namespace Ui { + class QGCMissionNavLoiterTime; +} + +class QGCMissionNavLoiterTime : public QWidget +{ + Q_OBJECT + +public: + explicit QGCMissionNavLoiterTime(WaypointEditableView* WEV); + ~QGCMissionNavLoiterTime(); + +public slots: + void updateFrame(MAV_FRAME); + +protected: + WaypointEditableView* WEV; + +private: + Ui::QGCMissionNavLoiterTime *ui; +}; + +#endif // QGCMISSIONNAVLOITERTIME_H diff --git a/src/ui/mission/QGCMissionNavLoiterTime.ui b/src/ui/mission/QGCMissionNavLoiterTime.ui new file mode 100644 index 0000000000000000000000000000000000000000..9d456cef2be7370475f16d5c1aff284f7e91af5d --- /dev/null +++ b/src/ui/mission/QGCMissionNavLoiterTime.ui @@ -0,0 +1,384 @@ + + + QGCMissionNavLoiterTime + + + + 0 + 0 + 2208 + 37 + + + + + 0 + 0 + + + + + 200 + 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 + + + + Loiter Radius. If negative loiter counter-clockwise + + + Loiter Radius. If negative loiter counter-clockwise + + + false + + + m + + + -1000000.000000000000000 + + + 1000000.000000000000000 + + + 0.000000000000000 + + + + + + + + 0 + 0 + + + + Time to loiter around the mission point + + + Time to loiter around the mission point + + + false + + + s + + + 2 + + + 0.000000000000000 + + + 1000000.000000000000000 + + + 0.000000000000000 + + + + + + + + diff --git a/src/ui/mission/QGCMissionNavLoiterTurns.cc b/src/ui/mission/QGCMissionNavLoiterTurns.cc new file mode 100644 index 0000000000000000000000000000000000000000..755ae784c81df12034d6a89646d09c15b4da4ef8 --- /dev/null +++ b/src/ui/mission/QGCMissionNavLoiterTurns.cc @@ -0,0 +1,68 @@ +#include "QGCMissionNavLoiterTurns.h" +#include "ui_QGCMissionNavLoiterTurns.h" +#include "WaypointEditableView.h" + +QGCMissionNavLoiterTurns::QGCMissionNavLoiterTurns(WaypointEditableView* WEV) : + QWidget(WEV), + ui(new Ui::QGCMissionNavLoiterTurns) +{ + ui->setupUi(this); + this->WEV = WEV; + + //Using UI to change WP: + connect(this->ui->turnsSpinBox, SIGNAL(valueChanged(double)),WEV,SLOT(changedParam1(double))); + //connect(this->ui->acceptanceSpinBox, SIGNAL(valueChanged(double)),WEV,SLOT(changedParam2(double))); + connect(this->ui->radSpinBox, 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->turnsSpinBox,SLOT(setValue(double))); + //connect(WEV,SIGNAL(param2Broadcast(double)),this->ui->acceptanceSpinBox,SLOT(setValue(double))); + connect(WEV,SIGNAL(param3Broadcast(double)),this->ui->radSpinBox,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 QGCMissionNavLoiterTurns::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; + } +} + +QGCMissionNavLoiterTurns::~QGCMissionNavLoiterTurns() +{ + delete ui; +} diff --git a/src/ui/mission/QGCMissionNavLoiterTurns.h b/src/ui/mission/QGCMissionNavLoiterTurns.h new file mode 100644 index 0000000000000000000000000000000000000000..038ebad6ad3fd625d79558c6c3718fc6293032d4 --- /dev/null +++ b/src/ui/mission/QGCMissionNavLoiterTurns.h @@ -0,0 +1,29 @@ +#ifndef QGCMISSIONNAVLOITERTURNS_H +#define QGCMISSIONNAVLOITERTURNS_H + +#include +#include "WaypointEditableView.h" + +namespace Ui { + class QGCMissionNavLoiterTurns; +} + +class QGCMissionNavLoiterTurns : public QWidget +{ + Q_OBJECT + +public: + explicit QGCMissionNavLoiterTurns(WaypointEditableView* WEV); + ~QGCMissionNavLoiterTurns(); + +public slots: + void updateFrame(MAV_FRAME); + +protected: + WaypointEditableView* WEV; + +private: + Ui::QGCMissionNavLoiterTurns *ui; +}; + +#endif // QGCMISSIONNAVLOITERTURNS_H diff --git a/src/ui/mission/QGCMissionNavLoiterTurns.ui b/src/ui/mission/QGCMissionNavLoiterTurns.ui new file mode 100644 index 0000000000000000000000000000000000000000..d4587a00d0151528fa04d34a3667658c97336ba5 --- /dev/null +++ b/src/ui/mission/QGCMissionNavLoiterTurns.ui @@ -0,0 +1,384 @@ + + + QGCMissionNavLoiterTurns + + + + 0 + 0 + 2208 + 37 + + + + + 0 + 0 + + + + + 200 + 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 + + + + Loiter Radius. If negative loiter counter-clockwise + + + Loiter Radius. If negative loiter counter-clockwise + + + false + + + m + + + -1000000.000000000000000 + + + 1000000.000000000000000 + + + 0.000000000000000 + + + + + + + + 0 + 0 + + + + Number of turns around the loiter point + + + Number of turns around the loiter point + + + false + + + turns + + + 0 + + + 0.000000000000000 + + + 1000000.000000000000000 + + + 0.000000000000000 + + + + + + + + diff --git a/src/ui/mission/QGCMissionNavLoiterUnlim.cc b/src/ui/mission/QGCMissionNavLoiterUnlim.cc new file mode 100644 index 0000000000000000000000000000000000000000..8e33e27d08aeef6db196b4442777a7aa71868853 --- /dev/null +++ b/src/ui/mission/QGCMissionNavLoiterUnlim.cc @@ -0,0 +1,68 @@ +#include "QGCMissionNavLoiterUnlim.h" +#include "ui_QGCMissionNavLoiterUnlim.h" +#include "WaypointEditableView.h" + +QGCMissionNavLoiterUnlim::QGCMissionNavLoiterUnlim(WaypointEditableView* WEV) : + QWidget(WEV), + ui(new Ui::QGCMissionNavLoiterUnlim) +{ + 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->radSpinBox, 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->radSpinBox,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 QGCMissionNavLoiterUnlim::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; + } +} + +QGCMissionNavLoiterUnlim::~QGCMissionNavLoiterUnlim() +{ + delete ui; +} diff --git a/src/ui/mission/QGCMissionNavLoiterUnlim.h b/src/ui/mission/QGCMissionNavLoiterUnlim.h new file mode 100644 index 0000000000000000000000000000000000000000..954a75292aae3574ad9f1c4fbd938d685ddb5ec1 --- /dev/null +++ b/src/ui/mission/QGCMissionNavLoiterUnlim.h @@ -0,0 +1,29 @@ +#ifndef QGCMISSIONNAVLOITERUNLIM_H +#define QGCMISSIONNAVLOITERUNLIM_H + +#include +#include "WaypointEditableView.h" + +namespace Ui { + class QGCMissionNavLoiterUnlim; +} + +class QGCMissionNavLoiterUnlim : public QWidget +{ + Q_OBJECT + +public: + explicit QGCMissionNavLoiterUnlim(WaypointEditableView* WEV); + ~QGCMissionNavLoiterUnlim(); + +public slots: + void updateFrame(MAV_FRAME); + +protected: + WaypointEditableView* WEV; + +private: + Ui::QGCMissionNavLoiterUnlim *ui; +}; + +#endif // QGCMISSIONNAVLOITERUNLIM_H diff --git a/src/ui/mission/QGCMissionNavLoiterUnlim.ui b/src/ui/mission/QGCMissionNavLoiterUnlim.ui new file mode 100644 index 0000000000000000000000000000000000000000..c41381d455d7a07f2672d3386814f625d5a4c96d --- /dev/null +++ b/src/ui/mission/QGCMissionNavLoiterUnlim.ui @@ -0,0 +1,350 @@ + + + QGCMissionNavLoiterUnlim + + + + 0 + 0 + 2208 + 37 + + + + + 0 + 0 + + + + + 200 + 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 + + + + Loiter Radius. If negative loiter counter-clockwise + + + Loiter Radius. If negative loiter counter-clockwise + + + false + + + m + + + -1000000.000000000000000 + + + 1000000.000000000000000 + + + 0.000000000000000 + + + + + + + + diff --git a/src/ui/mission/QGCMissionNavWaypoint.h b/src/ui/mission/QGCMissionNavWaypoint.h index b4454908d43024086ea1ddcffe7b3625728e82b7..c4c9d1531db054138766e733c3d6030cd310e105 100644 --- a/src/ui/mission/QGCMissionNavWaypoint.h +++ b/src/ui/mission/QGCMissionNavWaypoint.h @@ -26,7 +26,4 @@ private: Ui::QGCMissionNavWaypoint *ui; }; - - - #endif // QGCMISSIONNAVWAYPOINT_H diff --git a/src/ui/mission/QGCMissionNavWaypoint.ui b/src/ui/mission/QGCMissionNavWaypoint.ui index c4d3a29c0158e09923e5855f8f4e4b0da1d59ff6..5c502e12bc20c0c9fe7ca32eb8a4fc74e2b9cc7e 100644 --- a/src/ui/mission/QGCMissionNavWaypoint.ui +++ b/src/ui/mission/QGCMissionNavWaypoint.ui @@ -61,6 +61,9 @@ true + + false + N @@ -95,6 +98,9 @@ Position Y/Longitude coordinate + + false + E @@ -132,6 +138,9 @@ + + false + D @@ -166,6 +175,9 @@ Latitude in degrees + + false + lat @@ -203,6 +215,9 @@ Longitude in degrees + + false + lon @@ -237,6 +252,9 @@ Altitude in meters + + false + alt @@ -274,6 +292,9 @@ true + + false + @@ -306,6 +327,9 @@ where to accept this waypoint as reached Uncertainty radius in meters where to accept this waypoint as reached + + false + m @@ -328,6 +352,9 @@ where to accept this waypoint as reached Time to stay/loiter at this position before advancing + + false + s diff --git a/src/ui/mission/QGCMissionOther.h b/src/ui/mission/QGCMissionOther.h index eddda4887fa84c9f737395be0cfe8864d975425b..29da3ac18950dccd40d927a1e955440fbc81b906 100644 --- a/src/ui/mission/QGCMissionOther.h +++ b/src/ui/mission/QGCMissionOther.h @@ -14,13 +14,13 @@ class QGCMissionOther : public QWidget public: explicit QGCMissionOther(WaypointEditableView* WEV); - ~QGCMissionOther(); - Ui::QGCMissionOther *ui; + ~QGCMissionOther(); protected: WaypointEditableView* WEV; private: + Ui::QGCMissionOther *ui; }; #endif // QGCMISSIONOTHER_H diff --git a/src/ui/mission/QGCMissionOther.ui b/src/ui/mission/QGCMissionOther.ui index 1b7c0276d987937517b35d1facce900e12d5cd66..7ef0ea209d7daf0e1166bf3ee27c18dd2974db9c 100644 --- a/src/ui/mission/QGCMissionOther.ui +++ b/src/ui/mission/QGCMissionOther.ui @@ -28,6 +28,9 @@ MAV_CMD id + + false + CMD @@ -44,6 +47,9 @@ + + false + P1 @@ -63,6 +69,9 @@ + + false + P2 @@ -79,6 +88,9 @@ + + false + P3 @@ -95,6 +107,9 @@ + + false + P4 @@ -111,6 +126,9 @@ + + false + P5 @@ -127,6 +145,9 @@ + + false + P6 @@ -143,6 +164,9 @@ + + false + P7