Commit 4044530f authored by pixhawk's avatar pixhawk

Backup. Do not use

parent aa5d5043
......@@ -239,7 +239,8 @@ FORMS += src/ui/MainWindow.ui \
src/ui/mavlink/QGCMAVLinkMessageSender.ui \
src/ui/firmwareupdate/QGCFirmwareUpdateWidget.ui \
src/ui/QGCPluginHost.ui \
src/ui/firmwareupdate/QGCPX4FirmwareUpdate.ui
src/ui/firmwareupdate/QGCPX4FirmwareUpdate.ui \
src/ui/mission/QGCMissionOther.ui
INCLUDEPATH += src \
src/ui \
src/ui/linechart \
......@@ -254,6 +255,7 @@ INCLUDEPATH += src \
src/ui/param \
src/ui/watchdog \
src/ui/map3D \
src/ui/mission \
src/ui/designer
HEADERS += src/MG.h \
src/QGCCore.h \
......@@ -361,7 +363,8 @@ HEADERS += src/MG.h \
src/ui/mavlink/QGCMAVLinkMessageSender.h \
src/ui/firmwareupdate/QGCFirmwareUpdateWidget.h \
src/ui/QGCPluginHost.h \
src/ui/firmwareupdate/QGCPX4FirmwareUpdate.h
src/ui/firmwareupdate/QGCPX4FirmwareUpdate.h \
src/ui/mission/QGCMissionOther.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
......@@ -493,7 +496,8 @@ SOURCES += src/main.cc \
src/ui/mavlink/QGCMAVLinkMessageSender.cc \
src/ui/firmwareupdate/QGCFirmwareUpdateWidget.cc \
src/ui/QGCPluginHost.cc \
src/ui/firmwareupdate/QGCPX4FirmwareUpdate.cc
src/ui/firmwareupdate/QGCPX4FirmwareUpdate.cc \
src/ui/mission/QGCMissionOther.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
......
......@@ -21,11 +21,15 @@
#include "ui_WaypointEditableView.h"
#include "ui_QGCCustomWaypointAction.h"
#include "ui_QGCMissionDoWidget.h"
#include "ui_QGCMissionOther.h"
#include "QGCMissionDoWidget.h"
#include "QGCMissionConditionWidget.h"
#include "QGCMissionOther.h"
WaypointEditableView::WaypointEditableView(Waypoint* wp, QWidget* parent) :
QWidget(parent),
customCommand(new Ui_QGCCustomWaypointAction),
doCommand(new Ui_QGCMissionDoWidget),
viewMode(QGC_WAYPOINTEDITABLEVIEW_MODE_NAV),
m_ui(new Ui::WaypointEditableView)
{
......@@ -34,10 +38,40 @@ WaypointEditableView::WaypointEditableView(Waypoint* wp, QWidget* parent) :
this->wp = wp;
connect(wp, SIGNAL(destroyed(QObject*)), this, SLOT(deleted(QObject*)));
// CUSTOM COMMAND WIDGET
customCommand->setupUi(m_ui->customActionWidget);
// CUSTOM COMMAND WIDGET
// DO COMMAND WIDGET
//doCommand->setupUi(m_ui->customActionWidget);
/*
doCommand->setupUi(m_ui->customActionWidget);
QVBoxLayout *layout = new QVBoxLayout;
layout->addWidget(doCommand);
layout->addWidget(customCommand);
m_ui->customActionWidget->setLayout(layout);
*/
//Ui_QGCCustomWaypointAction *act = new Ui_QGCCustomWaypointAction;
MissionDoJumpWidget = new QGCMissionDoWidget(this);
MissionConditionDelayWidget = new QGCMissionConditionWidget(this);
MissionOtherWidget = new QGCMissionOther(this);
QHBoxLayout *layout = new QHBoxLayout;
layout->addWidget(MissionOtherWidget);
layout->setSpacing(2);
layout->setContentsMargins(4, 4 ,4 ,4);
m_ui->customActionWidget->setLayout(layout);
//qDebug() << "Count before " << m_ui->customActionWidget->layout()->count();
QDoubleSpinBox *param1widget = new QDoubleSpinBox;
//param1widget->setva
param1widget = MissionOtherWidget->findChild<QDoubleSpinBox *>("param1SpinBox");
param1widget->hide();
MissionOtherWidget->hide();
m_ui->customActionWidget->layout()->addWidget(MissionDoJumpWidget);
MissionDoJumpWidget->hide();
MissionOtherWidget->show();
m_ui->customActionWidget->layout()->addWidget(MissionConditionDelayWidget);
MissionConditionDelayWidget->hide();
// add actions
......@@ -49,9 +83,9 @@ WaypointEditableView::WaypointEditableView(Waypoint* wp, QWidget* parent) :
m_ui->comboBox_action->addItem(tr("NAV: Ret. to Launch"),MAV_CMD_NAV_RETURN_TO_LAUNCH);
m_ui->comboBox_action->addItem(tr("NAV: Land"),MAV_CMD_NAV_LAND);
//m_ui->comboBox_action->addItem(tr("NAV: Target"),MAV_CMD_NAV_TARGET);
//m_ui->comboBox_action->addItem(tr("IF: Delay over"),MAV_CMD_CONDITION_DELAY);
m_ui->comboBox_action->addItem(tr("IF: Delay over"),MAV_CMD_CONDITION_DELAY);
//m_ui->comboBox_action->addItem(tr("IF: Yaw angle is"),MAV_CMD_CONDITION_YAW);
//m_ui->comboBox_action->addItem(tr("DO: Jump to Index"),MAV_CMD_DO_JUMP);
m_ui->comboBox_action->addItem(tr("DO: Jump to Index"),MAV_CMD_DO_JUMP);
m_ui->comboBox_action->addItem(tr("Other"), MAV_CMD_ENUM_END);
// add frames
......@@ -97,6 +131,7 @@ WaypointEditableView::WaypointEditableView(Waypoint* wp, QWidget* parent) :
connect(m_ui->turnsSpinBox, SIGNAL(valueChanged(int)), wp, SLOT(setTurns(int)));
connect(m_ui->takeOffAngleSpinBox, SIGNAL(valueChanged(double)), wp, SLOT(setParam1(double)));
/*
// Connect actions
connect(customCommand->commandSpinBox, SIGNAL(valueChanged(int)), wp, SLOT(setAction(int)));
connect(customCommand->param1SpinBox, SIGNAL(valueChanged(double)), wp, SLOT(setParam1(double)));
......@@ -106,6 +141,17 @@ WaypointEditableView::WaypointEditableView(Waypoint* wp, QWidget* parent) :
connect(customCommand->param5SpinBox, SIGNAL(valueChanged(double)), wp, SLOT(setParam5(double)));
connect(customCommand->param6SpinBox, SIGNAL(valueChanged(double)), wp, SLOT(setParam6(double)));
connect(customCommand->param7SpinBox, SIGNAL(valueChanged(double)), wp, SLOT(setParam7(double)));
customCommand->param1SpinBox->hide();
customCommand->param2SpinBox->hide();
customCommand->param3SpinBox->hide();
customCommand->param4SpinBox->hide();
customCommand->param5SpinBox->hide();
customCommand->param6SpinBox->hide();
customCommand->param7SpinBox->hide();
customCommand->commandSpinBox->hide();
*/
}
void WaypointEditableView::moveUp()
......@@ -144,12 +190,10 @@ void WaypointEditableView::updateActionView(int action)
m_ui->orbitSpinBox->hide();
m_ui->yawSpinBox->hide();
m_ui->turnsSpinBox->hide();
m_ui->autoContinue->hide();
//m_ui->autoContinue->hide();
m_ui->holdTimeSpinBox->hide();
m_ui->acceptanceSpinBox->hide();
m_ui->customActionWidget->hide();
m_ui->missionDoWidgetSlot->hide();
m_ui->missionConditionWidgetSlot->hide();
//m_ui->customActionWidget->hide();
m_ui->horizontalLayout->insertStretch(17, 82);
m_ui->takeOffAngleSpinBox->show();
break;
......@@ -161,9 +205,7 @@ void WaypointEditableView::updateActionView(int action)
m_ui->autoContinue->hide();
m_ui->holdTimeSpinBox->hide();
m_ui->acceptanceSpinBox->hide();
m_ui->customActionWidget->hide();
m_ui->missionDoWidgetSlot->hide();
m_ui->missionConditionWidgetSlot->hide();
//m_ui->customActionWidget->hide();
m_ui->horizontalLayout->insertStretch(17, 26);
break;
case MAV_CMD_NAV_RETURN_TO_LAUNCH:
......@@ -174,9 +216,7 @@ void WaypointEditableView::updateActionView(int action)
m_ui->autoContinue->hide();
m_ui->holdTimeSpinBox->hide();
m_ui->acceptanceSpinBox->hide();
m_ui->customActionWidget->hide();
m_ui->missionDoWidgetSlot->hide();
m_ui->missionConditionWidgetSlot->hide();
//m_ui->customActionWidget->hide();
m_ui->horizontalLayout->insertStretch(17, 26);
break;
case MAV_CMD_NAV_WAYPOINT:
......@@ -184,11 +224,8 @@ void WaypointEditableView::updateActionView(int action)
m_ui->takeOffAngleSpinBox->hide();
m_ui->turnsSpinBox->hide();
m_ui->holdTimeSpinBox->show();
m_ui->customActionWidget->hide();
m_ui->missionDoWidgetSlot->hide();
m_ui->missionConditionWidgetSlot->hide();
//m_ui->customActionWidget->hide();
m_ui->horizontalLayout->insertStretch(17, 1);
m_ui->autoContinue->show();
m_ui->acceptanceSpinBox->show();
m_ui->yawSpinBox->show();
......@@ -200,9 +237,7 @@ void WaypointEditableView::updateActionView(int action)
m_ui->autoContinue->hide();
m_ui->holdTimeSpinBox->hide();
m_ui->acceptanceSpinBox->hide();
m_ui->customActionWidget->hide();
m_ui->missionDoWidgetSlot->hide();
m_ui->missionConditionWidgetSlot->hide();
//m_ui->customActionWidget->hide();
m_ui->horizontalLayout->insertStretch(17, 25);
m_ui->orbitSpinBox->show();
break;
......@@ -212,9 +247,7 @@ void WaypointEditableView::updateActionView(int action)
m_ui->autoContinue->hide();
m_ui->holdTimeSpinBox->hide();
m_ui->acceptanceSpinBox->hide();
m_ui->customActionWidget->hide();
m_ui->missionDoWidgetSlot->hide();
m_ui->missionConditionWidgetSlot->hide();
//m_ui->customActionWidget->hide();
m_ui->horizontalLayout->insertStretch(17, 20);
m_ui->orbitSpinBox->show();
m_ui->turnsSpinBox->show();
......@@ -225,9 +258,7 @@ void WaypointEditableView::updateActionView(int action)
m_ui->turnsSpinBox->hide();
m_ui->autoContinue->hide();
m_ui->acceptanceSpinBox->hide();
m_ui->customActionWidget->hide();
m_ui->missionDoWidgetSlot->hide();
m_ui->missionConditionWidgetSlot->hide();
//m_ui->customActionWidget->hide();
m_ui->horizontalLayout->insertStretch(17, 20);
m_ui->orbitSpinBox->show();
m_ui->holdTimeSpinBox->show();
......@@ -237,9 +268,8 @@ void WaypointEditableView::updateActionView(int action)
// m_ui->takeOffAngleSpinBox->hide();
// m_ui->turnsSpinBox->hide();
// m_ui->holdTimeSpinBox->show();
// m_ui->customActionWidget->hide();
// m_ui->missionDoWidgetSlot->hide();
// m_ui->missionConditionWidgetSlot->hide();
// //m_ui->customActionWidget->hide();
// m_ui->autoContinue->show();
// m_ui->acceptanceSpinBox->hide();
// m_ui->yawSpinBox->hide();
......@@ -318,13 +348,10 @@ void WaypointEditableView::changeViewMode(QGC_WAYPOINTEDITABLEVIEW_MODE mode)
m_ui->lonSpinBox->hide();
m_ui->altSpinBox->hide();
// Show action widget
if (!m_ui->missionDoWidgetSlot->isVisible()) {
m_ui->missionDoWidgetSlot->show();
}
if (!m_ui->autoContinue->isVisible()) {
m_ui->autoContinue->show();
}
MissionOtherWidget->hide();
//if (!MissionDoJumpWidget->isVisible()) {
MissionDoJumpWidget->show();
//}
break;
}
case QGC_WAYPOINTEDITABLEVIEW_MODE_DIRECT_EDITING:
......@@ -342,13 +369,15 @@ void WaypointEditableView::changeViewMode(QGC_WAYPOINTEDITABLEVIEW_MODE mode)
m_ui->lonSpinBox->hide();
m_ui->altSpinBox->hide();
MissionDoJumpWidget->hide();
int action_index = m_ui->comboBox_action->findData(MAV_CMD_ENUM_END);
m_ui->comboBox_action->setCurrentIndex(action_index);
// Show action widget
if (!m_ui->customActionWidget->isVisible()) {
m_ui->customActionWidget->show();
}
//if (!MissionOtherWidget->isVisible()) {
MissionOtherWidget->show();
//}
if (!m_ui->autoContinue->isVisible()) {
m_ui->autoContinue->show();
}
......@@ -372,9 +401,7 @@ void WaypointEditableView::updateFrameView(int frame)
m_ui->altSpinBox->show();
// Coordinate frame
m_ui->comboBox_frame->show();
m_ui->customActionWidget->hide();
m_ui->missionDoWidgetSlot->hide();
m_ui->missionConditionWidgetSlot->hide();
//m_ui->customActionWidget->hide();
}
else // do not hide customActionWidget if Command is set to "Other"
{
......@@ -392,9 +419,7 @@ void WaypointEditableView::updateFrameView(int frame)
m_ui->posDSpinBox->show();
// Coordinate frame
m_ui->comboBox_frame->show();
m_ui->customActionWidget->hide();
m_ui->missionDoWidgetSlot->hide();
m_ui->missionConditionWidgetSlot->hide();
//m_ui->customActionWidget->hide();
}
else // do not hide customActionWidget if Command is set to "Other"
{
......@@ -647,7 +672,7 @@ void WaypointEditableView::updateValues()
}
// // UPDATE CUSTOM ACTION WIDGET
/*
if (customCommand->commandSpinBox->value() != wp->getAction())
{
customCommand->commandSpinBox->setValue(wp->getAction());
......@@ -681,7 +706,7 @@ void WaypointEditableView::updateValues()
if (customCommand->param7SpinBox->value() != wp->getParam7()) {
customCommand->param7SpinBox->setValue(wp->getParam7());
}
*/
QColor backGroundColor = QGC::colorBackground;
static int lastId = -1;
......@@ -706,11 +731,13 @@ void WaypointEditableView::updateValues()
QString groupBoxStyle = QString("QGroupBox {padding: 0px; margin: 0px; border: 0px; background-color: %1; }").arg(backGroundColor.name());
QString labelStyle = QString("QWidget {background-color: %1; color: #DDDDDF; border-color: #EEEEEE; }").arg(backGroundColor.name());
QString checkBoxStyle = QString("QCheckBox {background-color: %1; color: #454545; border-color: #EEEEEE; }").arg(backGroundColor.name());
QString widgetSlotStyle = QString("QWidget {background-color: %1; color: #DDDDDF; border-color: #EEEEEE; } QSpinBox {background-color: #252528 } QDoubleSpinBox {background-color: #252528 } QComboBox {background-color: #252528 }").arg(backGroundColor.name()); //FIXME There should be a way to declare background color for widgetSlot without letting the children inherit this color. Here, background color for every widget-type (QSpinBox, etc.) has to be declared separately to overrule the coloring of QWidget.
m_ui->autoContinue->setStyleSheet(checkBoxStyle);
m_ui->selectedBox->setStyleSheet(checkBoxStyle);
m_ui->idLabel->setStyleSheet(labelStyle);
m_ui->groupBox->setStyleSheet(groupBoxStyle);
m_ui->customActionWidget->setStyleSheet(widgetSlotStyle);
lastId = currId;
}
......
......@@ -48,8 +48,11 @@ namespace Ui
{
class WaypointEditableView;
}
class Ui_QGCCustomWaypointAction;
class Ui_QGCMissionDoWidget;
//class Ui_QGCCustomWaypointAction;
//class Ui_QGCMissionDoWidget;
class QGCMissionDoWidget;
class QGCMissionConditionWidget;
class QGCMissionOther;
class WaypointEditableView : public QWidget
{
Q_OBJECT
......@@ -83,8 +86,9 @@ protected:
Waypoint* wp;
// Special widgets extendending the
// waypoint view to mission capabilities
Ui_QGCCustomWaypointAction* customCommand;
Ui_QGCMissionDoWidget* doCommand;
QGCMissionDoWidget* MissionDoJumpWidget;
QGCMissionConditionWidget* MissionConditionDelayWidget;
QGCMissionOther* MissionOtherWidget;
QGC_WAYPOINTEDITABLEVIEW_MODE viewMode;
private:
......
......@@ -96,7 +96,7 @@ QPushButton:pressed {
<property name="title">
<string/>
</property>
<layout class="QHBoxLayout" name="horizontalLayout" stretch="5,5,5,5,50,50,50,50,50,50,5,20,20,5,10,10,0,0,0,20,5,5,5,5">
<layout class="QHBoxLayout" name="horizontalLayout" stretch="2,5,20,20,50,50,50,50,50,50,5,20,20,5,10,10,200,5,0,0,0,0">
<property name="spacing">
<number>2</number>
</property>
......@@ -113,7 +113,7 @@ QPushButton:pressed {
</property>
<property name="minimumSize">
<size>
<width>25</width>
<width>20</width>
<height>0</height>
</size>
</property>
......@@ -165,11 +165,17 @@ QPushButton:pressed {
<item>
<widget class="QComboBox" name="comboBox_action">
<property name="sizePolicy">
<sizepolicy hsizetype="Expanding" vsizetype="Fixed">
<sizepolicy hsizetype="Minimum" vsizetype="Fixed">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="maximumSize">
<size>
<width>120</width>
<height>16777215</height>
</size>
</property>
<property name="toolTip">
<string>Action at Waypoint</string>
</property>
......@@ -184,11 +190,17 @@ QPushButton:pressed {
<item>
<widget class="QComboBox" name="comboBox_frame">
<property name="sizePolicy">
<sizepolicy hsizetype="Expanding" vsizetype="Fixed">
<sizepolicy hsizetype="Minimum" vsizetype="Fixed">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="maximumSize">
<size>
<width>100</width>
<height>16777215</height>
</size>
</property>
<property name="toolTip">
<string>Coordinate frame</string>
</property>
......@@ -594,7 +606,7 @@ where to accept this waypoint as reached</string>
<item>
<widget class="QWidget" name="customActionWidget" native="true">
<property name="sizePolicy">
<sizepolicy hsizetype="MinimumExpanding" vsizetype="Preferred">
<sizepolicy hsizetype="Expanding" vsizetype="Preferred">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
......@@ -607,26 +619,6 @@ where to accept this waypoint as reached</string>
</property>
</widget>
</item>
<item>
<widget class="QWidget" name="missionDoWidgetSlot" native="true">
<property name="sizePolicy">
<sizepolicy hsizetype="MinimumExpanding" vsizetype="Preferred">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
</widget>
</item>
<item>
<widget class="QWidget" name="missionConditionWidgetSlot" native="true">
<property name="sizePolicy">
<sizepolicy hsizetype="MinimumExpanding" vsizetype="Preferred">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
</widget>
</item>
<item>
<spacer name="removeSpacer">
<property name="orientation">
......@@ -635,7 +627,7 @@ where to accept this waypoint as reached</string>
<property name="sizeHint" stdset="0">
<size>
<width>5</width>
<height>20</height>
<height>10</height>
</size>
</property>
</spacer>
......@@ -643,7 +635,7 @@ where to accept this waypoint as reached</string>
<item>
<widget class="QCheckBox" name="autoContinue">
<property name="sizePolicy">
<sizepolicy hsizetype="MinimumExpanding" vsizetype="Fixed">
<sizepolicy hsizetype="Fixed" vsizetype="Fixed">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
......@@ -661,6 +653,12 @@ where to accept this waypoint as reached</string>
</item>
<item>
<widget class="QPushButton" name="upButton">
<property name="sizePolicy">
<sizepolicy hsizetype="Fixed" vsizetype="Fixed">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="minimumSize">
<size>
<width>28</width>
......@@ -687,6 +685,12 @@ where to accept this waypoint as reached</string>
</item>
<item>
<widget class="QPushButton" name="downButton">
<property name="sizePolicy">
<sizepolicy hsizetype="Fixed" vsizetype="Fixed">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="minimumSize">
<size>
<width>28</width>
......@@ -713,6 +717,12 @@ where to accept this waypoint as reached</string>
</item>
<item>
<widget class="QPushButton" name="removeButton">
<property name="sizePolicy">
<sizepolicy hsizetype="Fixed" vsizetype="Fixed">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="minimumSize">
<size>
<width>28</width>
......
/*=====================================================================
PIXHAWK Micro Air Vehicle Flying Robotics Toolkit
(c) 2009, 2010 PIXHAWK PROJECT <http://pixhawk.ethz.ch>
This file is part of the PIXHAWK project
PIXHAWK is free software: you can redistribute it and/or modify
it under the terms of the GNU General Public License as published by
the Free Software Foundation, either version 3 of the License, or
(at your option) any later version.
PIXHAWK is distributed in the hope that it will be useful,
but WITHOUT ANY WARRANTY; without even the implied warranty of
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
GNU General Public License for more details.
You should have received a copy of the GNU General Public License
along with PIXHAWK. If not, see <http://www.gnu.org/licenses/>.
======================================================================*/
/**
* @file
* @brief Waypoint list widget
*
* @author Lorenz Meier <mavteam@student.ethz.ch>
* @author Benjamin Knecht <mavteam@student.ethz.ch>
* @author Petri Tanskanen <mavteam@student.ethz.ch>
*
*/
#include "WaypointList.h"
#include "ui_WaypointList.h"
#include <UASInterface.h>
#include <UASManager.h>
#include <QDebug>
#include <QFileDialog>
#include <QMessageBox>
#include <QMouseEvent>
WaypointList::WaypointList(QWidget *parent, UASInterface* uas) :
QWidget(parent),
uas(NULL),
mavX(0.0),
mavY(0.0),
mavZ(0.0),
mavYaw(0.0),
showOfflineWarning(false),
m_ui(new Ui::WaypointList)
{
m_ui->setupUi(this);
//EDIT TAB
editableListLayout = new QVBoxLayout(m_ui->editableListWidget);
editableListLayout->setSpacing(0);
editableListLayout->setMargin(0);
editableListLayout->setAlignment(Qt::AlignTop);
m_ui->editableListWidget->setLayout(editableListLayout);
// ADD WAYPOINT
// Connect add action, set right button icon and connect action to this class
connect(m_ui->addButton, SIGNAL(clicked()), m_ui->actionAddWaypoint, SIGNAL(triggered()));
connect(m_ui->actionAddWaypoint, SIGNAL(triggered()), this, SLOT(addEditable()));
// ADD WAYPOINT AT CURRENT POSITION
connect(m_ui->positionAddButton, SIGNAL(clicked()), this, SLOT(addCurrentPositionWaypoint()));
// SEND WAYPOINTS
connect(m_ui->transmitButton, SIGNAL(clicked()), this, SLOT(transmit()));
// DELETE ALL WAYPOINTS
connect(m_ui->clearWPListButton, SIGNAL(clicked()), this, SLOT(clearWPWidget()));
// REQUEST WAYPOINTS
connect(m_ui->readButton, SIGNAL(clicked()), this, SLOT(read()));
// SAVE/LOAD WAYPOINTS
connect(m_ui->saveButton, SIGNAL(clicked()), this, SLOT(saveWaypoints()));
connect(m_ui->loadButton, SIGNAL(clicked()), this, SLOT(loadWaypoints()));
//connect(UASManager::instance(), SIGNAL(activeUASSet(UASInterface*)), this, SLOT(setUAS(UASInterface*)));
//VIEW TAB
viewOnlyListLayout = new QVBoxLayout(m_ui->viewOnlyListWidget);
viewOnlyListLayout->setSpacing(0);
viewOnlyListLayout->setMargin(0);
viewOnlyListLayout->setAlignment(Qt::AlignTop);
m_ui->viewOnlyListWidget->setLayout(viewOnlyListLayout);
// REFRESH VIEW TAB
connect(m_ui->refreshButton, SIGNAL(clicked()), this, SLOT(refresh()));
// SET UAS AFTER ALL SIGNALS/SLOTS ARE CONNECTED
if (uas)
{
WPM = uas->getWaypointManager();
//setUAS(uas);
}
else
{
// Hide buttons, which don't make sense without valid UAS
m_ui->positionAddButton->hide();
m_ui->transmitButton->hide();
m_ui->readButton->hide();
m_ui->refreshButton->hide();
//FIXME: The whole "Onboard Waypoints"-tab should be hidden, instead of "refresh" button
UnconnectedUASInfoWidget* inf = new UnconnectedUASInfoWidget(this);
viewOnlyListLayout->insertWidget(0, inf); //insert a "NO UAV" info into the Onboard Tab
showOfflineWarning = true;
WPM = new UASWaypointManager(NULL);
}
setUAS(uas);
// STATUS LABEL
updateStatusLabel("");
this->setVisible(false);
loadFileGlobalWP = false;
readGlobalWP = false;
centerMapCoordinate.setX(0.0);
centerMapCoordinate.setY(0.0);
}
WaypointList::~WaypointList()
{
delete m_ui;
}
void WaypointList::updatePosition(UASInterface* uas, double x, double y, double z, quint64 usec)
{
Q_UNUSED(uas);
Q_UNUSED(usec);
mavX = x;
mavY = y;
mavZ = z;
}
void WaypointList::updateAttitude(UASInterface* uas, double roll, double pitch, double yaw, quint64 usec)
{
Q_UNUSED(uas);
Q_UNUSED(usec);
Q_UNUSED(roll);
Q_UNUSED(pitch);
mavYaw = yaw;
}
void WaypointList::setUAS(UASInterface* uas)
{
//if (this->uas == NULL && uas != NULL)
if (this->uas == NULL)
{
this->uas = uas;
<<<<<<< HEAD
=======
if(uas != NULL)
{
connect(uas, SIGNAL(localPositionChanged(UASInterface*,double,double,double,quint64)), this, SLOT(updatePosition(UASInterface*,double,double,double,quint64)));
connect(uas, SIGNAL(attitudeChanged(UASInterface*,double,double,double,quint64)), this, SLOT(updateAttitude(UASInterface*,double,double,double,quint64)));
}
>>>>>>> 25e35803a3bef8d831e710769b2c1eb3ee2f967e
connect(WPM, SIGNAL(updateStatusString(const QString &)), this, SLOT(updateStatusLabel(const QString &)));
connect(WPM, SIGNAL(waypointEditableListChanged(void)), this, SLOT(waypointEditableListChanged(void)));
connect(WPM, SIGNAL(waypointEditableChanged(int,Waypoint*)), this, SLOT(updateWaypointEditable(int,Waypoint*)));
connect(WPM, SIGNAL(waypointViewOnlyListChanged(void)), this, SLOT(waypointViewOnlyListChanged(void)));
connect(WPM, SIGNAL(waypointViewOnlyChanged(int,Waypoint*)), this, SLOT(updateWaypointViewOnly(int,Waypoint*)));
connect(WPM, SIGNAL(currentWaypointChanged(quint16)), this, SLOT(currentWaypointViewOnlyChanged(quint16)));
if (uas != NULL)
{
connect(uas, SIGNAL(localPositionChanged(UASInterface*,double,double,double,quint64)), this, SLOT(updatePosition(UASInterface*,double,double,double,quint64)));
connect(uas, SIGNAL(attitudeChanged(UASInterface*,double,double,double,quint64)), this, SLOT(updateAttitude(UASInterface*,double,double,double,quint64)));
}
//connect(WPM,SIGNAL(loadWPFile()),this,SLOT(setIsLoadFileWP()));
//connect(WPM,SIGNAL(readGlobalWPFromUAS(bool)),this,SLOT(setIsReadGlobalWP(bool)));
}
}
void WaypointList::saveWaypoints()
{
QString fileName = QFileDialog::getSaveFileName(this, tr("Save File"), "./waypoints.txt", tr("Waypoint File (*.txt)"));
WPM->saveWaypoints(fileName);
}
void WaypointList::loadWaypoints()
{
//create a popup notifying the user about the limitations of offline editing
if (showOfflineWarning == true)
{
QMessageBox msgBox;
msgBox.setIcon(QMessageBox::Warning);
msgBox.setText("Offline editor!");
msgBox.setInformativeText("You are using the offline mission editor. Please don't forget to save your mission plan before connecting the UAV, otherwise it will be lost.");
msgBox.setStandardButtons(QMessageBox::Ok);
msgBox.setDefaultButton(QMessageBox::Ok);
int ret = msgBox.exec();
showOfflineWarning = false;
}
QString fileName = QFileDialog::getOpenFileName(this, tr("Load File"), ".", tr("Waypoint File (*.txt)"));
WPM->loadWaypoints(fileName);
}
void WaypointList::transmit()
{
if (uas)
{
WPM->writeWaypoints();
}
}
void WaypointList::read()
{
if (uas)
{
WPM->readWaypoints(true);
}
}
void WaypointList::refresh()
{
if (uas)
{
WPM->readWaypoints(false);
}
}
void WaypointList::addEditable()
{
const QVector<Waypoint *> &waypoints = WPM->getWaypointEditableList();
Waypoint *wp;
if (waypoints.size() > 0)
{
// Create waypoint with last frame
Waypoint *last = waypoints.at(waypoints.size()-1);
wp = new Waypoint(0, last->getX(), last->getY(), last->getZ(), last->getParam1(), last->getParam2(), last->getParam3(), last->getParam4(),
last->getAutoContinue(), false, last->getFrame(), last->getAction());
WPM->addWaypointEditable(wp);
}
else
{
if (uas)
{
// Create first waypoint at current MAV position
addCurrentPositionWaypoint();
}
else
{
//Since no UAV available, create first default waypoint.
updateStatusLabel(tr("No UAV. Added default LOCAL (NED) waypoint"));
wp = new Waypoint(0, 0, 0, -0.50, 0, 0.20, 0, 0,true, true, MAV_FRAME_LOCAL_NED, MAV_CMD_NAV_WAYPOINT);
WPM->addWaypointEditable(wp);
//create a popup notifying the user about the limitations of offline editing
if (showOfflineWarning == true)
{
QMessageBox msgBox;
msgBox.setIcon(QMessageBox::Warning);
msgBox.setText("Offline editor!");
msgBox.setInformativeText("You are using the offline mission editor. Please don't forget to save your mission plan before connecting the UAV, otherwise it will be lost.");
msgBox.setStandardButtons(QMessageBox::Ok);
msgBox.setDefaultButton(QMessageBox::Ok);
int ret = msgBox.exec();
showOfflineWarning = false;
}
}
}
}
void WaypointList::addCurrentPositionWaypoint()
{
if (uas)
{
const QVector<Waypoint *> &waypoints = WPM->getWaypointEditableList();
Waypoint *wp;
Waypoint *last = 0;
if (waypoints.size() > 0)
{
last = waypoints.at(waypoints.size()-1);
}
if (uas->globalPositionKnown())
{
float acceptanceRadiusGlobal = 10.0f;
float holdTime = 0.0f;
float yawGlobal = 0.0f;
if (last)
{
acceptanceRadiusGlobal = last->getAcceptanceRadius();
holdTime = last->getHoldTime();
yawGlobal = last->getYaw();
}
// Create global frame waypoint per default
wp = new Waypoint(0, uas->getLatitude(), uas->getLongitude(), uas->getAltitude(), 0, acceptanceRadiusGlobal, holdTime, yawGlobal, true, false, MAV_FRAME_GLOBAL_RELATIVE_ALT, MAV_CMD_NAV_WAYPOINT);
WPM->addWaypointEditable(wp);
updateStatusLabel(tr("Added GLOBAL, ALTITUDE OVER GROUND waypoint"));
}
else if (uas->localPositionKnown())
{
float acceptanceRadiusLocal = 0.2f;
float holdTime = 0.5f;
if (last)
{
acceptanceRadiusLocal = last->getAcceptanceRadius();
holdTime = last->getHoldTime();
}
// Create local frame waypoint as second option
wp = new Waypoint(0, uas->getLocalX(), uas->getLocalY(), uas->getLocalZ(), uas->getYaw(), acceptanceRadiusLocal, holdTime, 0.0, true, false, MAV_FRAME_LOCAL_NED, MAV_CMD_NAV_WAYPOINT);
WPM->addWaypointEditable(wp);
updateStatusLabel(tr("Added LOCAL (NED) waypoint"));
}
else
{
// Do nothing
updateStatusLabel(tr("Not adding waypoint, no position of MAV known yet."));
}
}
}
void WaypointList::updateStatusLabel(const QString &string)
{
// Status label in write widget
m_ui->statusLabel->setText(string);
// Status label in read only widget
m_ui->viewStatusLabel->setText(string);
}
// Request UASWaypointManager to send the SET_CURRENT message to UAV
void WaypointList::changeCurrentWaypoint(quint16 seq)
{
if (uas)
{
WPM->setCurrentWaypoint(seq);
}
}
// Request UASWaypointManager to set the new "current" and make sure all other waypoints are not "current"
void WaypointList::currentWaypointEditableChanged(quint16 seq)
{
WPM->setCurrentEditable(seq);
const QVector<Waypoint *> &waypoints = WPM->getWaypointEditableList();
if (seq < waypoints.size())
{
for(int i = 0; i < waypoints.size(); i++)
{
WaypointEditableView* widget = wpEditableViews.find(waypoints[i]).value();
if (waypoints[i]->getId() == seq)
{
widget->setCurrent(true);
}
else
{
widget->setCurrent(false);
}
}
}
}
// Update waypointViews to correctly indicate the new current waypoint
void WaypointList::currentWaypointViewOnlyChanged(quint16 seq)
{
const QVector<Waypoint *> &waypoints = WPM->getWaypointViewOnlyList();
if (seq < waypoints.size())
{
for(int i = 0; i < waypoints.size(); i++)
{
WaypointViewOnlyView* widget = wpViewOnlyViews.find(waypoints[i]).value();
if (waypoints[i]->getId() == seq)
{
widget->setCurrent(true);
}
else
{
widget->setCurrent(false);
}
}
}
}
void WaypointList::updateWaypointEditable(int uas, Waypoint* wp)
{
Q_UNUSED(uas);
WaypointEditableView *wpv = wpEditableViews.value(wp);
wpv->updateValues();
}
void WaypointList::updateWaypointViewOnly(int uas, Waypoint* wp)
{
Q_UNUSED(uas);
WaypointViewOnlyView *wpv = wpViewOnlyViews.value(wp);
wpv->updateValues();
}
void WaypointList::waypointViewOnlyListChanged()
{
// Prevent updates to prevent visual flicker
this->setUpdatesEnabled(false);
const QVector<Waypoint *> &waypoints = WPM->getWaypointViewOnlyList();
if (!wpViewOnlyViews.empty()) {
QMapIterator<Waypoint*,WaypointViewOnlyView*> viewIt(wpViewOnlyViews);
viewIt.toFront();
while(viewIt.hasNext()) {
viewIt.next();
Waypoint *cur = viewIt.key();
int i;
for (i = 0; i < waypoints.size(); i++) {
if (waypoints[i] == cur) {
break;
}
}
if (i == waypoints.size()) {
WaypointViewOnlyView* widget = wpViewOnlyViews.find(cur).value();
widget->hide();
viewOnlyListLayout->removeWidget(widget);
wpViewOnlyViews.remove(cur);
}
}
}
// then add/update the views for each waypoint in the list
for(int i = 0; i < waypoints.size(); i++) {
Waypoint *wp = waypoints[i];
if (!wpViewOnlyViews.contains(wp)) {
WaypointViewOnlyView* wpview = new WaypointViewOnlyView(wp, this);
wpViewOnlyViews.insert(wp, wpview);
connect(wpview, SIGNAL(changeCurrentWaypoint(quint16)), this, SLOT(changeCurrentWaypoint(quint16)));
viewOnlyListLayout->insertWidget(i, wpview);
}
WaypointViewOnlyView *wpv = wpViewOnlyViews.value(wp);
//check if ordering has changed
if(viewOnlyListLayout->itemAt(i)->widget() != wpv) {
viewOnlyListLayout->removeWidget(wpv);
viewOnlyListLayout->insertWidget(i, wpv);
}
wpv->updateValues(); // update the values of the ui elements in the view
}
this->setUpdatesEnabled(true);
loadFileGlobalWP = false;
}
void WaypointList::waypointEditableListChanged()
{
// Prevent updates to prevent visual flicker
this->setUpdatesEnabled(false);
const QVector<Waypoint *> &waypoints = WPM->getWaypointEditableList();
if (!wpEditableViews.empty()) {
QMapIterator<Waypoint*,WaypointEditableView*> viewIt(wpEditableViews);
viewIt.toFront();
while(viewIt.hasNext()) {
viewIt.next();
Waypoint *cur = viewIt.key();
int i;
for (i = 0; i < waypoints.size(); i++) {
if (waypoints[i] == cur) {
break;
}
}
if (i == waypoints.size()) {
WaypointEditableView* widget = wpEditableViews.find(cur).value();
widget->hide();
editableListLayout->removeWidget(widget);
wpEditableViews.remove(cur);
}
}
}
// then add/update the views for each waypoint in the list
for(int i = 0; i < waypoints.size(); i++) {
Waypoint *wp = waypoints[i];
if (!wpEditableViews.contains(wp)) {
WaypointEditableView* wpview = new WaypointEditableView(wp, this);
wpEditableViews.insert(wp, wpview);
connect(wpview, SIGNAL(moveDownWaypoint(Waypoint*)), this, SLOT(moveDown(Waypoint*)));
connect(wpview, SIGNAL(moveUpWaypoint(Waypoint*)), this, SLOT(moveUp(Waypoint*)));
connect(wpview, SIGNAL(removeWaypoint(Waypoint*)), this, SLOT(removeWaypoint(Waypoint*)));
//connect(wpview, SIGNAL(currentWaypointChanged(quint16)), this, SLOT(currentWaypointChanged(quint16)));
connect(wpview, SIGNAL(changeCurrentWaypoint(quint16)), this, SLOT(currentWaypointEditableChanged(quint16)));
editableListLayout->insertWidget(i, wpview);
}
WaypointEditableView *wpv = wpEditableViews.value(wp);
//check if ordering has changed
if(editableListLayout->itemAt(i)->widget() != wpv) {
editableListLayout->removeWidget(wpv);
editableListLayout->insertWidget(i, wpv);
}
wpv->updateValues(); // update the values of the ui elements in the view
}
this->setUpdatesEnabled(true);
loadFileGlobalWP = false;
}
void WaypointList::moveUp(Waypoint* wp)
{
const QVector<Waypoint *> &waypoints = WPM->getWaypointEditableList();
//get the current position of wp in the local storage
int i;
for (i = 0; i < waypoints.size(); i++) {
if (waypoints[i] == wp)
break;
}
// if wp was found and its not the first entry, move it
if (i < waypoints.size() && i > 0) {
WPM->moveWaypoint(i, i-1);
}
}
void WaypointList::moveDown(Waypoint* wp)
{
const QVector<Waypoint *> &waypoints = WPM->getWaypointEditableList();
//get the current position of wp in the local storage
int i;
for (i = 0; i < waypoints.size(); i++) {
if (waypoints[i] == wp)
break;
}
// if wp was found and its not the last entry, move it
if (i < waypoints.size()-1) {
WPM->moveWaypoint(i, i+1);
}
}
void WaypointList::removeWaypoint(Waypoint* wp)
{
WPM->removeWaypoint(wp->getId());
}
void WaypointList::changeEvent(QEvent *e)
{
switch (e->type()) {
case QEvent::LanguageChange:
m_ui->retranslateUi(this);
break;
default:
break;
}
}
void WaypointList::on_clearWPListButton_clicked()
{
if (uas) {
emit clearPathclicked();
const QVector<Waypoint *> &waypoints = WPM->getWaypointEditableList();
while(!waypoints.isEmpty()) { //for(int i = 0; i <= waypoints.size(); i++)
WaypointEditableView* widget = wpEditableViews.find(waypoints[0]).value();
widget->remove();
}
} else {
// if(isGlobalWP)
// {
// emit clearPathclicked();
// }
}
}
///** @brief The MapWidget informs that a waypoint global was changed on the map */
//void WaypointList::waypointGlobalChanged(QPointF coordinate, int indexWP)
//{
// if (uas)
// {
// const QVector<Waypoint *> &waypoints = WPM->getWaypointEditableList();
// if (waypoints.size() > 0)
// {
// Waypoint *temp = waypoints.at(indexWP);
// temp->setX(coordinate.x());
// temp->setY(coordinate.y());
// //WaypointGlobalView* widget = wpGlobalViews.find(waypoints[indexWP]).value();
// //widget->updateValues();
// }
// }
//}
///** @brief The MapWidget informs that a waypoint global was changed on the map */
//void WaypointList::waypointGlobalPositionChanged(Waypoint* wp)
//{
// QPointF coordinate;
// coordinate.setX(wp->getX());
// coordinate.setY(wp->getY());
// emit ChangeWaypointGlobalPosition(wp->getId(), coordinate);
//}
void WaypointList::clearWPWidget()
{
const QVector<Waypoint *> &waypoints = WPM->getWaypointEditableList();
while(!waypoints.isEmpty()) { //for(int i = 0; i <= waypoints.size(); i++)
WaypointEditableView* widget = wpEditableViews.find(waypoints[0]).value();
widget->remove();
}
}
//void WaypointList::setIsLoadFileWP()
//{
// loadFileGlobalWP = true;
//}
//void WaypointList::setIsReadGlobalWP(bool value)
//{
// // FIXME James Check this
// Q_UNUSED(value);
// // readGlobalWP = value;
//}
......@@ -28,7 +28,7 @@ void WaypointViewOnlyView::changedAutoContinue(int state)
void WaypointViewOnlyView::changedCurrent(int state)
//This is a slot receiving signals from QCheckBox m_ui->current. The state given here is whatever the user has clicked and not the true "current" value onboard.
{
qDebug() << "Trof: WaypointViewOnlyView::changedCurrent(" << state << ") ID:" << wp->getId();
//qDebug() << "Trof: WaypointViewOnlyView::changedCurrent(" << state << ") ID:" << wp->getId();
m_ui->current->blockSignals(true);
if (m_ui->current->isChecked() == false)
......@@ -36,19 +36,19 @@ void WaypointViewOnlyView::changedCurrent(int state)
if (wp->getCurrent() == true) //User clicked on the waypoint, that is already current. Box stays checked
{
m_ui->current->setCheckState(Qt::Checked);
qDebug() << "Trof: WaypointViewOnlyView::changedCurrent. Rechecked true. stay true " << m_ui->current->isChecked();
//qDebug() << "Trof: WaypointViewOnlyView::changedCurrent. Rechecked true. stay true " << m_ui->current->isChecked();
}
else // Strange case, unchecking the box which was not checked to start with
{
m_ui->current->setCheckState(Qt::Unchecked);
qDebug() << "Trof: WaypointViewOnlyView::changedCurrent. Unchecked false. set false " << m_ui->current->isChecked();
//qDebug() << "Trof: WaypointViewOnlyView::changedCurrent. Unchecked false. set false " << m_ui->current->isChecked();
}
}
else
{
hightlightDesiredCurrent(true);
m_ui->current->setCheckState(Qt::Unchecked);
qDebug() << "Trof: WaypointViewOnlyView::changedCurrent. Checked new. Sending set_current request to Manager " << m_ui->current->isChecked();
//qDebug() << "Trof: WaypointViewOnlyView::changedCurrent. Checked new. Sending set_current request to Manager " << m_ui->current->isChecked();
emit changeCurrentWaypoint(wp->getId()); //the slot changeCurrentWaypoint() in WaypointList sets all other current flags to false
}
......
......@@ -7,7 +7,7 @@
<x>0</x>
<y>0</y>
<width>1228</width>
<height>25</height>
<height>27</height>
</rect>
</property>
<property name="windowTitle">
......@@ -22,6 +22,12 @@
</property>
<item>
<widget class="QSpinBox" name="commandSpinBox">
<property name="toolTip">
<string>MAV_CMD id</string>
</property>
<property name="statusTip">
<string>MAV_CMD id</string>
</property>
<property name="prefix">
<string>CMD </string>
</property>
......@@ -41,6 +47,9 @@
<property name="prefix">
<string>P1 </string>
</property>
<property name="decimals">
<number>7</number>
</property>
<property name="minimum">
<double>-2147483647.000000000000000</double>
</property>
......@@ -51,9 +60,15 @@
</item>
<item>
<widget class="QDoubleSpinBox" name="param2SpinBox">
<property name="toolTip">
<string/>
</property>
<property name="prefix">
<string>P2 </string>
</property>
<property name="decimals">
<number>7</number>
</property>
<property name="minimum">
<double>-2147483647.000000000000000</double>
</property>
......@@ -67,6 +82,9 @@
<property name="prefix">
<string>P3 </string>
</property>
<property name="decimals">
<number>7</number>
</property>
<property name="minimum">
<double>-2147483647.000000000000000</double>
</property>
......@@ -80,6 +98,9 @@
<property name="prefix">
<string>P4 </string>
</property>
<property name="decimals">
<number>7</number>
</property>
<property name="minimum">
<double>-2147483647.000000000000000</double>
</property>
......@@ -93,6 +114,9 @@
<property name="prefix">
<string>P5 </string>
</property>
<property name="decimals">
<number>7</number>
</property>
<property name="minimum">
<double>-2147483647.000000000000000</double>
</property>
......@@ -106,6 +130,9 @@
<property name="prefix">
<string>P6 </string>
</property>
<property name="decimals">
<number>7</number>
</property>
<property name="minimum">
<double>-2147483647.000000000000000</double>
</property>
......@@ -119,6 +146,9 @@
<property name="prefix">
<string>P7 </string>
</property>
<property name="decimals">
<number>7</number>
</property>
<property name="minimum">
<double>-2147483647.000000000000000</double>
</property>
......
......@@ -7,60 +7,49 @@
<x>0</x>
<y>0</y>
<width>632</width>
<height>40</height>
<height>27</height>
</rect>
</property>
<property name="windowTitle">
<string>Form</string>
</property>
<widget class="QSpinBox" name="doJumpIndexSpinBox">
<property name="geometry">
<rect>
<x>170</x>
<y>10</y>
<width>201</width>
<height>25</height>
</rect>
</property>
<property name="suffix">
<string/>
</property>
<property name="prefix">
<string>list index to jump to: </string>
</property>
<property name="maximum">
<number>5000</number>
</property>
</widget>
<widget class="QSpinBox" name="doJumpRepeatSpinBox">
<property name="geometry">
<rect>
<x>380</x>
<y>10</y>
<width>121</width>
<height>25</height>
</rect>
</property>
<property name="suffix">
<string> times</string>
</property>
<property name="prefix">
<string>repeat </string>
</property>
<property name="maximum">
<number>1000</number>
</property>
</widget>
<widget class="QComboBox" name="doSetModeComboBox">
<property name="geometry">
<rect>
<x>20</x>
<y>10</y>
<width>111</width>
<height>26</height>
</rect>
</property>
</widget>
<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/>
......
#include "QGCMissionOther.h"
#include "ui_QGCMissionOther.h"
QGCMissionOther::QGCMissionOther(QWidget *parent) :
QWidget(parent),
ui(new Ui::QGCMissionOther)
{
ui->setupUi(this);
}
QGCMissionOther::~QGCMissionOther()
{
delete ui;
}
#ifndef QGCMISSIONOTHER_H
#define QGCMISSIONOTHER_H
#include <QWidget>
namespace Ui {
class QGCMissionOther;
}
class QGCMissionOther : public QWidget
{
Q_OBJECT
public:
explicit QGCMissionOther(QWidget *parent = 0);
~QGCMissionOther();
Ui::QGCMissionOther *ui;
private:
};
#endif // QGCMISSIONOTHER_H
<?xml version="1.0" encoding="UTF-8"?>
<ui version="4.0">
<class>QGCMissionOther</class>
<widget class="QWidget" name="QGCMissionOther">
<property name="geometry">
<rect>
<x>0</x>
<y>0</y>
<width>1266</width>
<height>27</height>
</rect>
</property>
<property name="windowTitle">
<string>Form</string>
</property>
<layout class="QHBoxLayout" name="horizontalLayout" stretch="10,0,10,10,10,10,0,0">
<property name="spacing">
<number>5</number>
</property>
<property name="margin">
<number>0</number>
</property>
<item>
<widget class="QSpinBox" name="commandSpinBox">
<property name="toolTip">
<string>MAV_CMD id</string>
</property>
<property name="statusTip">
<string>MAV_CMD id</string>
</property>
<property name="prefix">
<string>CMD </string>
</property>
<property name="minimum">
<number>0</number>
</property>
<property name="maximum">
<number>255</number>
</property>
<property name="value">
<number>0</number>
</property>
</widget>
</item>
<item>
<widget class="QDoubleSpinBox" name="param1SpinBox">
<property name="prefix">
<string>P1 </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>
</widget>
</item>
<item>
<widget class="QDoubleSpinBox" name="param2SpinBox">
<property name="toolTip">
<string/>
</property>
<property name="prefix">
<string>P2 </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>
</widget>
</item>
<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>
</widget>
</item>
<item>
<widget class="QDoubleSpinBox" name="param4SpinBox">
<property name="prefix">
<string>P4 </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>
</widget>
</item>
<item>
<widget class="QDoubleSpinBox" name="param5SpinBox">
<property name="prefix">
<string>P5 </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>
</widget>
</item>
<item>
<widget class="QDoubleSpinBox" name="param6SpinBox">
<property name="prefix">
<string>P6 </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>
</widget>
</item>
<item>
<widget class="QDoubleSpinBox" name="param7SpinBox">
<property name="prefix">
<string>P7 </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>
</widget>
</item>
</layout>
</widget>
<resources/>
<connections/>
</ui>
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