Commit 838e5e78 authored by pixhawk's avatar pixhawk

Remake of "editable" mission elements is now complete and usable. Missing...

Remake of "editable" mission elements is now complete and usable. Missing widgets for Takeoff and Land will be added soon.
parent 38275d4f
...@@ -224,12 +224,9 @@ FORMS += src/ui/MainWindow.ui \ ...@@ -224,12 +224,9 @@ FORMS += src/ui/MainWindow.ui \
src/ui/designer/QGCCommandButton.ui \ src/ui/designer/QGCCommandButton.ui \
src/ui/QGCMAVLinkLogPlayer.ui \ src/ui/QGCMAVLinkLogPlayer.ui \
src/ui/QGCWaypointListMulti.ui \ src/ui/QGCWaypointListMulti.ui \
src/ui/mission/QGCCustomWaypointAction.ui \
src/ui/QGCUDPLinkConfiguration.ui \ src/ui/QGCUDPLinkConfiguration.ui \
src/ui/QGCSettingsWidget.ui \ src/ui/QGCSettingsWidget.ui \
src/ui/UASControlParameters.ui \ src/ui/UASControlParameters.ui \
src/ui/mission/QGCMissionDoWidget.ui \
src/ui/mission/QGCMissionConditionWidget.ui \
src/ui/map/QGCMapTool.ui \ src/ui/map/QGCMapTool.ui \
src/ui/map/QGCMapToolBar.ui \ src/ui/map/QGCMapToolBar.ui \
src/ui/QGCMAVLinkInspector.ui \ src/ui/QGCMAVLinkInspector.ui \
...@@ -241,7 +238,12 @@ FORMS += src/ui/MainWindow.ui \ ...@@ -241,7 +238,12 @@ FORMS += src/ui/MainWindow.ui \
src/ui/QGCPluginHost.ui \ src/ui/QGCPluginHost.ui \
src/ui/firmwareupdate/QGCPX4FirmwareUpdate.ui \ src/ui/firmwareupdate/QGCPX4FirmwareUpdate.ui \
src/ui/mission/QGCMissionOther.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 \ INCLUDEPATH += src \
src/ui \ src/ui \
src/ui/linechart \ src/ui/linechart \
...@@ -343,8 +345,6 @@ HEADERS += src/MG.h \ ...@@ -343,8 +345,6 @@ HEADERS += src/MG.h \
src/ui/QGCUDPLinkConfiguration.h \ src/ui/QGCUDPLinkConfiguration.h \
src/ui/QGCSettingsWidget.h \ src/ui/QGCSettingsWidget.h \
src/ui/uas/UASControlParameters.h \ src/ui/uas/UASControlParameters.h \
src/ui/mission/QGCMissionDoWidget.h \
src/ui/mission/QGCMissionConditionWidget.h \
src/uas/QGCUASParamManager.h \ src/uas/QGCUASParamManager.h \
src/ui/map/QGCMapWidget.h \ src/ui/map/QGCMapWidget.h \
src/ui/map/MAV2DIcon.h \ src/ui/map/MAV2DIcon.h \
...@@ -366,7 +366,12 @@ HEADERS += src/MG.h \ ...@@ -366,7 +366,12 @@ HEADERS += src/MG.h \
src/ui/QGCPluginHost.h \ src/ui/QGCPluginHost.h \
src/ui/firmwareupdate/QGCPX4FirmwareUpdate.h \ src/ui/firmwareupdate/QGCPX4FirmwareUpdate.h \
src/ui/mission/QGCMissionOther.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 # 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 macx|macx-g++|macx-g++42|win32-msvc2008|win32-msvc2010::HEADERS += src/ui/map3D/QGCGoogleEarthView.h
...@@ -480,8 +485,6 @@ SOURCES += src/main.cc \ ...@@ -480,8 +485,6 @@ SOURCES += src/main.cc \
src/ui/QGCUDPLinkConfiguration.cc \ src/ui/QGCUDPLinkConfiguration.cc \
src/ui/QGCSettingsWidget.cc \ src/ui/QGCSettingsWidget.cc \
src/ui/uas/UASControlParameters.cpp \ src/ui/uas/UASControlParameters.cpp \
src/ui/mission/QGCMissionDoWidget.cc \
src/ui/mission/QGCMissionConditionWidget.cc \
src/uas/QGCUASParamManager.cc \ src/uas/QGCUASParamManager.cc \
src/ui/map/QGCMapWidget.cc \ src/ui/map/QGCMapWidget.cc \
src/ui/map/MAV2DIcon.cc \ src/ui/map/MAV2DIcon.cc \
...@@ -500,7 +503,12 @@ SOURCES += src/main.cc \ ...@@ -500,7 +503,12 @@ SOURCES += src/main.cc \
src/ui/QGCPluginHost.cc \ src/ui/QGCPluginHost.cc \
src/ui/firmwareupdate/QGCPX4FirmwareUpdate.cc \ src/ui/firmwareupdate/QGCPX4FirmwareUpdate.cc \
src/ui/mission/QGCMissionOther.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 # 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 macx|macx-g++|macx-g++42|win32-msvc2008|win32-msvc2010::SOURCES += src/ui/map3D/QGCGoogleEarthView.cc
......
...@@ -19,13 +19,14 @@ ...@@ -19,13 +19,14 @@
#include "WaypointEditableView.h" #include "WaypointEditableView.h"
#include "ui_WaypointEditableView.h" #include "ui_WaypointEditableView.h"
#include "ui_QGCCustomWaypointAction.h"
#include "ui_QGCMissionDoWidget.h"
#include "ui_QGCMissionOther.h"
#include "QGCMissionNavWaypoint.h" #include "QGCMissionNavWaypoint.h"
#include "QGCMissionDoWidget.h" #include "QGCMissionNavLoiterUnlim.h"
#include "QGCMissionConditionWidget.h" #include "QGCMissionNavLoiterTurns.h"
#include "QGCMissionNavLoiterTime.h"
#include "QGCMissionConditionDelay.h"
#include "QGCMissionDoJump.h"
#include "QGCMissionOther.h" #include "QGCMissionOther.h"
...@@ -42,10 +43,13 @@ WaypointEditableView::WaypointEditableView(Waypoint* wp, QWidget* parent) : ...@@ -42,10 +43,13 @@ WaypointEditableView::WaypointEditableView(Waypoint* wp, QWidget* parent) :
// CUSTOM COMMAND WIDGET // CUSTOM COMMAND WIDGET
QHBoxLayout *layout = new QHBoxLayout; QHBoxLayout *layout = new QHBoxLayout;
layout->setSpacing(2); layout->setSpacing(2);
layout->setContentsMargins(4, 4 ,4 ,4); layout->setContentsMargins(4, 0 ,4 ,0);
m_ui->customActionWidget->setLayout(layout); m_ui->customActionWidget->setLayout(layout);
MissionNavWaypointWidget = NULL; MissionNavWaypointWidget = NULL;
MissionNavLoiterUnlimWidget = NULL;
MissionNavLoiterTurnsWidget = NULL;
MissionNavLoiterTimeWidget = NULL;
MissionDoJumpWidget = NULL; MissionDoJumpWidget = NULL;
MissionConditionDelayWidget = NULL; MissionConditionDelayWidget = NULL;
MissionOtherWidget = NULL; MissionOtherWidget = NULL;
...@@ -72,10 +76,10 @@ WaypointEditableView::WaypointEditableView(Waypoint* wp, QWidget* parent) : ...@@ -72,10 +76,10 @@ WaypointEditableView::WaypointEditableView(Waypoint* wp, QWidget* parent) :
m_ui->comboBox_frame->addItem("Mission",MAV_FRAME_MISSION); m_ui->comboBox_frame->addItem("Mission",MAV_FRAME_MISSION);
// Initialize view correctly // Initialize view correctly
updateActionView(wp->getAction()); int actionID = wp->getAction();
initializeActionView(actionID);
// Read values and set user interface
updateValues(); updateValues();
updateActionView(actionID);
// Check for mission frame // Check for mission frame
if (wp->getFrame() == MAV_FRAME_MISSION) if (wp->getFrame() == MAV_FRAME_MISSION)
...@@ -120,9 +124,12 @@ void WaypointEditableView::changedAutoContinue(int state) ...@@ -120,9 +124,12 @@ void WaypointEditableView::changedAutoContinue(int state)
} }
void WaypointEditableView::updateActionView(int action) void WaypointEditableView::updateActionView(int action)
{ {
//Hide all //Hide all
if(MissionNavWaypointWidget) MissionNavWaypointWidget->hide(); if(MissionNavWaypointWidget) MissionNavWaypointWidget->hide();
if(MissionNavLoiterUnlimWidget) MissionNavLoiterUnlimWidget->hide();
if(MissionNavLoiterTurnsWidget) MissionNavLoiterTurnsWidget->hide();
if(MissionNavLoiterTimeWidget) MissionNavLoiterTimeWidget->hide();
if(MissionOtherWidget) MissionOtherWidget->hide(); if(MissionOtherWidget) MissionOtherWidget->hide();
if(MissionConditionDelayWidget) MissionConditionDelayWidget->hide(); if(MissionConditionDelayWidget) MissionConditionDelayWidget->hide();
if(MissionDoJumpWidget) MissionDoJumpWidget->hide(); if(MissionDoJumpWidget) MissionDoJumpWidget->hide();
...@@ -131,21 +138,30 @@ void WaypointEditableView::updateActionView(int action) ...@@ -131,21 +138,30 @@ void WaypointEditableView::updateActionView(int action)
if (viewMode != QGC_WAYPOINTEDITABLEVIEW_MODE_DIRECT_EDITING) if (viewMode != QGC_WAYPOINTEDITABLEVIEW_MODE_DIRECT_EDITING)
{ {
switch(action) { switch(action) {
case MAV_CMD_NAV_TAKEOFF: case MAV_CMD_NAV_WAYPOINT:
case MAV_CMD_NAV_LAND: if(MissionNavWaypointWidget) MissionNavWaypointWidget->show();
case MAV_CMD_NAV_RETURN_TO_LAUNCH: break;
case MAV_CMD_NAV_LOITER_UNLIM: case MAV_CMD_NAV_LOITER_UNLIM:
if(MissionNavLoiterUnlimWidget) MissionNavLoiterUnlimWidget->show();
break;
case MAV_CMD_NAV_LOITER_TURNS: case MAV_CMD_NAV_LOITER_TURNS:
if(MissionNavLoiterTurnsWidget) MissionNavLoiterTurnsWidget->show();
break;
case MAV_CMD_NAV_LOITER_TIME: case MAV_CMD_NAV_LOITER_TIME:
if(MissionNavLoiterTimeWidget) MissionNavLoiterTimeWidget->show();
break; break;
case MAV_CMD_NAV_WAYPOINT: case MAV_CMD_NAV_RETURN_TO_LAUNCH:
if(MissionNavWaypointWidget) MissionNavWaypointWidget->show(); case MAV_CMD_NAV_LAND:
case MAV_CMD_NAV_TAKEOFF:
case MAV_CMD_CONDITION_DELAY:
if(MissionConditionDelayWidget) MissionConditionDelayWidget->show();
break; break;
case MAV_CMD_DO_JUMP: case MAV_CMD_DO_JUMP:
if(MissionDoJumpWidget) MissionDoJumpWidget->show(); if(MissionDoJumpWidget) MissionDoJumpWidget->show();
break; break;
default: default:
if(MissionOtherWidget) MissionOtherWidget->show(); if(MissionOtherWidget) MissionOtherWidget->show();
viewMode = QGC_WAYPOINTEDITABLEVIEW_MODE_DIRECT_EDITING;
break; break;
} }
} }
...@@ -160,59 +176,83 @@ void WaypointEditableView::updateActionView(int action) ...@@ -160,59 +176,83 @@ void WaypointEditableView::updateActionView(int action)
*/ */
void WaypointEditableView::changedAction(int index) 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 // set waypoint action
int actionIndex = m_ui->comboBox_action->itemData(index).toUInt(); int actionID = m_ui->comboBox_action->itemData(index).toUInt();
if (actionIndex < MAV_CMD_ENUM_END && actionIndex >= 0) { if (actionID == QVariant::Invalid || actionID == MAV_CMD_ENUM_END)
MAV_CMD action = (MAV_CMD) actionIndex; {
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); wp->setAction(action);
} }
// change the view
initializeActionView(actionID);
updateValues();
updateActionView(actionID);
}
// Expose ui based on action void WaypointEditableView::initializeActionView(int actionID)
// Change to mission frame {
// if action is unknown //initialize a new action-widget, if needed.
viewMode = QGC_WAYPOINTEDITABLEVIEW_MODE_DEFAULT; switch(actionID) {
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;
case MAV_CMD_NAV_WAYPOINT: case MAV_CMD_NAV_WAYPOINT:
if (!MissionNavWaypointWidget) if (!MissionNavWaypointWidget)
{ {
MissionNavWaypointWidget = new QGCMissionNavWaypoint(this); MissionNavWaypointWidget = new QGCMissionNavWaypoint(this);
m_ui->customActionWidget->layout()->addWidget(MissionNavWaypointWidget); m_ui->customActionWidget->layout()->addWidget(MissionNavWaypointWidget);
} }
updateActionView(actionIndex);
break; break;
case MAV_CMD_NAV_LOITER_UNLIM:
case MAV_CMD_DO_JUMP: 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) if (!MissionDoJumpWidget)
{ {
MissionDoJumpWidget = new QGCMissionDoWidget(this); MissionDoJumpWidget = new QGCMissionDoJump(this);
m_ui->customActionWidget->layout()->addWidget(MissionDoJumpWidget); m_ui->customActionWidget->layout()->addWidget(MissionDoJumpWidget);
} }
updateActionView(actionIndex);
break; break;
case MAV_CMD_ENUM_END: case MAV_CMD_ENUM_END:
default: default:
// Switch to mission frame
viewMode = QGC_WAYPOINTEDITABLEVIEW_MODE_DIRECT_EDITING;
if (!MissionOtherWidget) if (!MissionOtherWidget)
{ {
MissionOtherWidget = new QGCMissionOther(this); MissionOtherWidget = new QGCMissionOther(this);
m_ui->customActionWidget->layout()->addWidget(MissionOtherWidget); m_ui->customActionWidget->layout()->addWidget(MissionOtherWidget);
} }
updateActionView(actionIndex);
break; break;
} }
updateValues();
} }
void WaypointEditableView::deleted(QObject* waypoint) void WaypointEditableView::deleted(QObject* waypoint)
...@@ -299,7 +339,7 @@ void WaypointEditableView::updateValues() ...@@ -299,7 +339,7 @@ void WaypointEditableView::updateValues()
QDoubleSpinBox* spin = dynamic_cast<QDoubleSpinBox*>(m_ui->customActionWidget->children().at(j)); QDoubleSpinBox* spin = dynamic_cast<QDoubleSpinBox*>(m_ui->customActionWidget->children().at(j));
if (spin) if (spin)
{ {
qDebug() << "DEACTIVATED SPINBOX #" << j; //qDebug() << "DEACTIVATED SPINBOX #" << j;
spin->blockSignals(true); spin->blockSignals(true);
} }
else else
...@@ -334,32 +374,20 @@ void WaypointEditableView::updateValues() ...@@ -334,32 +374,20 @@ void WaypointEditableView::updateValues()
// Update action // Update action
MAV_CMD action = wp->getAction(); MAV_CMD action = wp->getAction();
int action_index = m_ui->comboBox_action->findData(action); 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 (m_ui->comboBox_action->currentIndex() != action_index)
{ {
// If action is unknown, set direct editing mode if (viewMode != QGC_WAYPOINTEDITABLEVIEW_MODE_DIRECT_EDITING)
if (wp->getAction() < 0 || wp->getAction() > MAV_CMD_NAV_TAKEOFF)//FIXME condition should not depend on NAV_TAKEOFF
{ {
//changeViewMode(QGC_WAYPOINTEDITABLEVIEW_MODE_DIRECT_EDITING); // Set to "Other" action if it was -1
} if (action_index == -1)
else
{
if (viewMode != QGC_WAYPOINTEDITABLEVIEW_MODE_DIRECT_EDITING)
{ {
// Action ID known, update action_index = m_ui->comboBox_action->findData(MAV_CMD_ENUM_END);
m_ui->comboBox_action->setCurrentIndex(action_index); viewMode = QGC_WAYPOINTEDITABLEVIEW_MODE_DIRECT_EDITING;
updateActionView(action);
} }
m_ui->comboBox_action->setCurrentIndex(action_index);
} }
} }
emit commandBroadcast(wp->getAction()); emit commandBroadcast(wp->getAction());
emit frameBroadcast(wp->getFrame()); emit frameBroadcast(wp->getFrame());
emit param1Broadcast(wp->getParam1()); emit param1Broadcast(wp->getParam1());
......
...@@ -27,7 +27,7 @@ This file is part of the QGROUNDCONTROL project ...@@ -27,7 +27,7 @@ This file is part of the QGROUNDCONTROL project
* @author Lorenz Meier <mavteam@student.ethz.ch> * @author Lorenz Meier <mavteam@student.ethz.ch>
* @author Benjamin Knecht <mavteam@student.ethz.ch> * @author Benjamin Knecht <mavteam@student.ethz.ch>
* @author Petri Tanskanen <mavteam@student.ethz.ch> * @author Petri Tanskanen <mavteam@student.ethz.ch>
* * @author Alex Trofimov <talex@student.ethz.ch>
*/ */
#ifndef WAYPOINTEDITABLEVIEW_H #ifndef WAYPOINTEDITABLEVIEW_H
...@@ -46,12 +46,14 @@ namespace Ui ...@@ -46,12 +46,14 @@ namespace Ui
{ {
class WaypointEditableView; class WaypointEditableView;
} }
//class Ui_QGCCustomWaypointAction;
//class Ui_QGCMissionDoWidget;
class QGCMissionNavWaypoint; class QGCMissionNavWaypoint;
class QGCMissionDoWidget; class QGCMissionNavLoiterUnlim;
class QGCMissionConditionWidget; class QGCMissionNavLoiterTurns;
class QGCMissionNavLoiterTime;
class QGCMissionDoJump;
class QGCMissionConditionDelay;
class QGCMissionOther; class QGCMissionOther;
class WaypointEditableView : public QWidget class WaypointEditableView : public QWidget
{ {
Q_OBJECT Q_OBJECT
...@@ -72,6 +74,7 @@ public slots: ...@@ -72,6 +74,7 @@ public slots:
void changedAutoContinue(int); void changedAutoContinue(int);
void changedFrame(int state); void changedFrame(int state);
void updateActionView(int action); void updateActionView(int action);
void initializeActionView(int action);
void changedCurrent(int); void changedCurrent(int);
void updateValues(void); void updateValues(void);
...@@ -90,13 +93,16 @@ protected slots: ...@@ -90,13 +93,16 @@ protected slots:
protected: protected:
virtual void changeEvent(QEvent *e); virtual void changeEvent(QEvent *e);
Waypoint* wp; Waypoint* wp;
// Special widgets extendending the QGC_WAYPOINTEDITABLEVIEW_MODE viewMode;
// waypoint view to mission capabilities // Widgets for every mission element
QGCMissionNavWaypoint* MissionNavWaypointWidget; QGCMissionNavWaypoint* MissionNavWaypointWidget;
QGCMissionDoWidget* MissionDoJumpWidget; QGCMissionNavLoiterUnlim* MissionNavLoiterUnlimWidget;
QGCMissionConditionWidget* MissionConditionDelayWidget; QGCMissionNavLoiterTurns* MissionNavLoiterTurnsWidget;
QGCMissionNavLoiterTime* MissionNavLoiterTimeWidget;
QGCMissionDoJump* MissionDoJumpWidget;
QGCMissionConditionDelay* MissionConditionDelayWidget;
QGCMissionOther* MissionOtherWidget; QGCMissionOther* MissionOtherWidget;
QGC_WAYPOINTEDITABLEVIEW_MODE viewMode;
private: private:
Ui::WaypointEditableView *m_ui; Ui::WaypointEditableView *m_ui;
......
#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;
}
#ifndef QGCMISSIONCONDITIONDELAY_H
#define QGCMISSIONCONDITIONDELAY_H
#include <QWidget>
#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
<?xml version="1.0" encoding="UTF-8"?>
<ui version="4.0">
<class>QGCMissionConditionDelay</class>
<widget class="QWidget" name="QGCMissionConditionDelay">
<property name="geometry">
<rect>
<x>0</x>
<y>0</y>
<width>448</width>
<height>37</height>
</rect>
</property>
<property name="sizePolicy">
<sizepolicy hsizetype="Preferred" vsizetype="Preferred">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="minimumSize">
<size>
<width>200</width>
<height>0</height>
</size>
</property>
<property name="windowTitle">
<string>Form</string>
</property>
<property name="styleSheet">
<string notr="true"/>
</property>
<layout class="QHBoxLayout" name="horizontalLayout">
<property name="spacing">
<number>5</number>
</property>
<property name="margin">
<number>0</number>
</property>
<item>
<widget class="QDoubleSpinBox" name="param1SpinBox">
<property name="sizePolicy">
<sizepolicy hsizetype="Expanding" vsizetype="Fixed">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="focusPolicy">
<enum>Qt::WheelFocus</enum>
</property>
<property name="toolTip">
<string>Delay duration</string>
</property>
<property name="statusTip">
<string>Delay duration</string>
</property>
<property name="wrapping">
<bool>false</bool>
</property>
<property name="frame">
<bool>true</bool>
</property>
<property name="accelerated">
<bool>true</bool>
</property>
<property name="keyboardTracking">
<bool>false</bool>
</property>
<property name="prefix">
<string>Duration: </string>
</property>
<property name="suffix">
<string>s</string>
</property>
<property name="decimals">
<number>2</number>
</property>
<property name="minimum">
<double>0.000000000000000</double>
</property>
<property name="maximum">
<double>100000.000000000000000</double>
</property>
<property name="singleStep">
<double>1.000000000000000</double>
</property>
</widget>
</item>
</layout>
</widget>
<resources/>
<connections/>
</ui>
#include "QGCMissionConditionWidget.h"
#include "ui_QGCMissionConditionWidget.h"
QGCMissionConditionWidget::QGCMissionConditionWidget(QWidget *parent) :
QWidget(parent),
ui(new Ui::QGCMissionConditionWidget)
{
ui->setupUi(this);
}
QGCMissionConditionWidget::~QGCMissionConditionWidget()
{
delete ui;
}
#ifndef QGCMISSIONCONDITIONWIDGET_H
#define QGCMISSIONCONDITIONWIDGET_H
#include <QWidget>
namespace Ui
{
class QGCMissionConditionWidget;
}
class QGCMissionConditionWidget : public QWidget
{
Q_OBJECT
public:
explicit QGCMissionConditionWidget(QWidget *parent = 0);
~QGCMissionConditionWidget();
private:
Ui::QGCMissionConditionWidget *ui;
};
#endif // QGCMISSIONCONDITIONWIDGET_H
<?xml version="1.0" encoding="UTF-8"?>
<ui version="4.0">
<class>QGCMissionConditionWidget</class>
<widget class="QWidget" name="QGCMissionConditionWidget">
<property name="geometry">
<rect>
<x>0</x>
<y>0</y>
<width>1260</width>
<height>31</height>
</rect>
</property>
<property name="windowTitle">
<string>Form</string>
</property>
<layout class="QHBoxLayout" name="horizontalLayout">
<property name="spacing">
<number>4</number>
</property>
<property name="margin">
<number>0</number>
</property>
<item>
<widget class="QDoubleSpinBox" name="conditionDelayTimeSpinBox">
<property name="prefix">
<string>delay: </string>
</property>
<property name="suffix">
<string> s</string>
</property>
<property name="maximum">
<double>50000.000000000000000</double>
</property>
<property name="value">
<double>5.000000000000000</double>
</property>
</widget>
</item>
<item>
<widget class="QDoubleSpinBox" name="conditionChangeAltRateSpinBox">
<property name="prefix">
<string>rate: </string>
</property>
<property name="suffix">
<string> m/s</string>
</property>
<property name="maximum">
<double>200.000000000000000</double>
</property>
<property name="value">
<double>0.500000000000000</double>
</property>
</widget>
</item>
<item>
<widget class="QDoubleSpinBox" name="conditionChangeAltFinishAltitudeSpinBox">
<property name="prefix">
<string>finish altitude: </string>
</property>
<property name="suffix">
<string> m</string>
</property>
<property name="minimum">
<double>-100.000000000000000</double>
</property>
<property name="maximum">
<double>1000000.000000000000000</double>
</property>
</widget>
</item>
<item>
<widget class="QDoubleSpinBox" name="conditionDistanceSpinBox">
<property name="prefix">
<string>distance to next wp: </string>
</property>
<property name="suffix">
<string> m/s</string>
</property>
<property name="maximum">
<double>50000.000000000000000</double>
</property>
</widget>
</item>
<item>
<widget class="QDoubleSpinBox" name="conditionYawAngleSpinBox">
<property name="prefix">
<string>heading: </string>
</property>
<property name="suffix">
<string>°</string>
</property>
</widget>
</item>
<item>
<widget class="QDoubleSpinBox" name="conditionYawRateSpinBox">
<property name="prefix">
<string>turn rate: </string>
</property>
<property name="suffix">
<string>°/s</string>
</property>
<property name="maximum">
<double>1000.000000000000000</double>
</property>
<property name="value">
<double>15.000000000000000</double>
</property>
</widget>
</item>
<item>
<widget class="QComboBox" name="conditionYawDirectionComboBox">
<property name="currentIndex">
<number>1</number>
</property>
<item>
<property name="text">
<string>left/counter-clockwise</string>
</property>
</item>
<item>
<property name="text">
<string>right/clockwise</string>
</property>
</item>
</widget>
</item>
<item>
<widget class="QComboBox" name="conditionYawOffsetComboBox">
<item>
<property name="text">
<string>compass direction</string>
</property>
</item>
<item>
<property name="text">
<string>offset from current heading</string>
</property>
</item>
</widget>
</item>
</layout>
</widget>
<resources/>
<connections/>
</ui>
#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;
}
#ifndef QGCMISSIONDOJUMP_H
#define QGCMISSIONDOJUMP_H
#include <QWidget>
#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
<?xml version="1.0" encoding="UTF-8"?> <?xml version="1.0" encoding="UTF-8"?>
<ui version="4.0"> <ui version="4.0">
<class>QGCCustomWaypointAction</class> <class>QGCMissionDoJump</class>
<widget class="QWidget" name="QGCCustomWaypointAction"> <widget class="QWidget" name="QGCMissionDoJump">
<property name="geometry"> <property name="geometry">
<rect> <rect>
<x>0</x> <x>0</x>
<y>0</y> <y>0</y>
<width>1228</width> <width>448</width>
<height>27</height> <height>37</height>
</rect> </rect>
</property> </property>
<property name="sizePolicy">
<sizepolicy hsizetype="Preferred" vsizetype="Preferred">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="minimumSize">
<size>
<width>200</width>
<height>0</height>
</size>
</property>
<property name="windowTitle"> <property name="windowTitle">
<string>Form</string> <string>Form</string>
</property> </property>
<layout class="QHBoxLayout" name="horizontalLayout" stretch="10,0,10,10,10,10,0,0"> <property name="styleSheet">
<string notr="true"/>
</property>
<layout class="QHBoxLayout" name="horizontalLayout">
<property name="spacing"> <property name="spacing">
<number>5</number> <number>5</number>
</property> </property>
...@@ -21,139 +36,94 @@ ...@@ -21,139 +36,94 @@
<number>0</number> <number>0</number>
</property> </property>
<item> <item>
<widget class="QSpinBox" name="commandSpinBox"> <widget class="QDoubleSpinBox" name="param1SpinBox">
<property name="sizePolicy">
<sizepolicy hsizetype="Expanding" vsizetype="Fixed">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="focusPolicy">
<enum>Qt::WheelFocus</enum>
</property>
<property name="toolTip"> <property name="toolTip">
<string>MAV_CMD id</string> <string>Mission element ID to jump to</string>
</property> </property>
<property name="statusTip"> <property name="statusTip">
<string>MAV_CMD id</string> <string>Mission element ID to jump to</string>
</property> </property>
<property name="prefix"> <property name="wrapping">
<string>CMD </string> <bool>false</bool>
</property> </property>
<property name="minimum"> <property name="frame">
<number>0</number> <bool>true</bool>
</property> </property>
<property name="maximum"> <property name="accelerated">
<number>255</number> <bool>true</bool>
</property> </property>
<property name="value"> <property name="keyboardTracking">
<number>0</number> <bool>false</bool>
</property> </property>
</widget>
</item>
<item>
<widget class="QDoubleSpinBox" name="param1SpinBox">
<property name="prefix"> <property name="prefix">
<string>P1 </string> <string>Jump to index </string>
</property>
<property name="decimals">
<number>7</number>
</property> </property>
<property name="minimum"> <property name="suffix">
<double>-2147483647.000000000000000</double>
</property>
<property name="maximum">
<double>2147483647.000000000000000</double>
</property>
</widget>
</item>
<item>
<widget class="QDoubleSpinBox" name="param2SpinBox">
<property name="toolTip">
<string/> <string/>
</property> </property>
<property name="prefix">
<string>P2 </string>
</property>
<property name="decimals"> <property name="decimals">
<number>7</number> <number>0</number>
</property> </property>
<property name="minimum"> <property name="minimum">
<double>-2147483647.000000000000000</double> <double>0.000000000000000</double>
</property> </property>
<property name="maximum"> <property name="maximum">
<double>2147483647.000000000000000</double> <double>10000.000000000000000</double>
</property> </property>
</widget> <property name="singleStep">
</item> <double>1.000000000000000</double>
<item>
<widget class="QDoubleSpinBox" name="param3SpinBox">
<property name="prefix">
<string>P3 </string>
</property>
<property name="decimals">
<number>7</number>
</property>
<property name="minimum">
<double>-2147483647.000000000000000</double>
</property>
<property name="maximum">
<double>2147483647.000000000000000</double>
</property> </property>
</widget> </widget>
</item> </item>
<item> <item>
<widget class="QDoubleSpinBox" name="param4SpinBox"> <widget class="QDoubleSpinBox" name="param2SpinBox">
<property name="prefix"> <property name="sizePolicy">
<string>P4 </string> <sizepolicy hsizetype="Expanding" vsizetype="Fixed">
</property> <horstretch>0</horstretch>
<property name="decimals"> <verstretch>0</verstretch>
<number>7</number> </sizepolicy>
</property>
<property name="minimum">
<double>-2147483647.000000000000000</double>
</property>
<property name="maximum">
<double>2147483647.000000000000000</double>
</property> </property>
</widget> <property name="focusPolicy">
</item> <enum>Qt::WheelFocus</enum>
<item>
<widget class="QDoubleSpinBox" name="param5SpinBox">
<property name="prefix">
<string>P5 </string>
</property> </property>
<property name="decimals"> <property name="toolTip">
<number>7</number> <string>Maximal number of jumps</string>
</property> </property>
<property name="minimum"> <property name="statusTip">
<double>-2147483647.000000000000000</double> <string>Maximal number of jumps</string>
</property> </property>
<property name="maximum"> <property name="keyboardTracking">
<double>2147483647.000000000000000</double> <bool>false</bool>
</property> </property>
</widget>
</item>
<item>
<widget class="QDoubleSpinBox" name="param6SpinBox">
<property name="prefix"> <property name="prefix">
<string>P6 </string> <string/>
</property>
<property name="suffix">
<string> time(s)</string>
</property> </property>
<property name="decimals"> <property name="decimals">
<number>7</number> <number>0</number>
</property> </property>
<property name="minimum"> <property name="minimum">
<double>-2147483647.000000000000000</double> <double>0.000000000000000</double>
</property> </property>
<property name="maximum"> <property name="maximum">
<double>2147483647.000000000000000</double> <double>10000.000000000000000</double>
</property>
</widget>
</item>
<item>
<widget class="QDoubleSpinBox" name="param7SpinBox">
<property name="prefix">
<string>P7 </string>
</property> </property>
<property name="decimals"> <property name="singleStep">
<number>7</number> <double>1.000000000000000</double>
</property> </property>
<property name="minimum"> <property name="value">
<double>-2147483647.000000000000000</double> <double>1.000000000000000</double>
</property>
<property name="maximum">
<double>2147483647.000000000000000</double>
</property> </property>
</widget> </widget>
</item> </item>
......
#include "QGCMissionDoWidget.h"
#include "ui_QGCMissionDoWidget.h"
QGCMissionDoWidget::QGCMissionDoWidget(QWidget *parent) :
QWidget(parent),
ui(new Ui::QGCMissionDoWidget)
{
ui->setupUi(this);
}
QGCMissionDoWidget::~QGCMissionDoWidget()
{
delete ui;
}
#ifndef QGCMISSIONDOWIDGET_H
#define QGCMISSIONDOWIDGET_H
#include <QWidget>
namespace Ui
{
class QGCMissionDoWidget;
}
class QGCMissionDoWidget : public QWidget
{
Q_OBJECT
public:
explicit QGCMissionDoWidget(QWidget *parent = 0);
~QGCMissionDoWidget();
private:
Ui::QGCMissionDoWidget *ui;
};
#endif // QGCMISSIONDOWIDGET_H
<?xml version="1.0" encoding="UTF-8"?>
<ui version="4.0">
<class>QGCMissionDoWidget</class>
<widget class="QWidget" name="QGCMissionDoWidget">
<property name="geometry">
<rect>
<x>0</x>
<y>0</y>
<width>632</width>
<height>27</height>
</rect>
</property>
<property name="windowTitle">
<string>Form</string>
</property>
<layout class="QHBoxLayout" name="horizontalLayout" stretch="10,10,10">
<property name="spacing">
<number>5</number>
</property>
<property name="margin">
<number>0</number>
</property>
<item>
<widget class="QComboBox" name="doSetModeComboBox"/>
</item>
<item>
<widget class="QSpinBox" name="doJumpIndexSpinBox">
<property name="suffix">
<string/>
</property>
<property name="prefix">
<string>list index to jump to: </string>
</property>
<property name="maximum">
<number>5000</number>
</property>
</widget>
</item>
<item>
<widget class="QSpinBox" name="doJumpRepeatSpinBox">
<property name="suffix">
<string> times</string>
</property>
<property name="prefix">
<string>repeat </string>
</property>
<property name="maximum">
<number>1000</number>
</property>
</widget>
</item>
</layout>
</widget>
<resources/>
<connections/>
</ui>
#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;
}
#ifndef QGCMISSIONNAVLOITERTIME_H
#define QGCMISSIONNAVLOITERTIME_H
#include <QWidget>
#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
This diff is collapsed.
#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;
}
#ifndef QGCMISSIONNAVLOITERTURNS_H
#define QGCMISSIONNAVLOITERTURNS_H
#include <QWidget>
#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
This diff is collapsed.
#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;
}
#ifndef QGCMISSIONNAVLOITERUNLIM_H
#define QGCMISSIONNAVLOITERUNLIM_H
#include <QWidget>
#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
This diff is collapsed.
...@@ -26,7 +26,4 @@ private: ...@@ -26,7 +26,4 @@ private:
Ui::QGCMissionNavWaypoint *ui; Ui::QGCMissionNavWaypoint *ui;
}; };
#endif // QGCMISSIONNAVWAYPOINT_H #endif // QGCMISSIONNAVWAYPOINT_H
...@@ -61,6 +61,9 @@ ...@@ -61,6 +61,9 @@
<property name="accelerated"> <property name="accelerated">
<bool>true</bool> <bool>true</bool>
</property> </property>
<property name="keyboardTracking">
<bool>false</bool>
</property>
<property name="prefix"> <property name="prefix">
<string>N </string> <string>N </string>
</property> </property>
...@@ -95,6 +98,9 @@ ...@@ -95,6 +98,9 @@
<property name="statusTip"> <property name="statusTip">
<string>Position Y/Longitude coordinate</string> <string>Position Y/Longitude coordinate</string>
</property> </property>
<property name="keyboardTracking">
<bool>false</bool>
</property>
<property name="prefix"> <property name="prefix">
<string>E </string> <string>E </string>
</property> </property>
...@@ -132,6 +138,9 @@ ...@@ -132,6 +138,9 @@
<property name="statusTip"> <property name="statusTip">
<string/> <string/>
</property> </property>
<property name="keyboardTracking">
<bool>false</bool>
</property>
<property name="prefix"> <property name="prefix">
<string>D </string> <string>D </string>
</property> </property>
...@@ -166,6 +175,9 @@ ...@@ -166,6 +175,9 @@
<property name="statusTip"> <property name="statusTip">
<string>Latitude in degrees</string> <string>Latitude in degrees</string>
</property> </property>
<property name="keyboardTracking">
<bool>false</bool>
</property>
<property name="prefix"> <property name="prefix">
<string>lat </string> <string>lat </string>
</property> </property>
...@@ -203,6 +215,9 @@ ...@@ -203,6 +215,9 @@
<property name="statusTip"> <property name="statusTip">
<string>Longitude in degrees</string> <string>Longitude in degrees</string>
</property> </property>
<property name="keyboardTracking">
<bool>false</bool>
</property>
<property name="prefix"> <property name="prefix">
<string>lon </string> <string>lon </string>
</property> </property>
...@@ -237,6 +252,9 @@ ...@@ -237,6 +252,9 @@
<property name="statusTip"> <property name="statusTip">
<string>Altitude in meters</string> <string>Altitude in meters</string>
</property> </property>
<property name="keyboardTracking">
<bool>false</bool>
</property>
<property name="prefix"> <property name="prefix">
<string>alt </string> <string>alt </string>
</property> </property>
...@@ -274,6 +292,9 @@ ...@@ -274,6 +292,9 @@
<property name="wrapping"> <property name="wrapping">
<bool>true</bool> <bool>true</bool>
</property> </property>
<property name="keyboardTracking">
<bool>false</bool>
</property>
<property name="prefix"> <property name="prefix">
<string/> <string/>
</property> </property>
...@@ -306,6 +327,9 @@ where to accept this waypoint as reached</string> ...@@ -306,6 +327,9 @@ where to accept this waypoint as reached</string>
<property name="statusTip"> <property name="statusTip">
<string>Uncertainty radius in meters where to accept this waypoint as reached</string> <string>Uncertainty radius in meters where to accept this waypoint as reached</string>
</property> </property>
<property name="keyboardTracking">
<bool>false</bool>
</property>
<property name="suffix"> <property name="suffix">
<string> m</string> <string> m</string>
</property> </property>
...@@ -328,6 +352,9 @@ where to accept this waypoint as reached</string> ...@@ -328,6 +352,9 @@ where to accept this waypoint as reached</string>
<property name="statusTip"> <property name="statusTip">
<string>Time to stay/loiter at this position before advancing</string> <string>Time to stay/loiter at this position before advancing</string>
</property> </property>
<property name="keyboardTracking">
<bool>false</bool>
</property>
<property name="suffix"> <property name="suffix">
<string> s</string> <string> s</string>
</property> </property>
......
...@@ -14,13 +14,13 @@ class QGCMissionOther : public QWidget ...@@ -14,13 +14,13 @@ class QGCMissionOther : public QWidget
public: public:
explicit QGCMissionOther(WaypointEditableView* WEV); explicit QGCMissionOther(WaypointEditableView* WEV);
~QGCMissionOther(); ~QGCMissionOther();
Ui::QGCMissionOther *ui;
protected: protected:
WaypointEditableView* WEV; WaypointEditableView* WEV;
private: private:
Ui::QGCMissionOther *ui;
}; };
#endif // QGCMISSIONOTHER_H #endif // QGCMISSIONOTHER_H
...@@ -28,6 +28,9 @@ ...@@ -28,6 +28,9 @@
<property name="statusTip"> <property name="statusTip">
<string>MAV_CMD id</string> <string>MAV_CMD id</string>
</property> </property>
<property name="keyboardTracking">
<bool>false</bool>
</property>
<property name="prefix"> <property name="prefix">
<string>CMD </string> <string>CMD </string>
</property> </property>
...@@ -44,6 +47,9 @@ ...@@ -44,6 +47,9 @@
</item> </item>
<item> <item>
<widget class="QDoubleSpinBox" name="param1SpinBox"> <widget class="QDoubleSpinBox" name="param1SpinBox">
<property name="keyboardTracking">
<bool>false</bool>
</property>
<property name="prefix"> <property name="prefix">
<string>P1 </string> <string>P1 </string>
</property> </property>
...@@ -63,6 +69,9 @@ ...@@ -63,6 +69,9 @@
<property name="toolTip"> <property name="toolTip">
<string/> <string/>
</property> </property>
<property name="keyboardTracking">
<bool>false</bool>
</property>
<property name="prefix"> <property name="prefix">
<string>P2 </string> <string>P2 </string>
</property> </property>
...@@ -79,6 +88,9 @@ ...@@ -79,6 +88,9 @@
</item> </item>
<item> <item>
<widget class="QDoubleSpinBox" name="param3SpinBox"> <widget class="QDoubleSpinBox" name="param3SpinBox">
<property name="keyboardTracking">
<bool>false</bool>
</property>
<property name="prefix"> <property name="prefix">
<string>P3 </string> <string>P3 </string>
</property> </property>
...@@ -95,6 +107,9 @@ ...@@ -95,6 +107,9 @@
</item> </item>
<item> <item>
<widget class="QDoubleSpinBox" name="param4SpinBox"> <widget class="QDoubleSpinBox" name="param4SpinBox">
<property name="keyboardTracking">
<bool>false</bool>
</property>
<property name="prefix"> <property name="prefix">
<string>P4 </string> <string>P4 </string>
</property> </property>
...@@ -111,6 +126,9 @@ ...@@ -111,6 +126,9 @@
</item> </item>
<item> <item>
<widget class="QDoubleSpinBox" name="param5SpinBox"> <widget class="QDoubleSpinBox" name="param5SpinBox">
<property name="keyboardTracking">
<bool>false</bool>
</property>
<property name="prefix"> <property name="prefix">
<string>P5 </string> <string>P5 </string>
</property> </property>
...@@ -127,6 +145,9 @@ ...@@ -127,6 +145,9 @@
</item> </item>
<item> <item>
<widget class="QDoubleSpinBox" name="param6SpinBox"> <widget class="QDoubleSpinBox" name="param6SpinBox">
<property name="keyboardTracking">
<bool>false</bool>
</property>
<property name="prefix"> <property name="prefix">
<string>P6 </string> <string>P6 </string>
</property> </property>
...@@ -143,6 +164,9 @@ ...@@ -143,6 +164,9 @@
</item> </item>
<item> <item>
<widget class="QDoubleSpinBox" name="param7SpinBox"> <widget class="QDoubleSpinBox" name="param7SpinBox">
<property name="keyboardTracking">
<bool>false</bool>
</property>
<property name="prefix"> <property name="prefix">
<string>P7 </string> <string>P7 </string>
</property> </property>
......
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