Commit e72400d1 authored by Michael Carpenter's avatar Michael Carpenter

Additional functionaltiy of Actions view, including setwaypoint,change speed, and ARM/DISARM

parent 6b449af3
#include "UASActionsWidget.h"
#include <QMessageBox>
#include <UAS.h>
UASActionsWidget::UASActionsWidget(QWidget *parent) : QWidget(parent)
{
m_uas = 0;
ui.setupUi(this);
connect(ui.changeAltitudeButton,SIGNAL(clicked()),this,SLOT(changeAltitudeClicked()));
connect(ui.changeSpeedButton,SIGNAL(clicked()),this,SLOT(changeSpeedClicked()));
connect(ui.goToWaypointButton,SIGNAL(clicked()),this,SLOT(goToWaypointClicked()));
connect(ui.armDisarmButton,SIGNAL(clicked()),this,SLOT(armButtonClicked()));
connect(UASManager::instance(),SIGNAL(activeUASSet(UASInterface*)),this,SLOT(activeUASSet(UASInterface*)));
if (UASManager::instance()->getActiveUAS())
{
activeUASSet(UASManager::instance()->getActiveUAS());
}
}
void UASActionsWidget::activeUASSet(UASInterface *uas)
{
m_uas = uas;
connect(m_uas->getWaypointManager(),SIGNAL(waypointEditableListChanged()),this,SLOT(updateWaypointList()));
connect(m_uas->getWaypointManager(),SIGNAL(currentWaypointChanged(quint16)),this,SLOT(currentWaypointChanged(quint16)));
connect(m_uas,SIGNAL(armingChanged(bool)),this,SLOT(armingChanged(bool)));
armingChanged(m_uas->isArmed());
updateWaypointList();
}
void UASActionsWidget::armButtonClicked()
{
if (m_uas)
{
if (m_uas->isArmed())
{
((UAS*)m_uas)->disarmSystem();
}
else
{
((UAS*)m_uas)->armSystem();
}
}
}
void UASActionsWidget::armingChanged(bool state)
{
//TODO:
//Figure out why arm/disarm is in UAS.h and not part of the interface, and fix.
if (state)
{
ui.armDisarmButton->setText("DISARM\nCurrently Armed");
}
else
{
ui.armDisarmButton->setText("ARM\nCurrently Disarmed");
}
}
void UASActionsWidget::currentWaypointChanged(quint16 wpid)
{
ui.currentWaypointLabel->setText("Current: " + QString::number(wpid));
}
void UASActionsWidget::updateWaypointList()
{
ui.waypointComboBox->clear();
for (int i=0;i<m_uas->getWaypointManager()->getWaypointEditableList().size();i++)
{
ui.waypointComboBox->addItem(QString::number(i));
}
}
UASActionsWidget::~UASActionsWidget()
{
}
void UASActionsWidget::goToWaypointClicked()
{
if (!m_uas)
{
return;
}
m_uas->getWaypointManager()->setCurrentWaypoint(ui.waypointComboBox->currentIndex());
}
void UASActionsWidget::changeAltitudeClicked()
{
QMessageBox::information(0,"Error","No implemented yet.");
}
void UASActionsWidget::changeSpeedClicked()
{
if (!m_uas)
{
return;
}
if (m_uas->getSystemType() == MAV_TYPE_QUADROTOR)
{
m_uas->setParameter(1,"WP_SPEED_MAX",QVariant(((float)ui.altitudeSpinBox->value() * 100)));
return;
}
else if (m_uas->getSystemType() == MAV_TYPE_FIXED_WING)
{
QVariant variant;
if (m_uas->getParamManager()->getParameterValue(1,"ARSPD_ENABLE",variant))
{
if (variant.toInt() == 1)
{
m_uas->setParameter(1,"TRIM_ARSPD_CN",QVariant(((float)ui.altitudeSpinBox->value() * 100)));
return;
}
}
m_uas->setParameter(1,"TRIM_ARSPD_CN",QVariant(((float)ui.altitudeSpinBox->value() * 100)));
}
}
......@@ -3,7 +3,8 @@
#include <QWidget>
#include "ui_UASActionsWidget.h"
#include <UASManager.h>
#include <UASInterface.h>
class UASActionsWidget : public QWidget
{
Q_OBJECT
......@@ -14,6 +15,16 @@ public:
private:
Ui::UASActionsWidget ui;
UASInterface *m_uas;
private slots:
void armButtonClicked();
void armingChanged(bool state);
void currentWaypointChanged(quint16 wpid);
void updateWaypointList();
void activeUASSet(UASInterface *uas);
void goToWaypointClicked();
void changeAltitudeClicked();
void changeSpeedClicked();
};
#endif // UASACTIONSWIDGET_H
......@@ -6,8 +6,8 @@
<rect>
<x>0</x>
<y>0</y>
<width>413</width>
<height>304</height>
<width>321</width>
<height>363</height>
</rect>
</property>
<property name="windowTitle">
......@@ -25,7 +25,7 @@
<property name="title">
<string>Mission Controls</string>
</property>
<widget class="QPushButton" name="pushButton_9">
<widget class="QPushButton" name="goToWaypointButton">
<property name="geometry">
<rect>
<x>10</x>
......@@ -38,7 +38,7 @@
<string>Go To Waypoint</string>
</property>
</widget>
<widget class="QComboBox" name="comboBox_2">
<widget class="QComboBox" name="waypointComboBox">
<property name="geometry">
<rect>
<x>10</x>
......@@ -48,19 +48,6 @@
</rect>
</property>
</widget>
<widget class="QPushButton" name="pushButton_6">
<property name="geometry">
<rect>
<x>150</x>
<y>50</y>
<width>81</width>
<height>23</height>
</rect>
</property>
<property name="text">
<string>Restart Mission</string>
</property>
</widget>
<widget class="QWidget" name="horizontalLayoutWidget">
<property name="geometry">
<rect>
......@@ -72,10 +59,10 @@
</property>
<layout class="QHBoxLayout" name="horizontalLayout">
<item>
<widget class="QSpinBox" name="spinBox_2"/>
<widget class="QSpinBox" name="speedSpinBox"/>
</item>
<item>
<widget class="QPushButton" name="pushButton_12">
<widget class="QPushButton" name="changeSpeedButton">
<property name="text">
<string>Change Speed</string>
</property>
......@@ -94,10 +81,10 @@
</property>
<layout class="QHBoxLayout" name="horizontalLayout_2">
<item>
<widget class="QSpinBox" name="spinBox"/>
<widget class="QSpinBox" name="altitudeSpinBox"/>
</item>
<item>
<widget class="QPushButton" name="pushButton_11">
<widget class="QPushButton" name="changeAltitudeButton">
<property name="text">
<string>Change Altitude</string>
</property>
......@@ -105,14 +92,40 @@
</item>
</layout>
</widget>
<widget class="QLabel" name="currentWaypointLabel">
<property name="geometry">
<rect>
<x>150</x>
<y>20</y>
<width>81</width>
<height>20</height>
</rect>
</property>
<property name="text">
<string>Current:</string>
</property>
</widget>
<widget class="QPushButton" name="pushButton_6">
<property name="geometry">
<rect>
<x>150</x>
<y>50</y>
<width>81</width>
<height>23</height>
</rect>
</property>
<property name="text">
<string>Restart Mission</string>
</property>
</widget>
</widget>
<widget class="QGroupBox" name="groupBox_2">
<property name="geometry">
<rect>
<x>0</x>
<y>180</y>
<width>401</width>
<height>111</height>
<width>311</width>
<height>161</height>
</rect>
</property>
<property name="title">
......@@ -203,17 +216,17 @@
<string>RTL</string>
</property>
</widget>
<widget class="QPushButton" name="pushButton_10">
<widget class="QPushButton" name="armDisarmButton">
<property name="geometry">
<rect>
<x>310</x>
<y>20</y>
<width>81</width>
<height>51</height>
<x>10</x>
<y>110</y>
<width>291</width>
<height>41</height>
</rect>
</property>
<property name="text">
<string>Arm/Disarm</string>
<string>ARM</string>
</property>
</widget>
</widget>
......
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