Commit b22d4023 authored by Michael Carpenter's avatar Michael Carpenter

ArduPlane level configuration widget

parent 771d74b7
......@@ -256,7 +256,8 @@ FORMS += src/ui/MainWindow.ui \
src/ui/configuration/GeoFenceConfig.ui \
src/ui/configuration/FailSafeConfig.ui \
src/ui/configuration/AdvancedParamConfig.ui \
src/ui/configuration/ArduCopterPidConfig.ui
src/ui/configuration/ArduCopterPidConfig.ui \
src/ui/configuration/ApmPlaneLevel.ui
INCLUDEPATH += src \
src/ui \
src/ui/linechart \
......@@ -437,7 +438,8 @@ HEADERS += src/MG.h \
src/ui/configuration/GeoFenceConfig.h \
src/ui/configuration/FailSafeConfig.h \
src/ui/configuration/AdvancedParamConfig.h \
src/ui/configuration/ArduCopterPidConfig.h
src/ui/configuration/ArduCopterPidConfig.h \
src/ui/configuration/ApmPlaneLevel.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|win32-msvc2012::HEADERS += src/ui/map3D/QGCGoogleEarthView.h
......@@ -636,7 +638,8 @@ SOURCES += src/main.cc \
src/ui/configuration/GeoFenceConfig.cc \
src/ui/configuration/FailSafeConfig.cc \
src/ui/configuration/AdvancedParamConfig.cc \
src/ui/configuration/ArduCopterPidConfig.cc
src/ui/configuration/ArduCopterPidConfig.cc \
src/ui/configuration/ApmPlaneLevel.cc
# Enable Google Earth only on Mac OS and Windows with Visual Studio compiler
macx|macx-g++|macx-g++42|win32-msvc2008|win32-msvc2010|win32-msvc2012::SOURCES += src/ui/map3D/QGCGoogleEarthView.cc
......
#include "ApmPlaneLevel.h"
#include <QMessageBox>
ApmPlaneLevel::ApmPlaneLevel(QWidget *parent) : AP2ConfigWidget(parent)
{
ui.setupUi(this);
connect(ui.levelPushButton,SIGNAL(clicked()),this,SLOT(levelClicked()));
connect(ui.manualLevelCheckBox,SIGNAL(toggled(bool)),this,SLOT(manualCheckBoxToggled(bool)));
}
ApmPlaneLevel::~ApmPlaneLevel()
{
}
void ApmPlaneLevel::levelClicked()
{
QMessageBox::information(0,"Warning","Be sure the plane is completly level, then click ok");
MAV_CMD command = MAV_CMD_PREFLIGHT_CALIBRATION;
int confirm = 0;
float param1 = 1;
float param2 = 0;
float param3 = 1;
float param4 = 0;
float param5 = 0;
float param6 = 0;
float param7 = 0;
int component = 1;
m_uas->executeCommand(command, confirm, param1, param2, param3, param4, param5, param6, param7, component);
QMessageBox::information(0,"Warning","Leveling completed");
}
void ApmPlaneLevel::manualCheckBoxToggled(bool checked)
{
if (!m_uas)
{
return;
}
if (checked)
{
m_uas->getParamManager()->setParameter(1,"MANUAL_LEVEL",1);
}
else
{
m_uas->getParamManager()->setParameter(1,"MANUAL_LEVEL",0);
}
}
void ApmPlaneLevel::parameterChanged(int uas, int component, QString parameterName, QVariant value)
{
if (parameterName == "MANUAL_LEVEL")
{
if (value.toInt() == 1)
{
ui.manualLevelCheckBox->setChecked(true);
}
else
{
ui.manualLevelCheckBox->setChecked(false);
}
}
}
#ifndef APMPLANELEVEL_H
#define APMPLANELEVEL_H
#include <QWidget>
#include "ui_ApmPlaneLevel.h"
#include "AP2ConfigWidget.h"
class ApmPlaneLevel : public AP2ConfigWidget
{
Q_OBJECT
public:
explicit ApmPlaneLevel(QWidget *parent = 0);
~ApmPlaneLevel();
private slots:
void parameterChanged(int uas, int component, QString parameterName, QVariant value);
void levelClicked();
void manualCheckBoxToggled(bool checked);
private:
Ui::ApmPlaneLevel ui;
};
#endif // APMPLANELEVEL_H
<?xml version="1.0" encoding="UTF-8"?>
<ui version="4.0">
<class>ApmPlaneLevel</class>
<widget class="QWidget" name="ApmPlaneLevel">
<property name="geometry">
<rect>
<x>0</x>
<y>0</y>
<width>400</width>
<height>300</height>
</rect>
</property>
<property name="windowTitle">
<string>Form</string>
</property>
<widget class="QLabel" name="label">
<property name="geometry">
<rect>
<x>10</x>
<y>10</y>
<width>141</width>
<height>31</height>
</rect>
</property>
<property name="text">
<string>&lt;h2&gt;ArduPlane Level&lt;/h2&gt;</string>
</property>
</widget>
<widget class="QLabel" name="label_2">
<property name="geometry">
<rect>
<x>50</x>
<y>70</y>
<width>271</width>
<height>41</height>
</rect>
</property>
<property name="text">
<string>By Default your plane will autolevel on every boot.
To disable this action you need to turn on manual
level and perform a level to calibrate the accel offsets.</string>
</property>
</widget>
<widget class="QLabel" name="label_3">
<property name="geometry">
<rect>
<x>50</x>
<y>150</y>
<width>291</width>
<height>16</height>
</rect>
</property>
<property name="text">
<string>Level your plane and click Level to set default accel offsets</string>
</property>
</widget>
<widget class="QPushButton" name="levelPushButton">
<property name="geometry">
<rect>
<x>160</x>
<y>180</y>
<width>75</width>
<height>23</height>
</rect>
</property>
<property name="text">
<string>Level</string>
</property>
</widget>
<widget class="QGroupBox" name="groupBox">
<property name="geometry">
<rect>
<x>120</x>
<y>230</y>
<width>151</width>
<height>51</height>
</rect>
</property>
<property name="title">
<string>For advanced users ONLY</string>
</property>
<widget class="QCheckBox" name="manualLevelCheckBox">
<property name="geometry">
<rect>
<x>30</x>
<y>20</y>
<width>91</width>
<height>17</height>
</rect>
</property>
<property name="text">
<string>Manual Level</string>
</property>
</widget>
</widget>
</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