Commit c434fd70 authored by pixhawk's avatar pixhawk

Mission Plan Widget: Added support for MAV_CMD_DO_SEARCH custom pixhawk...

Mission Plan Widget: Added support for MAV_CMD_DO_SEARCH custom pixhawk commands, fixed some tooltip bugs.
parent 676e0d02
...@@ -247,7 +247,9 @@ FORMS += src/ui/MainWindow.ui \ ...@@ -247,7 +247,9 @@ FORMS += src/ui/MainWindow.ui \
src/ui/mission/QGCMissionNavReturnToLaunch.ui \ src/ui/mission/QGCMissionNavReturnToLaunch.ui \
src/ui/mission/QGCMissionNavLand.ui \ src/ui/mission/QGCMissionNavLand.ui \
src/ui/mission/QGCMissionNavTakeoff.ui \ src/ui/mission/QGCMissionNavTakeoff.ui \
src/ui/mission/QGCMissionNavSweep.ui src/ui/mission/QGCMissionNavSweep.ui \
src/ui/mission/QGCMissionDoStartSearch.ui \
src/ui/mission/QGCMissionDoFinishSearch.ui
INCLUDEPATH += src \ INCLUDEPATH += src \
src/ui \ src/ui \
src/ui/linechart \ src/ui/linechart \
...@@ -379,7 +381,9 @@ HEADERS += src/MG.h \ ...@@ -379,7 +381,9 @@ HEADERS += src/MG.h \
src/ui/mission/QGCMissionNavReturnToLaunch.h \ src/ui/mission/QGCMissionNavReturnToLaunch.h \
src/ui/mission/QGCMissionNavLand.h \ src/ui/mission/QGCMissionNavLand.h \
src/ui/mission/QGCMissionNavTakeoff.h \ src/ui/mission/QGCMissionNavTakeoff.h \
src/ui/mission/QGCMissionNavSweep.h src/ui/mission/QGCMissionNavSweep.h \
src/ui/mission/QGCMissionDoStartSearch.h \
src/ui/mission/QGCMissionDoFinishSearch.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
...@@ -520,7 +524,9 @@ SOURCES += src/main.cc \ ...@@ -520,7 +524,9 @@ SOURCES += src/main.cc \
src/ui/mission/QGCMissionNavReturnToLaunch.cc \ src/ui/mission/QGCMissionNavReturnToLaunch.cc \
src/ui/mission/QGCMissionNavLand.cc \ src/ui/mission/QGCMissionNavLand.cc \
src/ui/mission/QGCMissionNavTakeoff.cc \ src/ui/mission/QGCMissionNavTakeoff.cc \
src/ui/mission/QGCMissionNavSweep.cc src/ui/mission/QGCMissionNavSweep.cc \
src/ui/mission/QGCMissionDoStartSearch.cc \
src/ui/mission/QGCMissionDoFinishSearch.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
......
...@@ -31,6 +31,8 @@ ...@@ -31,6 +31,8 @@
#include "QGCMissionNavSweep.h" #include "QGCMissionNavSweep.h"
#include "QGCMissionConditionDelay.h" #include "QGCMissionConditionDelay.h"
#include "QGCMissionDoJump.h" #include "QGCMissionDoJump.h"
#include "QGCMissionDoStartSearch.h"
#include "QGCMissionDoFinishSearch.h"
#include "QGCMissionOther.h" #include "QGCMissionOther.h"
...@@ -58,8 +60,10 @@ WaypointEditableView::WaypointEditableView(Waypoint* wp, QWidget* parent) : ...@@ -58,8 +60,10 @@ WaypointEditableView::WaypointEditableView(Waypoint* wp, QWidget* parent) :
MissionNavLandWidget = NULL; MissionNavLandWidget = NULL;
MissionNavTakeoffWidget = NULL; MissionNavTakeoffWidget = NULL;
MissionNavSweepWidget = NULL; MissionNavSweepWidget = NULL;
MissionDoJumpWidget = NULL;
MissionConditionDelayWidget = NULL; MissionConditionDelayWidget = NULL;
MissionDoJumpWidget = NULL;
MissionDoStartSearchWidget = NULL;
MissionDoFinishSearchWidget = NULL;
MissionOtherWidget = NULL; MissionOtherWidget = NULL;
...@@ -77,6 +81,8 @@ WaypointEditableView::WaypointEditableView(Waypoint* wp, QWidget* parent) : ...@@ -77,6 +81,8 @@ WaypointEditableView::WaypointEditableView(Waypoint* wp, QWidget* parent) :
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);
#ifdef MAVLINK_ENABLED_PIXHAWK #ifdef MAVLINK_ENABLED_PIXHAWK
m_ui->comboBox_action->addItem(tr("NAV: Sweep"),MAV_CMD_NAV_SWEEP); m_ui->comboBox_action->addItem(tr("NAV: Sweep"),MAV_CMD_NAV_SWEEP);
m_ui->comboBox_action->addItem(tr("Do: Start Search"),MAV_CMD_DO_START_SEARCH);
m_ui->comboBox_action->addItem(tr("Do: Finish Search"),MAV_CMD_DO_FINISH_SEARCH);
#endif #endif
m_ui->comboBox_action->addItem(tr("Other"), MAV_CMD_ENUM_END); m_ui->comboBox_action->addItem(tr("Other"), MAV_CMD_ENUM_END);
...@@ -144,8 +150,11 @@ void WaypointEditableView::updateActionView(int action) ...@@ -144,8 +150,11 @@ void WaypointEditableView::updateActionView(int action)
if(MissionNavReturnToLaunchWidget) MissionNavReturnToLaunchWidget->hide(); if(MissionNavReturnToLaunchWidget) MissionNavReturnToLaunchWidget->hide();
if(MissionNavLandWidget) MissionNavLandWidget->hide(); if(MissionNavLandWidget) MissionNavLandWidget->hide();
if(MissionNavTakeoffWidget) MissionNavTakeoffWidget->hide(); if(MissionNavTakeoffWidget) MissionNavTakeoffWidget->hide();
if(MissionNavSweepWidget) MissionNavSweepWidget->hide();
if(MissionConditionDelayWidget) MissionConditionDelayWidget->hide(); if(MissionConditionDelayWidget) MissionConditionDelayWidget->hide();
if(MissionDoJumpWidget) MissionDoJumpWidget->hide(); if(MissionDoJumpWidget) MissionDoJumpWidget->hide();
if(MissionDoStartSearchWidget) MissionDoStartSearchWidget->hide();
if(MissionDoFinishSearchWidget) MissionDoFinishSearchWidget->hide();
if(MissionOtherWidget) MissionOtherWidget->hide(); if(MissionOtherWidget) MissionOtherWidget->hide();
//Show only the correct one //Show only the correct one
...@@ -183,6 +192,12 @@ void WaypointEditableView::updateActionView(int action) ...@@ -183,6 +192,12 @@ void WaypointEditableView::updateActionView(int action)
case MAV_CMD_NAV_SWEEP: case MAV_CMD_NAV_SWEEP:
if(MissionNavSweepWidget) MissionNavSweepWidget->show(); if(MissionNavSweepWidget) MissionNavSweepWidget->show();
break; break;
case MAV_CMD_DO_START_SEARCH:
if(MissionDoStartSearchWidget) MissionDoStartSearchWidget->show();
break;
case MAV_CMD_DO_FINISH_SEARCH:
if(MissionDoFinishSearchWidget) MissionDoFinishSearchWidget->show();
break;
#endif #endif
default: default:
...@@ -295,6 +310,20 @@ void WaypointEditableView::initializeActionView(int actionID) ...@@ -295,6 +310,20 @@ void WaypointEditableView::initializeActionView(int actionID)
m_ui->customActionWidget->layout()->addWidget(MissionNavSweepWidget); m_ui->customActionWidget->layout()->addWidget(MissionNavSweepWidget);
} }
break; break;
case MAV_CMD_DO_START_SEARCH:
if (!MissionDoStartSearchWidget)
{
MissionDoStartSearchWidget = new QGCMissionDoStartSearch(this);
m_ui->customActionWidget->layout()->addWidget(MissionDoStartSearchWidget);
}
break;
case MAV_CMD_DO_FINISH_SEARCH:
if (!MissionDoFinishSearchWidget)
{
MissionDoFinishSearchWidget = new QGCMissionDoFinishSearch(this);
m_ui->customActionWidget->layout()->addWidget(MissionDoFinishSearchWidget);
}
break;
#endif #endif
case MAV_CMD_ENUM_END: case MAV_CMD_ENUM_END:
default: default:
......
...@@ -55,6 +55,8 @@ class QGCMissionNavLand; ...@@ -55,6 +55,8 @@ class QGCMissionNavLand;
class QGCMissionNavTakeoff; class QGCMissionNavTakeoff;
class QGCMissionNavSweep; class QGCMissionNavSweep;
class QGCMissionDoJump; class QGCMissionDoJump;
class QGCMissionDoStartSearch;
class QGCMissionDoFinishSearch;
class QGCMissionConditionDelay; class QGCMissionConditionDelay;
class QGCMissionOther; class QGCMissionOther;
...@@ -108,6 +110,8 @@ protected: ...@@ -108,6 +110,8 @@ protected:
QGCMissionNavTakeoff* MissionNavTakeoffWidget; QGCMissionNavTakeoff* MissionNavTakeoffWidget;
QGCMissionNavSweep* MissionNavSweepWidget; QGCMissionNavSweep* MissionNavSweepWidget;
QGCMissionDoJump* MissionDoJumpWidget; QGCMissionDoJump* MissionDoJumpWidget;
QGCMissionDoStartSearch* MissionDoStartSearchWidget;
QGCMissionDoFinishSearch* MissionDoFinishSearchWidget;
QGCMissionConditionDelay* MissionConditionDelayWidget; QGCMissionConditionDelay* MissionConditionDelayWidget;
QGCMissionOther* MissionOtherWidget; QGCMissionOther* MissionOtherWidget;
......
...@@ -365,17 +365,18 @@ void WaypointViewOnlyView::updateValues() ...@@ -365,17 +365,18 @@ void WaypointViewOnlyView::updateValues()
m_ui->displayBar->setText(QString("Delay: %1 sec").arg(wp->getParam1())); m_ui->displayBar->setText(QString("Delay: %1 sec").arg(wp->getParam1()));
break; break;
} }
case 237: //MAV_CMD_DO_START_SEARCH #ifdef MAVLINK_ENABLED_PIXHAWK
case MAV_CMD_DO_START_SEARCH:
{ {
m_ui->displayBar->setText(QString("Start searching for pattern. Success when got more than %2 detections with confidence %1").arg(wp->getParam1()).arg(wp->getParam2())); m_ui->displayBar->setText(QString("Start searching for pattern. Success when got more than %2 detections with confidence %1").arg(wp->getParam1()).arg(wp->getParam2()));
break; break;
} }
case 238: //MAV_CMD_DO_FINISH_SEARCH case MAV_CMD_DO_FINISH_SEARCH:
{ {
m_ui->displayBar->setText(QString("Check if search was successful. yes -> jump to %1, no -> jump to %2. Jumps left: %3").arg(wp->getParam1()).arg(wp->getParam2()).arg(wp->getParam3())); m_ui->displayBar->setText(QString("Check if search was successful. yes -> jump to %1, no -> jump to %2. Jumps left: %3").arg(wp->getParam1()).arg(wp->getParam2()).arg(wp->getParam3()));
break; break;
} }
case 240: //MAV_CMD_DO_SWEEP case MAV_CMD_NAV_SWEEP:
{ {
switch (wp->getFrame()) switch (wp->getFrame())
{ {
...@@ -394,6 +395,7 @@ void WaypointViewOnlyView::updateValues() ...@@ -394,6 +395,7 @@ void WaypointViewOnlyView::updateValues()
} //end Frame switch } //end Frame switch
break; break;
} }
#endif
default: default:
{ {
m_ui->displayBar->setText(QString("Unknown Command ID (%1) : %2, %3, %4, %5, %6, %7, %8").arg(wp->getAction()).arg(wp->getParam1()).arg(wp->getParam2()).arg(wp->getParam3()).arg(wp->getParam4()).arg(wp->getParam5()).arg(wp->getParam6()).arg(wp->getParam7())); m_ui->displayBar->setText(QString("Unknown Command ID (%1) : %2, %3, %4, %5, %6, %7, %8").arg(wp->getAction()).arg(wp->getParam1()).arg(wp->getParam2()).arg(wp->getParam3()).arg(wp->getParam4()).arg(wp->getParam5()).arg(wp->getParam6()).arg(wp->getParam7()));
......
#include "QGCMissionDoFinishSearch.h"
#include "ui_QGCMissionDoFinishSearch.h"
#include "WaypointEditableView.h"
QGCMissionDoFinishSearch::QGCMissionDoFinishSearch(WaypointEditableView* WEV) :
QWidget(WEV),
ui(new Ui::QGCMissionDoFinishSearch)
{
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)));
connect(this->ui->param3SpinBox, SIGNAL(valueChanged(double)),WEV,SLOT(changedParam3(double)));
//connect(this->ui->param4SpinBox, SIGNAL(valueChanged(double)),WEV,SLOT(changedParam4(double)));
//connect(this->ui->param5SpinBox, SIGNAL(valueChanged(double)),WEV,SLOT(changedParam5(double)));
//connect(this->ui->param6SpinBox, SIGNAL(valueChanged(double)),WEV,SLOT(changedParam6(double)));
//connect(this->ui->param7SpinBox, SIGNAL(valueChanged(double)),WEV,SLOT(changedParam7(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)));
connect(WEV,SIGNAL(param3Broadcast(double)),this->ui->param3SpinBox,SLOT(setValue(double)));
//connect(WEV,SIGNAL(param4Broadcast(double)),this->ui->param4SpinBox,SLOT(setValue(double)));
//connect(WEV,SIGNAL(param5Broadcast(double)),this->ui->param5SpinBox,SLOT(setValue(double)));
//connect(WEV,SIGNAL(param6Broadcast(double)),this->ui->param6SpinBox,SLOT(setValue(double)));
//connect(WEV,SIGNAL(param7Broadcast(double)),this->ui->param7SpinBox,SLOT(setValue(double)));
}
QGCMissionDoFinishSearch::~QGCMissionDoFinishSearch()
{
delete ui;
}
#ifndef QGCMISSIONDOFINISHSEARCH_H
#define QGCMISSIONDOFINISHSEARCH_H
#include <QWidget>
#include "WaypointEditableView.h"
namespace Ui {
class QGCMissionDoFinishSearch;
}
class QGCMissionDoFinishSearch : public QWidget
{
Q_OBJECT
public:
explicit QGCMissionDoFinishSearch(WaypointEditableView* WEV);
~QGCMissionDoFinishSearch();
protected:
WaypointEditableView* WEV;
private:
Ui::QGCMissionDoFinishSearch *ui;
};
#endif // QGCMISSIONDOFINISHSEARCH_H
<?xml version="1.0" encoding="UTF-8"?>
<ui version="4.0">
<class>QGCMissionDoFinishSearch</class>
<widget class="QWidget" name="QGCMissionDoFinishSearch">
<property name="geometry">
<rect>
<x>0</x>
<y>0</y>
<width>499</width>
<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>
<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="QDoubleSpinBox" name="param1SpinBox">
<property name="toolTip">
<string>Jump to this index, if search successful</string>
</property>
<property name="statusTip">
<string>Jump to this index, if search successful</string>
</property>
<property name="whatsThis">
<string/>
</property>
<property name="keyboardTracking">
<bool>false</bool>
</property>
<property name="prefix">
<string>Jump to index: </string>
</property>
<property name="suffix">
<string/>
</property>
<property name="decimals">
<number>0</number>
</property>
<property name="minimum">
<double>0.000000000000000</double>
</property>
<property name="maximum">
<double>2147483647.000000000000000</double>
</property>
</widget>
</item>
<item>
<widget class="QDoubleSpinBox" name="param2SpinBox">
<property name="toolTip">
<string>Jump to this index, if search unsuccessful</string>
</property>
<property name="statusTip">
<string>Jump to this index, if search unsuccessful</string>
</property>
<property name="whatsThis">
<string/>
</property>
<property name="keyboardTracking">
<bool>false</bool>
</property>
<property name="prefix">
<string>Jump to index: </string>
</property>
<property name="decimals">
<number>0</number>
</property>
<property name="minimum">
<double>0.000000000000000</double>
</property>
<property name="maximum">
<double>2147483647.000000000000000</double>
</property>
</widget>
</item>
<item>
<widget class="QDoubleSpinBox" name="param3SpinBox">
<property name="toolTip">
<string>Remaining number of jumps. Terminate search if jumps == 0.</string>
</property>
<property name="statusTip">
<string>Remaining number of jumps. Terminate search if jumps == 0.</string>
</property>
<property name="whatsThis">
<string/>
</property>
<property name="keyboardTracking">
<bool>false</bool>
</property>
<property name="prefix">
<string/>
</property>
<property name="suffix">
<string> time(s)</string>
</property>
<property name="decimals">
<number>0</number>
</property>
<property name="minimum">
<double>0.000000000000000</double>
</property>
<property name="maximum">
<double>2147483647.000000000000000</double>
</property>
</widget>
</item>
</layout>
</widget>
<resources/>
<connections/>
</ui>
#include "QGCMissionDoStartSearch.h"
#include "ui_QGCMissionDoStartSearch.h"
#include "WaypointEditableView.h"
QGCMissionDoStartSearch::QGCMissionDoStartSearch(WaypointEditableView* WEV) :
QWidget(WEV),
ui(new Ui::QGCMissionDoStartSearch)
{
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)));
//connect(this->ui->param3SpinBox, SIGNAL(valueChanged(double)),WEV,SLOT(changedParam3(double)));
//connect(this->ui->param4SpinBox, SIGNAL(valueChanged(double)),WEV,SLOT(changedParam4(double)));
//connect(this->ui->param5SpinBox, SIGNAL(valueChanged(double)),WEV,SLOT(changedParam5(double)));
//connect(this->ui->param6SpinBox, SIGNAL(valueChanged(double)),WEV,SLOT(changedParam6(double)));
//connect(this->ui->param7SpinBox, SIGNAL(valueChanged(double)),WEV,SLOT(changedParam7(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)));
//connect(WEV,SIGNAL(param3Broadcast(double)),this->ui->param3SpinBox,SLOT(setValue(double)));
//connect(WEV,SIGNAL(param4Broadcast(double)),this->ui->param4SpinBox,SLOT(setValue(double)));
//connect(WEV,SIGNAL(param5Broadcast(double)),this->ui->param5SpinBox,SLOT(setValue(double)));
//connect(WEV,SIGNAL(param6Broadcast(double)),this->ui->param6SpinBox,SLOT(setValue(double)));
//connect(WEV,SIGNAL(param7Broadcast(double)),this->ui->param7SpinBox,SLOT(setValue(double)));
}
QGCMissionDoStartSearch::~QGCMissionDoStartSearch()
{
delete ui;
}
#ifndef QGCMISSIONDOSTARTSEARCH_H
#define QGCMISSIONDOSTARTSEARCH_H
#include <QWidget>
#include "WaypointEditableView.h"
namespace Ui {
class QGCMissionDoStartSearch;
}
class QGCMissionDoStartSearch : public QWidget
{
Q_OBJECT
public:
explicit QGCMissionDoStartSearch(WaypointEditableView* WEV);
~QGCMissionDoStartSearch();
protected:
WaypointEditableView* WEV;
private:
Ui::QGCMissionDoStartSearch *ui;
};
#endif // QGCMISSIONDOSTARTSEARCH_H
<?xml version="1.0" encoding="UTF-8"?>
<ui version="4.0">
<class>QGCMissionDoStartSearch</class>
<widget class="QWidget" name="QGCMissionDoStartSearch">
<property name="geometry">
<rect>
<x>0</x>
<y>0</y>
<width>482</width>
<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>
<layout class="QHBoxLayout" name="horizontalLayout" stretch="10,10">
<property name="spacing">
<number>5</number>
</property>
<property name="margin">
<number>0</number>
</property>
<item>
<widget class="QDoubleSpinBox" name="param1SpinBox">
<property name="toolTip">
<string>Minimal required detection confidence</string>
</property>
<property name="statusTip">
<string>Minimal required detection confidence</string>
</property>
<property name="keyboardTracking">
<bool>false</bool>
</property>
<property name="prefix">
<string>Conf: </string>
</property>
<property name="decimals">
<number>3</number>
</property>
<property name="minimum">
<double>0.000000000000000</double>
</property>
<property name="maximum">
<double>100.000000000000000</double>
</property>
<property name="singleStep">
<double>0.100000000000000</double>
</property>
</widget>
</item>
<item>
<widget class="QDoubleSpinBox" name="param2SpinBox">
<property name="toolTip">
<string>Required number of detections</string>
</property>
<property name="statusTip">
<string>Required number of detections</string>
</property>
<property name="keyboardTracking">
<bool>false</bool>
</property>
<property name="prefix">
<string>#det: </string>
</property>
<property name="decimals">
<number>0</number>
</property>
<property name="minimum">
<double>0.000000000000000</double>
</property>
<property name="maximum">
<double>2147483647.000000000000000</double>
</property>
</widget>
</item>
</layout>
</widget>
<resources/>
<connections/>
</ui>
...@@ -59,6 +59,12 @@ ...@@ -59,6 +59,12 @@
</item> </item>
<item> <item>
<widget class="QDoubleSpinBox" name="param1SpinBox"> <widget class="QDoubleSpinBox" name="param1SpinBox">
<property name="toolTip">
<string>Mission parameter #1</string>
</property>
<property name="statusTip">
<string>Mission parameter #1</string>
</property>
<property name="keyboardTracking"> <property name="keyboardTracking">
<bool>false</bool> <bool>false</bool>
</property> </property>
...@@ -79,7 +85,10 @@ ...@@ -79,7 +85,10 @@
<item> <item>
<widget class="QDoubleSpinBox" name="param2SpinBox"> <widget class="QDoubleSpinBox" name="param2SpinBox">
<property name="toolTip"> <property name="toolTip">
<string/> <string>Mission parameter #2</string>
</property>
<property name="statusTip">
<string>Mission parameter #2</string>
</property> </property>
<property name="keyboardTracking"> <property name="keyboardTracking">
<bool>false</bool> <bool>false</bool>
...@@ -100,6 +109,12 @@ ...@@ -100,6 +109,12 @@
</item> </item>
<item> <item>
<widget class="QDoubleSpinBox" name="param3SpinBox"> <widget class="QDoubleSpinBox" name="param3SpinBox">
<property name="toolTip">
<string>Mission parameter #3</string>
</property>
<property name="statusTip">
<string>Mission parameter #3</string>
</property>
<property name="keyboardTracking"> <property name="keyboardTracking">
<bool>false</bool> <bool>false</bool>
</property> </property>
...@@ -119,6 +134,12 @@ ...@@ -119,6 +134,12 @@
</item> </item>
<item> <item>
<widget class="QDoubleSpinBox" name="param4SpinBox"> <widget class="QDoubleSpinBox" name="param4SpinBox">
<property name="toolTip">
<string>Mission parameter #4</string>
</property>
<property name="statusTip">
<string>Mission parameter #4</string>
</property>
<property name="keyboardTracking"> <property name="keyboardTracking">
<bool>false</bool> <bool>false</bool>
</property> </property>
...@@ -138,6 +159,12 @@ ...@@ -138,6 +159,12 @@
</item> </item>
<item> <item>
<widget class="QDoubleSpinBox" name="param5SpinBox"> <widget class="QDoubleSpinBox" name="param5SpinBox">
<property name="toolTip">
<string>Mission parameter #5</string>
</property>
<property name="statusTip">
<string>Mission parameter #5</string>
</property>
<property name="keyboardTracking"> <property name="keyboardTracking">
<bool>false</bool> <bool>false</bool>
</property> </property>
...@@ -157,6 +184,12 @@ ...@@ -157,6 +184,12 @@
</item> </item>
<item> <item>
<widget class="QDoubleSpinBox" name="param6SpinBox"> <widget class="QDoubleSpinBox" name="param6SpinBox">
<property name="toolTip">
<string>Mission parameter #6</string>
</property>
<property name="statusTip">
<string>Mission parameter #6</string>
</property>
<property name="keyboardTracking"> <property name="keyboardTracking">
<bool>false</bool> <bool>false</bool>
</property> </property>
...@@ -176,6 +209,12 @@ ...@@ -176,6 +209,12 @@
</item> </item>
<item> <item>
<widget class="QDoubleSpinBox" name="param7SpinBox"> <widget class="QDoubleSpinBox" name="param7SpinBox">
<property name="toolTip">
<string>Mission parameter #7</string>
</property>
<property name="statusTip">
<string>Mission parameter #7</string>
</property>
<property name="keyboardTracking"> <property name="keyboardTracking">
<bool>false</bool> <bool>false</bool>
</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