Commit 9b62308e authored by Michael Carpenter's avatar Michael Carpenter

Initial implementation of Flight Mode Config screen

parent 8a48aa00
......@@ -4,8 +4,238 @@
FlightModeConfig::FlightModeConfig(QWidget *parent) : QWidget(parent)
{
ui.setupUi(this);
connect(UASManager::instance(),SIGNAL(activeUASSet(UASInterface*)),this,SLOT(setActiveUAS(UASInterface*)));
}
FlightModeConfig::~FlightModeConfig()
{
}
void FlightModeConfig::setActiveUAS(UASInterface *uas)
{
if (!uas) return;
if (m_uas)
{
}
m_uas = uas;
connect(m_uas,SIGNAL(modeChanged(int,QString,QString)),this,SLOT(modeChanged(int,QString,QString)));
connect(m_uas,SIGNAL(parameterChanged(int,int,QString,QVariant)),this,SLOT(parameterChanged(int,int,QString,QVariant)));
connect(m_uas,SIGNAL(remoteControlChannelRawChanged(int,float)),this,SLOT(remoteControlChannelRawChanged(int,float)));
QStringList itemlist;
if (m_uas->getSystemType() == MAV_TYPE_FIXED_WING)
{
itemlist << "Manual";
itemlist << "Circle";
itemlist << "Stabilize";
itemlist << "Training";
itemlist << "FBW A";
itemlist << "FBW B";
itemlist << "Auto";
itemlist << "RTL";
itemlist << "Loiter";
itemlist << "Guided";
planeModeIndexToUiIndex[0] = 0;
planeModeIndexToUiIndex[1] = 1;
planeModeIndexToUiIndex[2] = 2;
planeModeIndexToUiIndex[3] = 3;
planeModeIndexToUiIndex[5] = 4;
planeModeIndexToUiIndex[6] = 5;
planeModeIndexToUiIndex[10] = 6;
planeModeIndexToUiIndex[11] = 7;
planeModeIndexToUiIndex[12] = 8;
planeModeIndexToUiIndex[15] = 9;
ui.mode6ComboBox->setEnabled(true);
}
else if (m_uas->getSystemType() == MAV_TYPE_GROUND_ROVER)
{
itemlist << "Manual";
itemlist << "Learning";
itemlist << "Steering";
itemlist << "Hold";
itemlist << "Auto";
itemlist << "RTL";
itemlist << "Guided";
itemlist << "Initialising";
ui.mode6ComboBox->setEnabled(false);
roverModeIndexToUiIndex[0] = 0;
roverModeIndexToUiIndex[2] = 1;
roverModeIndexToUiIndex[3] = 2;
roverModeIndexToUiIndex[4] = 3;
roverModeIndexToUiIndex[10] = 5;
roverModeIndexToUiIndex[11] = 6;
roverModeIndexToUiIndex[15] = 7;
roverModeIndexToUiIndex[16] = 8;
}
else if (m_uas->getSystemType() == MAV_TYPE_QUADROTOR)
{
itemlist << "Stabilize";
itemlist << "Acro";
itemlist << "Alt Hold";
itemlist << "Auto";
itemlist << "Guided";
itemlist << "Loiter";
itemlist << "RTL";
itemlist << "Circle";
itemlist << "Pos Hold";
itemlist << "Land";
itemlist << "OF_LOITER";
itemlist << "Toy";
ui.mode6ComboBox->setEnabled(true);
}
ui.mode1ComboBox->addItems(itemlist);
ui.mode2ComboBox->addItems(itemlist);
ui.mode3ComboBox->addItems(itemlist);
ui.mode4ComboBox->addItems(itemlist);
ui.mode5ComboBox->addItems(itemlist);
ui.mode6ComboBox->addItems(itemlist);
}
void FlightModeConfig::modeChanged(int sysId, QString status, QString description)
{
//Unused?
}
void FlightModeConfig::remoteControlChannelRawChanged(int chan,float val)
{
if (chan == 5)
{
//Channel 5 is the mode switch.
///TODO: Make this configurable
if (val <= 1230)
{
ui.mode1ComboBox->setBackgroundRole(QPalette::Highlight);
ui.mode2ComboBox->setBackgroundRole(QPalette::Background);
ui.mode3ComboBox->setBackgroundRole(QPalette::Background);
ui.mode4ComboBox->setBackgroundRole(QPalette::Background);
ui.mode5ComboBox->setBackgroundRole(QPalette::Background);
ui.mode6ComboBox->setBackgroundRole(QPalette::Background);
}
else if (val <= 1360)
{
ui.mode1ComboBox->setBackgroundRole(QPalette::Background);
ui.mode2ComboBox->setBackgroundRole(QPalette::Highlight);
ui.mode3ComboBox->setBackgroundRole(QPalette::Background);
ui.mode4ComboBox->setBackgroundRole(QPalette::Background);
ui.mode5ComboBox->setBackgroundRole(QPalette::Background);
ui.mode6ComboBox->setBackgroundRole(QPalette::Background);
}
else if (val <= 1490)
{
ui.mode1ComboBox->setBackgroundRole(QPalette::Background);
ui.mode2ComboBox->setBackgroundRole(QPalette::Background);
ui.mode3ComboBox->setBackgroundRole(QPalette::Highlight);
ui.mode4ComboBox->setBackgroundRole(QPalette::Background);
ui.mode5ComboBox->setBackgroundRole(QPalette::Background);
ui.mode6ComboBox->setBackgroundRole(QPalette::Background);
}
else if (val <=1620)
{
ui.mode1ComboBox->setBackgroundRole(QPalette::Background);
ui.mode2ComboBox->setBackgroundRole(QPalette::Background);
ui.mode3ComboBox->setBackgroundRole(QPalette::Background);
ui.mode4ComboBox->setBackgroundRole(QPalette::Highlight);
ui.mode5ComboBox->setBackgroundRole(QPalette::Background);
ui.mode6ComboBox->setBackgroundRole(QPalette::Background);
}
else if (val <=1749)
{
ui.mode1ComboBox->setBackgroundRole(QPalette::Background);
ui.mode2ComboBox->setBackgroundRole(QPalette::Background);
ui.mode3ComboBox->setBackgroundRole(QPalette::Background);
ui.mode4ComboBox->setBackgroundRole(QPalette::Background);
ui.mode5ComboBox->setBackgroundRole(QPalette::Highlight);
ui.mode6ComboBox->setBackgroundRole(QPalette::Background);
}
else
{
ui.mode1ComboBox->setBackgroundRole(QPalette::Background);
ui.mode2ComboBox->setBackgroundRole(QPalette::Background);
ui.mode3ComboBox->setBackgroundRole(QPalette::Background);
ui.mode4ComboBox->setBackgroundRole(QPalette::Background);
ui.mode5ComboBox->setBackgroundRole(QPalette::Background);
ui.mode6ComboBox->setBackgroundRole(QPalette::Highlight);
}
}
}
void FlightModeConfig::parameterChanged(int uas, int component, QString parameterName, QVariant value)
{
if (m_uas->getSystemType() == MAV_TYPE_FIXED_WING)
{
if (parameterName == "FLTMODE1")
{
ui.mode1ComboBox->setCurrentIndex(planeModeIndexToUiIndex[value.toInt()]);
}
else if (parameterName == "FLTMODE2")
{
ui.mode2ComboBox->setCurrentIndex(planeModeIndexToUiIndex[value.toInt()]);
}
else if (parameterName == "FLTMODE3")
{
ui.mode3ComboBox->setCurrentIndex(planeModeIndexToUiIndex[value.toInt()]);
}
else if (parameterName == "FLTMODE4")
{
ui.mode4ComboBox->setCurrentIndex(planeModeIndexToUiIndex[value.toInt()]);
}
else if (parameterName == "FLTMODE5")
{
ui.mode5ComboBox->setCurrentIndex(planeModeIndexToUiIndex[value.toInt()]);
}
else if (parameterName == "FLTMODE6")
{
ui.mode6ComboBox->setCurrentIndex(planeModeIndexToUiIndex[value.toInt()]);
}
}
else if (m_uas->getSystemType() == MAV_TYPE_GROUND_ROVER)
{
if (parameterName == "MODE1")
{
ui.mode1ComboBox->setCurrentIndex(roverModeIndexToUiIndex[value.toInt()]);
}
else if (parameterName == "MODE2")
{
ui.mode2ComboBox->setCurrentIndex(roverModeIndexToUiIndex[value.toInt()]);
}
else if (parameterName == "MODE3")
{
ui.mode3ComboBox->setCurrentIndex(roverModeIndexToUiIndex[value.toInt()]);
}
else if (parameterName == "MODE4")
{
ui.mode4ComboBox->setCurrentIndex(roverModeIndexToUiIndex[value.toInt()]);
}
else if (parameterName == "MODE5")
{
ui.mode5ComboBox->setCurrentIndex(roverModeIndexToUiIndex[value.toInt()]);
}
}
else if (m_uas->getSystemType() == MAV_TYPE_QUADROTOR)
{
if (parameterName == "FLTMODE1")
{
ui.mode1ComboBox->setCurrentIndex(value.toInt()-1);
}
else if (parameterName == "FLTMODE2")
{
ui.mode2ComboBox->setCurrentIndex(value.toInt()-1);
}
else if (parameterName == "FLTMODE3")
{
ui.mode3ComboBox->setCurrentIndex(value.toInt()-1);
}
else if (parameterName == "FLTMODE4")
{
ui.mode4ComboBox->setCurrentIndex(value.toInt()-1);
}
else if (parameterName == "FLTMODE5")
{
ui.mode5ComboBox->setCurrentIndex(value.toInt()-1);
}
else if (parameterName == "FLTMODE6")
{
ui.mode6ComboBox->setCurrentIndex(value.toInt()-1);
}
}
}
......@@ -3,6 +3,8 @@
#include <QWidget>
#include "ui_FlightModeConfig.h"
#include "UASInterface.h"
#include "UASManager.h"
class FlightModeConfig : public QWidget
{
......@@ -11,9 +13,16 @@ class FlightModeConfig : public QWidget
public:
explicit FlightModeConfig(QWidget *parent = 0);
~FlightModeConfig();
private slots:
void setActiveUAS(UASInterface *uas);
void modeChanged(int sysId, QString status, QString description);
void remoteControlChannelRawChanged(int chan,float val);
void parameterChanged(int uas, int component, QString parameterName, QVariant value);
private:
QMap<int,int> roverModeIndexToUiIndex;
QMap<int,int> planeModeIndexToUiIndex;
Ui::FlightModeConfig ui;
UASInterface *m_uas;
};
#endif // FLIGHTMODECONFIG_H
......@@ -6,8 +6,8 @@
<rect>
<x>0</x>
<y>0</y>
<width>400</width>
<height>300</height>
<width>608</width>
<height>359</height>
</rect>
</property>
<property name="windowTitle">
......@@ -29,6 +29,212 @@
<bool>false</bool>
</property>
</widget>
<widget class="QWidget" name="horizontalLayoutWidget">
<property name="geometry">
<rect>
<x>20</x>
<y>70</y>
<width>481</width>
<height>191</height>
</rect>
</property>
<layout class="QHBoxLayout" name="horizontalLayout">
<item>
<layout class="QVBoxLayout" name="verticalLayout">
<property name="spacing">
<number>8</number>
</property>
<property name="topMargin">
<number>0</number>
</property>
<item>
<widget class="QLabel" name="label_11">
<property name="text">
<string>Flight Mode 1</string>
</property>
<property name="alignment">
<set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
</property>
</widget>
</item>
<item>
<widget class="QLabel" name="label_5">
<property name="text">
<string>Flight Mode 2</string>
</property>
<property name="alignment">
<set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
</property>
</widget>
</item>
<item>
<widget class="QLabel" name="label_9">
<property name="text">
<string>Flight Mode 3</string>
</property>
<property name="alignment">
<set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
</property>
</widget>
</item>
<item>
<widget class="QLabel" name="label_2">
<property name="text">
<string>Flight Mode 4</string>
</property>
<property name="alignment">
<set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
</property>
</widget>
</item>
<item>
<widget class="QLabel" name="label_7">
<property name="text">
<string>Flight Mode 5</string>
</property>
<property name="alignment">
<set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
</property>
</widget>
</item>
<item>
<widget class="QLabel" name="label_13">
<property name="text">
<string>Flight Mode 6</string>
</property>
<property name="alignment">
<set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
</property>
</widget>
</item>
</layout>
</item>
<item>
<layout class="QVBoxLayout" name="verticalLayout_4">
<item>
<widget class="QComboBox" name="mode1ComboBox">
<property name="frame">
<bool>true</bool>
</property>
</widget>
</item>
<item>
<widget class="QComboBox" name="mode2ComboBox"/>
</item>
<item>
<widget class="QComboBox" name="mode3ComboBox"/>
</item>
<item>
<widget class="QComboBox" name="mode4ComboBox"/>
</item>
<item>
<widget class="QComboBox" name="mode5ComboBox"/>
</item>
<item>
<widget class="QComboBox" name="mode6ComboBox"/>
</item>
</layout>
</item>
<item>
<layout class="QVBoxLayout" name="verticalLayout_3">
<property name="spacing">
<number>8</number>
</property>
<property name="topMargin">
<number>0</number>
</property>
<item>
<widget class="QCheckBox" name="mode1SimpleCheckBox">
<property name="text">
<string>Simple Mode</string>
</property>
</widget>
</item>
<item>
<widget class="QCheckBox" name="mode2SimpleCheckBox">
<property name="text">
<string>Simple Mode</string>
</property>
</widget>
</item>
<item>
<widget class="QCheckBox" name="mode3SimpleCheckBox">
<property name="text">
<string>Simple Mode</string>
</property>
</widget>
</item>
<item>
<widget class="QCheckBox" name="mode4SimpleCheckBox">
<property name="text">
<string>Simple Mode</string>
</property>
</widget>
</item>
<item>
<widget class="QCheckBox" name="mode5SimpleCheckBox">
<property name="text">
<string>Simple Mode</string>
</property>
</widget>
</item>
<item>
<widget class="QCheckBox" name="mode6SimpleCheckBox">
<property name="text">
<string>Simple Mode</string>
</property>
</widget>
</item>
</layout>
</item>
<item>
<layout class="QVBoxLayout" name="verticalLayout_2">
<item>
<widget class="QLabel" name="label_6">
<property name="text">
<string>PWM 0 - 1230</string>
</property>
</widget>
</item>
<item>
<widget class="QLabel" name="label_4">
<property name="text">
<string>PWM 1231 - 1360</string>
</property>
</widget>
</item>
<item>
<widget class="QLabel" name="label_3">
<property name="text">
<string>PWM 1361 - 1490</string>
</property>
</widget>
</item>
<item>
<widget class="QLabel" name="label_10">
<property name="text">
<string>PWM 1491 - 1620</string>
</property>
</widget>
</item>
<item>
<widget class="QLabel" name="label_8">
<property name="text">
<string>PWM 1621 - 1749</string>
</property>
</widget>
</item>
<item>
<widget class="QLabel" name="label_12">
<property name="text">
<string>PWM 1750 +</string>
</property>
</widget>
</item>
</layout>
</item>
</layout>
</widget>
</widget>
<resources/>
<connections/>
......
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