Commit a3bf4c81 authored by pixhawk's avatar pixhawk

Final version of the "editable"-mission redesign.

parent 838e5e78
......@@ -243,7 +243,10 @@ FORMS += src/ui/MainWindow.ui \
src/ui/mission/QGCMissionConditionDelay.ui \
src/ui/mission/QGCMissionNavLoiterUnlim.ui \
src/ui/mission/QGCMissionNavLoiterTurns.ui \
src/ui/mission/QGCMissionNavLoiterTime.ui
src/ui/mission/QGCMissionNavLoiterTime.ui \
src/ui/mission/QGCMissionNavReturnToLaunch.ui \
src/ui/mission/QGCMissionNavLand.ui \
src/ui/mission/QGCMissionNavTakeoff.ui
INCLUDEPATH += src \
src/ui \
src/ui/linechart \
......@@ -371,7 +374,10 @@ HEADERS += src/MG.h \
src/ui/mission/QGCMissionConditionDelay.h \
src/ui/mission/QGCMissionNavLoiterUnlim.h \
src/ui/mission/QGCMissionNavLoiterTurns.h \
src/ui/mission/QGCMissionNavLoiterTime.h
src/ui/mission/QGCMissionNavLoiterTime.h \
src/ui/mission/QGCMissionNavReturnToLaunch.h \
src/ui/mission/QGCMissionNavLand.h \
src/ui/mission/QGCMissionNavTakeoff.h
# Google Earth is only supported on Mac OS and Windows with Visual Studio Compiler
macx|macx-g++|macx-g++42|win32-msvc2008|win32-msvc2010::HEADERS += src/ui/map3D/QGCGoogleEarthView.h
......@@ -508,7 +514,10 @@ SOURCES += src/main.cc \
src/ui/mission/QGCMissionConditionDelay.cc \
src/ui/mission/QGCMissionNavLoiterUnlim.cc \
src/ui/mission/QGCMissionNavLoiterTurns.cc \
src/ui/mission/QGCMissionNavLoiterTime.cc
src/ui/mission/QGCMissionNavLoiterTime.cc \
src/ui/mission/QGCMissionNavReturnToLaunch.cc \
src/ui/mission/QGCMissionNavLand.cc \
src/ui/mission/QGCMissionNavTakeoff.cc
# Enable Google Earth only on Mac OS and Windows with Visual Studio compiler
macx|macx-g++|macx-g++42|win32-msvc2008|win32-msvc2010::SOURCES += src/ui/map3D/QGCGoogleEarthView.cc
......
......@@ -25,6 +25,9 @@
#include "QGCMissionNavLoiterUnlim.h"
#include "QGCMissionNavLoiterTurns.h"
#include "QGCMissionNavLoiterTime.h"
#include "QGCMissionNavReturnToLaunch.h"
#include "QGCMissionNavLand.h"
#include "QGCMissionNavTakeoff.h"
#include "QGCMissionConditionDelay.h"
#include "QGCMissionDoJump.h"
#include "QGCMissionOther.h"
......@@ -50,6 +53,9 @@ WaypointEditableView::WaypointEditableView(Waypoint* wp, QWidget* parent) :
MissionNavLoiterUnlimWidget = NULL;
MissionNavLoiterTurnsWidget = NULL;
MissionNavLoiterTimeWidget = NULL;
MissionNavReturnToLaunchWidget = NULL;
MissionNavLandWidget = NULL;
MissionNavTakeoffWidget = NULL;
MissionDoJumpWidget = NULL;
MissionConditionDelayWidget = NULL;
MissionOtherWidget = NULL;
......@@ -130,9 +136,12 @@ void WaypointEditableView::updateActionView(int action)
if(MissionNavLoiterUnlimWidget) MissionNavLoiterUnlimWidget->hide();
if(MissionNavLoiterTurnsWidget) MissionNavLoiterTurnsWidget->hide();
if(MissionNavLoiterTimeWidget) MissionNavLoiterTimeWidget->hide();
if(MissionOtherWidget) MissionOtherWidget->hide();
if(MissionNavReturnToLaunchWidget) MissionNavReturnToLaunchWidget->hide();
if(MissionNavLandWidget) MissionNavLandWidget->hide();
if(MissionNavTakeoffWidget) MissionNavTakeoffWidget->hide();
if(MissionConditionDelayWidget) MissionConditionDelayWidget->hide();
if(MissionDoJumpWidget) MissionDoJumpWidget->hide();
if(MissionOtherWidget) MissionOtherWidget->hide();
//Show only the correct one
if (viewMode != QGC_WAYPOINTEDITABLEVIEW_MODE_DIRECT_EDITING)
......@@ -151,8 +160,14 @@ void WaypointEditableView::updateActionView(int action)
if(MissionNavLoiterTimeWidget) MissionNavLoiterTimeWidget->show();
break;
case MAV_CMD_NAV_RETURN_TO_LAUNCH:
if(MissionNavReturnToLaunchWidget) MissionNavReturnToLaunchWidget->show();
break;
case MAV_CMD_NAV_LAND:
if(MissionNavLandWidget) MissionNavLandWidget->show();
break;
case MAV_CMD_NAV_TAKEOFF:
if(MissionNavTakeoffWidget) MissionNavTakeoffWidget->show();
break;
case MAV_CMD_CONDITION_DELAY:
if(MissionConditionDelayWidget) MissionConditionDelayWidget->show();
break;
......@@ -227,8 +242,26 @@ void WaypointEditableView::initializeActionView(int actionID)
}
break;
case MAV_CMD_NAV_RETURN_TO_LAUNCH:
if (!MissionNavReturnToLaunchWidget)
{
MissionNavReturnToLaunchWidget = new QGCMissionNavReturnToLaunch(this);
m_ui->customActionWidget->layout()->addWidget(MissionNavReturnToLaunchWidget);
}
break;
case MAV_CMD_NAV_LAND:
if (!MissionNavLandWidget)
{
MissionNavLandWidget = new QGCMissionNavLand(this);
m_ui->customActionWidget->layout()->addWidget(MissionNavLandWidget);
}
break;
case MAV_CMD_NAV_TAKEOFF:
if (!MissionNavTakeoffWidget)
{
MissionNavTakeoffWidget = new QGCMissionNavTakeoff(this);
m_ui->customActionWidget->layout()->addWidget(MissionNavTakeoffWidget);
}
break;
case MAV_CMD_CONDITION_DELAY:
if (!MissionConditionDelayWidget)
{
......
......@@ -50,6 +50,9 @@ class QGCMissionNavWaypoint;
class QGCMissionNavLoiterUnlim;
class QGCMissionNavLoiterTurns;
class QGCMissionNavLoiterTime;
class QGCMissionNavReturnToLaunch;
class QGCMissionNavLand;
class QGCMissionNavTakeoff;
class QGCMissionDoJump;
class QGCMissionConditionDelay;
class QGCMissionOther;
......@@ -99,6 +102,9 @@ protected:
QGCMissionNavLoiterUnlim* MissionNavLoiterUnlimWidget;
QGCMissionNavLoiterTurns* MissionNavLoiterTurnsWidget;
QGCMissionNavLoiterTime* MissionNavLoiterTimeWidget;
QGCMissionNavReturnToLaunch* MissionNavReturnToLaunchWidget;
QGCMissionNavLand* MissionNavLandWidget;
QGCMissionNavTakeoff* MissionNavTakeoffWidget;
QGCMissionDoJump* MissionDoJumpWidget;
QGCMissionConditionDelay* MissionConditionDelayWidget;
QGCMissionOther* MissionOtherWidget;
......
......@@ -18,7 +18,7 @@
</property>
<property name="minimumSize">
<size>
<width>200</width>
<width>0</width>
<height>0</height>
</size>
</property>
......
......@@ -18,7 +18,7 @@
</property>
<property name="minimumSize">
<size>
<width>200</width>
<width>0</width>
<height>0</height>
</size>
</property>
......
#include "QGCMissionNavLand.h"
#include "ui_QGCMissionNavLand.h"
#include "WaypointEditableView.h"
QGCMissionNavLand::QGCMissionNavLand(WaypointEditableView* WEV) :
QWidget(WEV),
ui(new Ui::QGCMissionNavLand)
{
ui->setupUi(this);
this->WEV = WEV;
//Using UI to change WP:
//connect(this->ui->holdTimeSpinBox, SIGNAL(valueChanged(double)),WEV,SLOT(changedParam1(double)));
//connect(this->ui->acceptanceSpinBox, SIGNAL(valueChanged(double)),WEV,SLOT(changedParam2(double)));
//connect(this->ui->param3SpinBox, SIGNAL(valueChanged(double)),WEV,SLOT(changedParam3(double)));
connect(this->ui->yawSpinBox, SIGNAL(valueChanged(double)),WEV,SLOT(changedParam4(double)));
connect(this->ui->posNSpinBox, SIGNAL(valueChanged(double)),WEV,SLOT(changedParam5(double)));//NED
connect(this->ui->posESpinBox, SIGNAL(valueChanged(double)),WEV,SLOT(changedParam6(double)));
connect(this->ui->posDSpinBox, SIGNAL(valueChanged(double)),WEV,SLOT(changedParam7(double)));
connect(this->ui->latSpinBox, SIGNAL(valueChanged(double)),WEV,SLOT(changedParam5(double)));//Global
connect(this->ui->lonSpinBox, SIGNAL(valueChanged(double)),WEV,SLOT(changedParam6(double)));
connect(this->ui->altSpinBox, SIGNAL(valueChanged(double)),WEV,SLOT(changedParam7(double)));
//Reading WP to update UI:
connect(WEV,SIGNAL(frameBroadcast(MAV_FRAME)),this,SLOT(updateFrame(MAV_FRAME)));
//connect(WEV,SIGNAL(param1Broadcast(double)),this->ui->holdTimeSpinBox,SLOT(setValue(double)));
//connect(WEV,SIGNAL(param2Broadcast(double)),this->ui->acceptanceSpinBox,SLOT(setValue(double)));
//connect(WEV,SIGNAL(param3Broadcast(double)),this->ui->param3SpinBox,SLOT(setValue(double)));
connect(WEV,SIGNAL(param4Broadcast(double)),this->ui->yawSpinBox,SLOT(setValue(double)));
connect(WEV,SIGNAL(param5Broadcast(double)),this->ui->posNSpinBox,SLOT(setValue(double)));//NED
connect(WEV,SIGNAL(param6Broadcast(double)),this->ui->posESpinBox,SLOT(setValue(double)));
connect(WEV,SIGNAL(param7Broadcast(double)),this->ui->posDSpinBox,SLOT(setValue(double)));
connect(WEV,SIGNAL(param5Broadcast(double)),this->ui->latSpinBox,SLOT(setValue(double)));//Global
connect(WEV,SIGNAL(param6Broadcast(double)),this->ui->lonSpinBox,SLOT(setValue(double)));
connect(WEV,SIGNAL(param7Broadcast(double)),this->ui->altSpinBox,SLOT(setValue(double)));
}
void QGCMissionNavLand::updateFrame(MAV_FRAME frame)
{
switch(frame)
{
case MAV_FRAME_LOCAL_ENU:
case MAV_FRAME_LOCAL_NED:
this->ui->posNSpinBox->show();
this->ui->posESpinBox->show();
this->ui->posDSpinBox->show();
this->ui->latSpinBox->hide();
this->ui->lonSpinBox->hide();
this->ui->altSpinBox->hide();
break;
case MAV_FRAME_GLOBAL:
case MAV_FRAME_GLOBAL_RELATIVE_ALT:
this->ui->posNSpinBox->hide();
this->ui->posESpinBox->hide();
this->ui->posDSpinBox->hide();
this->ui->latSpinBox->show();
this->ui->lonSpinBox->show();
this->ui->altSpinBox->show();
break;
default:
break;
}
}
QGCMissionNavLand::~QGCMissionNavLand()
{
delete ui;
}
#ifndef QGCMISSIONNAVLAND_H
#define QGCMISSIONNAVLAND_H
#include <QWidget>
#include "WaypointEditableView.h"
namespace Ui {
class QGCMissionNavLand;
}
class QGCMissionNavLand : public QWidget
{
Q_OBJECT
public:
explicit QGCMissionNavLand(WaypointEditableView* WEV);
~QGCMissionNavLand();
public slots:
void updateFrame(MAV_FRAME);
protected:
WaypointEditableView* WEV;
private:
Ui::QGCMissionNavLand *ui;
};
#endif // QGCMISSIONNAVLAND_H
<?xml version="1.0" encoding="UTF-8"?>
<ui version="4.0">
<class>QGCMissionNavLand</class>
<widget class="QWidget" name="QGCMissionNavLand">
<property name="geometry">
<rect>
<x>0</x>
<y>0</y>
<width>2208</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>0</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="posNSpinBox">
<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>Position X coordinate</string>
</property>
<property name="statusTip">
<string>Position X corrdinate</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>N </string>
</property>
<property name="suffix">
<string> m</string>
</property>
<property name="minimum">
<double>-10000.000000000000000</double>
</property>
<property name="maximum">
<double>10000.000000000000000</double>
</property>
<property name="singleStep">
<double>0.050000000000000</double>
</property>
</widget>
</item>
<item>
<widget class="QDoubleSpinBox" name="posESpinBox">
<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>Position Y/Longitude coordinate</string>
</property>
<property name="statusTip">
<string>Position Y/Longitude coordinate</string>
</property>
<property name="keyboardTracking">
<bool>false</bool>
</property>
<property name="prefix">
<string>E </string>
</property>
<property name="suffix">
<string> m</string>
</property>
<property name="minimum">
<double>-10000.000000000000000</double>
</property>
<property name="maximum">
<double>10000.000000000000000</double>
</property>
<property name="singleStep">
<double>0.050000000000000</double>
</property>
<property name="value">
<double>0.000000000000000</double>
</property>
</widget>
</item>
<item>
<widget class="QDoubleSpinBox" name="posDSpinBox">
<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>Position Z coordinate (local frame, negative)</string>
</property>
<property name="statusTip">
<string/>
</property>
<property name="keyboardTracking">
<bool>false</bool>
</property>
<property name="prefix">
<string>D </string>
</property>
<property name="suffix">
<string> m</string>
</property>
<property name="minimum">
<double>-10000.000000000000000</double>
</property>
<property name="maximum">
<double>10000.000000000000000</double>
</property>
<property name="singleStep">
<double>0.050000000000000</double>
</property>
</widget>
</item>
<item>
<widget class="QDoubleSpinBox" name="latSpinBox">
<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>Latitude in degrees</string>
</property>
<property name="statusTip">
<string>Latitude in degrees</string>
</property>
<property name="keyboardTracking">
<bool>false</bool>
</property>
<property name="prefix">
<string>lat </string>
</property>
<property name="suffix">
<string>°</string>
</property>
<property name="decimals">
<number>7</number>
</property>
<property name="minimum">
<double>-90.000000000000000</double>
</property>
<property name="maximum">
<double>90.000000000000000</double>
</property>
<property name="singleStep">
<double>0.000010000000000</double>
</property>
</widget>
</item>
<item>
<widget class="QDoubleSpinBox" name="lonSpinBox">
<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>Longitude in degrees</string>
</property>
<property name="statusTip">
<string>Longitude in degrees</string>
</property>
<property name="keyboardTracking">
<bool>false</bool>
</property>
<property name="prefix">
<string>lon </string>
</property>
<property name="suffix">
<string>°</string>
</property>
<property name="decimals">
<number>7</number>
</property>
<property name="minimum">
<double>-180.000000000000000</double>
</property>
<property name="maximum">
<double>180.000000000000000</double>
</property>
<property name="singleStep">
<double>0.000010000000000</double>
</property>
</widget>
</item>
<item>
<widget class="QDoubleSpinBox" name="altSpinBox">
<property name="sizePolicy">
<sizepolicy hsizetype="Expanding" vsizetype="Fixed">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="toolTip">
<string>Altitude in meters</string>
</property>
<property name="statusTip">
<string>Altitude in meters</string>
</property>
<property name="keyboardTracking">
<bool>false</bool>
</property>
<property name="prefix">
<string>alt </string>
</property>
<property name="suffix">
<string>m</string>
</property>
<property name="decimals">
<number>2</number>
</property>
<property name="minimum">
<double>-100000.000000000000000</double>
</property>
<property name="maximum">
<double>100000.000000000000000</double>
</property>
</widget>
</item>
<item>
<widget class="QDoubleSpinBox" name="yawSpinBox">
<property name="sizePolicy">
<sizepolicy hsizetype="Expanding" vsizetype="Fixed">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="focusPolicy">
<enum>Qt::StrongFocus</enum>
</property>
<property name="toolTip">
<string>Rotary wing only: Desired yaw angle at waypoint</string>
</property>
<property name="statusTip">
<string>Rotary wing only: Desired yaw angle at waypoint</string>
</property>
<property name="wrapping">
<bool>true</bool>
</property>
<property name="keyboardTracking">
<bool>false</bool>
</property>
<property name="prefix">
<string/>
</property>
<property name="suffix">
<string>°</string>
</property>
<property name="decimals">
<number>0</number>
</property>
<property name="minimum">
<double>-180.000000000000000</double>
</property>
<property name="maximum">
<double>180.000000000000000</double>
</property>
</widget>
</item>
</layout>
</widget>
<resources/>
<connections/>
</ui>
......@@ -18,7 +18,7 @@
</property>
<property name="minimumSize">
<size>
<width>200</width>
<width>0</width>
<height>0</height>
</size>
</property>
......
......@@ -18,7 +18,7 @@
</property>
<property name="minimumSize">
<size>
<width>200</width>
<width>0</width>
<height>0</height>
</size>
</property>
......
......@@ -18,7 +18,7 @@
</property>
<property name="minimumSize">
<size>
<width>200</width>
<width>0</width>
<height>0</height>
</size>
</property>
......
#include "QGCMissionNavReturnToLaunch.h"
#include "ui_QGCMissionNavReturnToLaunch.h"
#include "WaypointEditableView.h"
QGCMissionNavReturnToLaunch::QGCMissionNavReturnToLaunch(WaypointEditableView* WEV) :
QWidget(WEV),
ui(new Ui::QGCMissionNavReturnToLaunch)
{
ui->setupUi(this);
this->WEV = WEV;
}
QGCMissionNavReturnToLaunch::~QGCMissionNavReturnToLaunch()
{
delete ui;
}
#ifndef QGCMISSIONNAVRETURNTOLAUNCH_H
#define QGCMISSIONNAVRETURNTOLAUNCH_H
#include <QWidget>
#include "WaypointEditableView.h"
namespace Ui {
class QGCMissionNavReturnToLaunch;
}
class QGCMissionNavReturnToLaunch : public QWidget
{
Q_OBJECT
public:
explicit QGCMissionNavReturnToLaunch(WaypointEditableView* WEV);
~QGCMissionNavReturnToLaunch();
protected:
WaypointEditableView* WEV;
private:
Ui::QGCMissionNavReturnToLaunch *ui;
};
#endif // QGCMISSIONNAVRETURNTOLAUNCH_H
<?xml version="1.0" encoding="UTF-8"?>
<ui version="4.0">
<class>QGCMissionNavReturnToLaunch</class>
<widget class="QWidget" name="QGCMissionNavReturnToLaunch">
<property name="geometry">
<rect>
<x>0</x>
<y>0</y>
<width>258</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>0</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="QLabel" name="noParamLabel">
<property name="text">
<string>No Parameters</string>
</property>
<property name="alignment">
<set>Qt::AlignCenter</set>
</property>
</widget>
</item>
</layout>
</widget>
<resources/>
<connections/>
</ui>
#include "QGCMissionNavTakeoff.h"
#include "ui_QGCMissionNavTakeoff.h"
#include "WaypointEditableView.h"
QGCMissionNavTakeoff::QGCMissionNavTakeoff(WaypointEditableView* WEV) :
QWidget(WEV),
ui(new Ui::QGCMissionNavTakeoff)
{
ui->setupUi(this);
this->WEV = WEV;
//Using UI to change WP:
connect(this->ui->minPitchSpinBox, SIGNAL(valueChanged(double)),WEV,SLOT(changedParam1(double)));
//connect(this->ui->acceptanceSpinBox, SIGNAL(valueChanged(double)),WEV,SLOT(changedParam2(double)));
//connect(this->ui->param3SpinBox, SIGNAL(valueChanged(double)),WEV,SLOT(changedParam3(double)));
connect(this->ui->yawSpinBox, SIGNAL(valueChanged(double)),WEV,SLOT(changedParam4(double)));
connect(this->ui->posNSpinBox, SIGNAL(valueChanged(double)),WEV,SLOT(changedParam5(double)));//NED
connect(this->ui->posESpinBox, SIGNAL(valueChanged(double)),WEV,SLOT(changedParam6(double)));
connect(this->ui->posDSpinBox, SIGNAL(valueChanged(double)),WEV,SLOT(changedParam7(double)));
connect(this->ui->latSpinBox, SIGNAL(valueChanged(double)),WEV,SLOT(changedParam5(double)));//Global
connect(this->ui->lonSpinBox, SIGNAL(valueChanged(double)),WEV,SLOT(changedParam6(double)));
connect(this->ui->altSpinBox, SIGNAL(valueChanged(double)),WEV,SLOT(changedParam7(double)));
//Reading WP to update UI:
connect(WEV,SIGNAL(frameBroadcast(MAV_FRAME)),this,SLOT(updateFrame(MAV_FRAME)));
connect(WEV,SIGNAL(param1Broadcast(double)),this->ui->minPitchSpinBox,SLOT(setValue(double)));
//connect(WEV,SIGNAL(param2Broadcast(double)),this->ui->acceptanceSpinBox,SLOT(setValue(double)));
//connect(WEV,SIGNAL(param3Broadcast(double)),this->ui->param3SpinBox,SLOT(setValue(double)));
connect(WEV,SIGNAL(param4Broadcast(double)),this->ui->yawSpinBox,SLOT(setValue(double)));
connect(WEV,SIGNAL(param5Broadcast(double)),this->ui->posNSpinBox,SLOT(setValue(double)));//NED
connect(WEV,SIGNAL(param6Broadcast(double)),this->ui->posESpinBox,SLOT(setValue(double)));
connect(WEV,SIGNAL(param7Broadcast(double)),this->ui->posDSpinBox,SLOT(setValue(double)));
connect(WEV,SIGNAL(param5Broadcast(double)),this->ui->latSpinBox,SLOT(setValue(double)));//Global
connect(WEV,SIGNAL(param6Broadcast(double)),this->ui->lonSpinBox,SLOT(setValue(double)));
connect(WEV,SIGNAL(param7Broadcast(double)),this->ui->altSpinBox,SLOT(setValue(double)));
}
void QGCMissionNavTakeoff::updateFrame(MAV_FRAME frame)
{
switch(frame)
{
case MAV_FRAME_LOCAL_ENU:
case MAV_FRAME_LOCAL_NED:
this->ui->posNSpinBox->show();
this->ui->posESpinBox->show();
this->ui->posDSpinBox->show();
this->ui->latSpinBox->hide();
this->ui->lonSpinBox->hide();
this->ui->altSpinBox->hide();
break;
case MAV_FRAME_GLOBAL:
case MAV_FRAME_GLOBAL_RELATIVE_ALT:
this->ui->posNSpinBox->hide();
this->ui->posESpinBox->hide();
this->ui->posDSpinBox->hide();
this->ui->latSpinBox->show();
this->ui->lonSpinBox->show();
this->ui->altSpinBox->show();
break;
default:
break;
}
}
QGCMissionNavTakeoff::~QGCMissionNavTakeoff()
{
delete ui;
}
#ifndef QGCMISSIONNAVTAKEOFF_H
#define QGCMISSIONNAVTAKEOFF_H
#include <QWidget>
#include "WaypointEditableView.h"
namespace Ui {
class QGCMissionNavTakeoff;
}
class QGCMissionNavTakeoff : public QWidget
{
Q_OBJECT
public:
explicit QGCMissionNavTakeoff(WaypointEditableView* WEV);
~QGCMissionNavTakeoff();
public slots:
void updateFrame(MAV_FRAME);
protected:
WaypointEditableView* WEV;
private:
Ui::QGCMissionNavTakeoff *ui;
};
#endif // QGCMISSIONNAVTAKEOFF_H
<?xml version="1.0" encoding="UTF-8"?>
<ui version="4.0">
<class>QGCMissionNavTakeoff</class>
<widget class="QWidget" name="QGCMissionNavTakeoff">
<property name="geometry">
<rect>
<x>0</x>
<y>0</y>
<width>2208</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>0</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="posNSpinBox">
<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>Position X coordinate</string>
</property>
<property name="statusTip">
<string>Position X corrdinate</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>N </string>
</property>
<property name="suffix">
<string> m</string>
</property>
<property name="minimum">
<double>-10000.000000000000000</double>
</property>
<property name="maximum">
<double>10000.000000000000000</double>
</property>
<property name="singleStep">
<double>0.050000000000000</double>
</property>
</widget>
</item>
<item>
<widget class="QDoubleSpinBox" name="posESpinBox">
<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>Position Y/Longitude coordinate</string>
</property>
<property name="statusTip">
<string>Position Y/Longitude coordinate</string>
</property>
<property name="keyboardTracking">
<bool>false</bool>
</property>
<property name="prefix">
<string>E </string>
</property>
<property name="suffix">
<string> m</string>
</property>
<property name="minimum">
<double>-10000.000000000000000</double>
</property>
<property name="maximum">
<double>10000.000000000000000</double>
</property>
<property name="singleStep">
<double>0.050000000000000</double>
</property>
<property name="value">
<double>0.000000000000000</double>
</property>
</widget>
</item>
<item>
<widget class="QDoubleSpinBox" name="posDSpinBox">
<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>Position Z coordinate (local frame, negative)</string>
</property>
<property name="statusTip">
<string/>
</property>
<property name="keyboardTracking">
<bool>false</bool>
</property>
<property name="prefix">
<string>D </string>
</property>
<property name="suffix">
<string> m</string>
</property>
<property name="minimum">
<double>-10000.000000000000000</double>
</property>
<property name="maximum">
<double>10000.000000000000000</double>
</property>
<property name="singleStep">
<double>0.050000000000000</double>
</property>
</widget>
</item>
<item>
<widget class="QDoubleSpinBox" name="latSpinBox">
<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>Latitude in degrees</string>
</property>
<property name="statusTip">
<string>Latitude in degrees</string>
</property>
<property name="keyboardTracking">
<bool>false</bool>
</property>
<property name="prefix">
<string>lat </string>
</property>
<property name="suffix">
<string>°</string>
</property>
<property name="decimals">
<number>7</number>
</property>
<property name="minimum">
<double>-90.000000000000000</double>
</property>
<property name="maximum">
<double>90.000000000000000</double>
</property>
<property name="singleStep">
<double>0.000010000000000</double>
</property>
</widget>
</item>
<item>
<widget class="QDoubleSpinBox" name="lonSpinBox">
<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>Longitude in degrees</string>
</property>
<property name="statusTip">
<string>Longitude in degrees</string>
</property>
<property name="keyboardTracking">
<bool>false</bool>
</property>
<property name="prefix">
<string>lon </string>
</property>
<property name="suffix">
<string>°</string>
</property>
<property name="decimals">
<number>7</number>
</property>
<property name="minimum">
<double>-180.000000000000000</double>
</property>
<property name="maximum">
<double>180.000000000000000</double>
</property>
<property name="singleStep">
<double>0.000010000000000</double>
</property>
</widget>
</item>
<item>
<widget class="QDoubleSpinBox" name="altSpinBox">
<property name="sizePolicy">
<sizepolicy hsizetype="Expanding" vsizetype="Fixed">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="toolTip">
<string>Altitude in meters</string>
</property>
<property name="statusTip">
<string>Altitude in meters</string>
</property>
<property name="keyboardTracking">
<bool>false</bool>
</property>
<property name="prefix">
<string>alt </string>
</property>
<property name="suffix">
<string>m</string>
</property>
<property name="decimals">
<number>2</number>
</property>
<property name="minimum">
<double>-100000.000000000000000</double>
</property>
<property name="maximum">
<double>100000.000000000000000</double>
</property>
</widget>
</item>
<item>
<widget class="QDoubleSpinBox" name="yawSpinBox">
<property name="sizePolicy">
<sizepolicy hsizetype="Expanding" vsizetype="Fixed">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="focusPolicy">
<enum>Qt::StrongFocus</enum>
</property>
<property name="toolTip">
<string>Rotary wing only: Desired yaw angle at waypoint</string>
</property>
<property name="statusTip">
<string>Rotary wing only: Desired yaw angle at waypoint</string>
</property>
<property name="wrapping">
<bool>true</bool>
</property>
<property name="keyboardTracking">
<bool>false</bool>
</property>
<property name="prefix">
<string/>
</property>
<property name="suffix">
<string>°</string>
</property>
<property name="decimals">
<number>0</number>
</property>
<property name="minimum">
<double>-180.000000000000000</double>
</property>
<property name="maximum">
<double>180.000000000000000</double>
</property>
</widget>
</item>
<item>
<widget class="QDoubleSpinBox" name="minPitchSpinBox">
<property name="sizePolicy">
<sizepolicy hsizetype="MinimumExpanding" vsizetype="Fixed">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="toolTip">
<string>Minimum Pitch</string>
</property>
<property name="statusTip">
<string>Minimum Pitch</string>
</property>
<property name="keyboardTracking">
<bool>false</bool>
</property>
<property name="suffix">
<string>°</string>
</property>
<property name="decimals">
<number>0</number>
</property>
<property name="minimum">
<double>-90.000000000000000</double>
</property>
<property name="maximum">
<double>90.000000000000000</double>
</property>
<property name="value">
<double>0.000000000000000</double>
</property>
</widget>
</item>
</layout>
</widget>
<resources/>
<connections/>
</ui>
......@@ -18,7 +18,7 @@
</property>
<property name="minimumSize">
<size>
<width>200</width>
<width>0</width>
<height>0</height>
</size>
</property>
......
......@@ -10,6 +10,18 @@
<height>27</height>
</rect>
</property>
<property name="sizePolicy">
<sizepolicy hsizetype="Preferred" vsizetype="Preferred">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="minimumSize">
<size>
<width>0</width>
<height>0</height>
</size>
</property>
<property name="windowTitle">
<string>Form</string>
</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