1
0
mirror of https://bitbucket.org/librepilot/librepilot.git synced 2024-12-01 09:24:10 +01:00

OP-39 Output calibration functionality. Connection diagram updates.

This commit is contained in:
Fredrik Arvidsson 2012-09-03 01:01:57 +02:00
parent df987ab57f
commit a44ea92df7
17 changed files with 15636 additions and 10406 deletions

View File

@ -57,20 +57,20 @@ void ConnectionDiagram::showEvent(QShowEvent * event)
void ConnectionDiagram::setupGraphicsScene()
{
QGraphicsScene *scene = new QGraphicsScene(this);
ui->connectionDiagram->setScene(scene);
ui->connectionDiagram->setViewportUpdateMode(QGraphicsView::FullViewportUpdate);
m_renderer = new QSvgRenderer();
if (QFile::exists(QString(":/setupwizard/resources/connection-diagrams.svg")) &&
m_renderer->load(QString(":/setupwizard/resources/connection-diagrams.svg")) &&
m_renderer->isValid())
{
scene->clear();
QGraphicsScene *scene = new QGraphicsScene(this);
ui->connectionDiagram->setScene(scene);
//ui->connectionDiagram->setViewportUpdateMode(QGraphicsView::FullViewportUpdate);
m_background = new QGraphicsSvgItem();
m_background->setSharedRenderer(m_renderer);
m_background->setElementId("background");
m_background->setVisible(true);
m_background->setFlags(QGraphicsItem::ItemClipsToShape);
m_background->setOpacity(0);
//m_background->setFlags(QGraphicsItem::ItemClipsToShape);
m_background->setZValue(-1);
scene->addItem(m_background);
@ -124,10 +124,10 @@ void ConnectionDiagram::setupGraphicsScene()
switch (m_configSource->getInputType())
{
case VehicleConfigurationSource::INPUT_PWM:
elementsToShow << "receiver" << "pwm" ;
elementsToShow << "pwm" ;
break;
case VehicleConfigurationSource::INPUT_PPM:
elementsToShow << "receiver" << "ppm";
elementsToShow << "ppm";
break;
case VehicleConfigurationSource::INPUT_SBUS:
elementsToShow << "sbus";
@ -151,23 +151,28 @@ void ConnectionDiagram::setupGraphicsScene()
void ConnectionDiagram::setupGraphicsSceneItems(QGraphicsScene *scene, QList<QString> elementsToShow)
{
qreal z = 0;
QRectF backgBounds = m_renderer->boundsOnElement("background");
foreach(QString elementId, elementsToShow) {
if(m_renderer->elementExists(elementId)) {
QGraphicsSvgItem* element = new QGraphicsSvgItem();
element->setSharedRenderer(m_renderer);
element->setElementId(elementId);
element->setVisible(true);
element->setZValue(z++);
scene->addItem(element);
element->setOpacity(1.0);
QMatrix matrix = m_renderer->matrixForElement(elementId);
QRectF orig = matrix.mapRect(m_renderer->boundsOnElement(elementId));
element->setPos(orig.x(),orig.y());
//QRectF orig = m_renderer->boundsOnElement(elementId);
//element->setPos(orig.x() - backgBounds.x(), orig.y() - backgBounds.y());
scene->addItem(element);
qDebug() << "Adding " << elementId << " to scene at " << element->pos();
}
else
{
qDebug() << "Element " << elementId << " not found in renderer!";
else {
qDebug() << "Element with id: " << elementId << " not found.";
}
}
}

View File

@ -6,8 +6,8 @@
<rect>
<x>0</x>
<y>0</y>
<width>600</width>
<height>400</height>
<width>800</width>
<height>440</height>
</rect>
</property>
<property name="windowTitle">

View File

@ -0,0 +1,92 @@
/**
******************************************************************************
*
* @file outputcalibrationutil.cpp
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012.
* @addtogroup
* @{
* @addtogroup OutputCalibrationUtil
* @{
* @brief
*****************************************************************************/
/*
* This program 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.
*
* This program 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 this program; if not, write to the Free Software Foundation, Inc.,
* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA
*/
#include "outputcalibrationutil.h"
#include "actuatorcommand.h"
#include "extensionsystem/pluginmanager.h"
OutputCalibrationUtil::OutputCalibrationUtil(QObject *parent) :
QObject(parent), m_outputChannel(0)
{
ExtensionSystem::PluginManager *pm = ExtensionSystem::PluginManager::instance();
m_uavObjectManager = pm->getObject<UAVObjectManager>();
Q_ASSERT(m_uavObjectManager);
}
void OutputCalibrationUtil::startChannelOutput(quint16 channel)
{
if(m_outputChannel == 0 && channel > 0 && channel <= ActuatorCommand::CHANNEL_NUMELEM)
{
ActuatorCommand *actuatorCommand = ActuatorCommand::GetInstance(m_uavObjectManager);
Q_ASSERT(actuatorCommand);
UAVObject::Metadata metaData = actuatorCommand->getMetadata();
m_savedActuatorMetadata = metaData;
UAVObject::SetFlightAccess(metaData, UAVObject::ACCESS_READONLY);
UAVObject::SetFlightTelemetryUpdateMode(metaData, UAVObject::UPDATEMODE_ONCHANGE);
UAVObject::SetGcsTelemetryAcked(metaData, false);
UAVObject::SetGcsTelemetryUpdateMode(metaData, UAVObject::UPDATEMODE_ONCHANGE);
metaData.gcsTelemetryUpdatePeriod = 100;
actuatorCommand->setMetadata(metaData);
actuatorCommand->updated();
//Start output...
m_outputChannel = channel;
}
}
void OutputCalibrationUtil::stopChannelOutput()
{
if(m_outputChannel > 0)
{
//Stop output...
ActuatorCommand *actuatorCommand = ActuatorCommand::GetInstance(m_uavObjectManager);
Q_ASSERT(actuatorCommand);
UAVObject::Metadata metaData = actuatorCommand->getMetadata();
// Restore metadata to what it was before
metaData = m_savedActuatorMetadata;
actuatorCommand->setMetadata(metaData);
actuatorCommand->updated();
m_outputChannel = 0;
}
}
void OutputCalibrationUtil::setChannelOutputValue(quint16 value)
{
if(m_outputChannel > 0)
{
//Set output value
ActuatorCommand *actuatorCommand = ActuatorCommand::GetInstance(m_uavObjectManager);
Q_ASSERT(actuatorCommand);
ActuatorCommand::DataFields data = actuatorCommand->getData();
data.Channel[m_outputChannel - 1] = value;
actuatorCommand->setData(data);
}
}

View File

@ -0,0 +1,57 @@
/**
******************************************************************************
*
* @file outputcalibrationutil.h
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012.
* @addtogroup
* @{
* @addtogroup OutputCalibrationUtil
* @{
* @brief
*****************************************************************************/
/*
* This program 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.
*
* This program 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 this program; if not, write to the Free Software Foundation, Inc.,
* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA
*/
#ifndef OUTPUTCALIBRATIONUTIL_H
#define OUTPUTCALIBRATIONUTIL_H
#include <QObject>
#include "uavobject.h"
#include "uavobjectmanager.h"
class OutputCalibrationUtil : public QObject
{
Q_OBJECT
public:
explicit OutputCalibrationUtil(QObject *parent = 0);
signals:
public slots:
void startChannelOutput(quint16 channel);
void stopChannelOutput();
void setChannelOutputValue(quint16 value);
private:
quint16 m_outputChannel;
UAVObject::Metadata m_savedActuatorMetadata;
UAVObjectManager *m_uavObjectManager;
};
#endif // OUTPUTCALIBRATIONUTIL_H

View File

@ -68,7 +68,7 @@ void FlashPage::writeToController()
ui->saveButton->setEnabled(false);
getWizard()->button(QWizard::CancelButton)->setEnabled(false);
getWizard()->button(QWizard::BackButton)->setEnabled(false);
setCommitPage(true);
VehicleConfigurationHelper helper(getWizard());
connect(&helper, SIGNAL(saveProgress(int, int, QString)),this, SLOT(saveProgress(int, int, QString)));
m_successfulWrite = helper.setupVehicle();
@ -76,7 +76,7 @@ void FlashPage::writeToController()
ui->saveProgressLabel->setText(QString("<font color='%1'>%2</font>").arg(m_successfulWrite ? "green" : "red", ui->saveProgressLabel->text()));
ui->saveButton->setEnabled(true);
getWizard()->button(QWizard::CancelButton)->setEnabled(true);
getWizard()->button(QWizard::BackButton)->setEnabled(true);
setCommitPage(false);
emit completeChanged();
}

View File

@ -71,7 +71,6 @@ void LevellingPage::performLevelling()
}
getWizard()->button(QWizard::CancelButton)->setEnabled(false);
getWizard()->button(QWizard::BackButton)->setEnabled(false);
ui->levelButton->setEnabled(false);
if(!m_levellingUtil)
@ -122,8 +121,7 @@ void LevellingPage::stopLevelling()
disconnect(m_levellingUtil, SIGNAL(progress(long,long)), this, SLOT(levellingProgress(long,long)));
disconnect(m_levellingUtil, SIGNAL(done(accelGyroBias)), this, SLOT(levellingDone(accelGyroBias)));
disconnect(m_levellingUtil, SIGNAL(timeout(QString)), this, SLOT(levellingTimeout(QString)));
ui->levelButton->setEnabled(true);
getWizard()->button(QWizard::CancelButton)->setEnabled(true);
getWizard()->button(QWizard::BackButton)->setEnabled(true);
ui->levelButton->setEnabled(true);
}
}

View File

@ -29,12 +29,213 @@
#include "ui_outputcalibrationpage.h"
OutputCalibrationPage::OutputCalibrationPage(SetupWizard *wizard, QWidget *parent) :
AbstractWizardPage(wizard, parent), ui(new Ui::OutputCalibrationPage)
AbstractWizardPage(wizard, parent), ui(new Ui::OutputCalibrationPage), m_vehicleBoundsItem(0),
m_currentWizardIndex(0), m_calibrationUtil(0)
{
ui->setupUi(this);
m_calibrationUtil = new OutputCalibrationUtil();
m_vehicleRenderer = new QSvgRenderer();
if (QFile::exists(QString(":/setupwizard/resources/multirotor-shapes.svg")) &&
m_vehicleRenderer->load(QString(":/setupwizard/resources/multirotor-shapes.svg")) &&
m_vehicleRenderer->isValid())
{
m_vehicleScene = new QGraphicsScene(this);
ui->vehicleView->setScene(m_vehicleScene);
}
}
OutputCalibrationPage::~OutputCalibrationPage()
{
if(m_calibrationUtil) {
delete m_calibrationUtil;
}
delete ui;
}
void OutputCalibrationPage::setupVehicle()
{
m_wizardIndexes.clear();
m_vehicleElementIds.clear();
m_vehicleHighlightElementIndexes.clear();
m_currentWizardIndex = 0;
m_vehicleScene->clear();
switch(getWizard()->getVehicleSubType())
{
case SetupWizard::MULTI_ROTOR_TRI_Y:
m_wizardIndexes << 0 << 1 << 2 << 1 << 2 << 1 << 2 << 3 << 4;
m_vehicleElementIds << "tri" << "tri-frame" << "tri-m1" << "tri-m2" << "tri-m3" << "tri-s1";
m_vehicleHighlightElementIndexes << 0 << 1 << 1 << 2 << 2 << 3 << 3 << 4 << 4;
break;
case SetupWizard::MULTI_ROTOR_QUAD_X:
m_wizardIndexes << 0 << 1 << 2 << 1 << 2 << 1 << 2 << 1 << 2;
m_vehicleElementIds << "quad-x" << "quad-x-frame" << "quad-x-m1" << "quad-x-m2" << "quad-x-m3" << "quad-x-m4";
m_vehicleHighlightElementIndexes << 0 << 1 << 1 << 2 << 2 << 3 << 3 << 4 << 4;
break;
case SetupWizard::MULTI_ROTOR_QUAD_PLUS:
m_wizardIndexes << 0 << 1 << 2 << 1 << 2 << 1 << 2 << 1 << 2;
m_vehicleElementIds << "quad-p" << "quad-p-frame" << "quad-p-m1" << "quad-p-m2" << "quad-p-m3" << "quad-p-m4";
m_vehicleHighlightElementIndexes << 0 << 1 << 1 << 2 << 2 << 3 << 3 << 4 << 4;
break;
case SetupWizard::MULTI_ROTOR_HEXA:
m_wizardIndexes << 0 << 1 << 2 << 1 << 2 << 1 << 2 << 1 << 2 << 1 << 2 << 1 << 2;
m_vehicleElementIds << "hexa" << "hexa-frame" << "hexa-m1" << "hexa-m2" << "hexa-m3" << "hexa-m4" << "hexa-m5" << "hexa-m6";
m_vehicleHighlightElementIndexes << 0 << 1 << 1 << 2 << 2 << 3 << 3 << 4 << 4 << 5 << 5 << 6 << 6;
break;
case SetupWizard::MULTI_ROTOR_HEXA_COAX_Y:
m_wizardIndexes << 0 << 1 << 2 << 1 << 2 << 1 << 2 << 1 << 2 << 1 << 2 << 1 << 2;
m_vehicleElementIds << "hexa-y6" << "hexa-y6-frame" << "hexa-y6-m1" << "hexa-y6-m2" << "hexa-y6-m3" << "hexa-y6-m4" << "hexa-y6-m5" << "hexa-y6-m6";
m_vehicleHighlightElementIndexes << 0 << 1 << 1 << 2 << 2 << 3 << 3 << 4 << 4 << 5 << 5 << 6 << 6;
break;
case SetupWizard::MULTI_ROTOR_HEXA_H:
m_wizardIndexes << 0 << 1 << 2 << 1 << 2 << 1 << 2 << 1 << 2 << 1 << 2 << 1 << 2;
m_vehicleElementIds << "hexa-h" << "hexa-h-frame" << "hexa-h-m1" << "hexa-h-m2" << "hexa-h-m3" << "hexa-h-m4" << "hexa-h-m5" << "hexa-h-m6";
m_vehicleHighlightElementIndexes << 0 << 1 << 1 << 2 << 2 << 3 << 3 << 4 << 4 << 5 << 5 << 6 << 6;
break;
default:
break;
}
setupVehicleItems();
}
void OutputCalibrationPage::setupVehicleItems()
{
m_vehicleItems.clear();
m_vehicleBoundsItem = new QGraphicsSvgItem();
m_vehicleBoundsItem->setSharedRenderer(m_vehicleRenderer);
m_vehicleBoundsItem->setElementId(m_vehicleElementIds[0]);
m_vehicleBoundsItem->setZValue(-1);
m_vehicleBoundsItem->setOpacity(0);
m_vehicleScene->addItem(m_vehicleBoundsItem);
QRectF parentBounds = m_vehicleRenderer->boundsOnElement(m_vehicleElementIds[0]);
for(int i = 1; i < m_vehicleElementIds.size(); i++)
{
QGraphicsSvgItem *item = new QGraphicsSvgItem();
item->setSharedRenderer(m_vehicleRenderer);
item->setElementId(m_vehicleElementIds[i]);
item->setZValue(i);
item->setOpacity(1.0);
QRectF itemBounds = m_vehicleRenderer->boundsOnElement(m_vehicleElementIds[i]);
item->setPos(itemBounds.x() - parentBounds.x(), itemBounds.y() - parentBounds.y());
m_vehicleScene->addItem(item);
m_vehicleItems << item;
}
}
void OutputCalibrationPage::startWizard()
{
ui->calibrationStack->setCurrentIndex(m_wizardIndexes[0]);
setupVehicleHighlightedPart();
}
void OutputCalibrationPage::setupVehicleHighlightedPart()
{
qreal dimOpaque = m_currentWizardIndex == 0 ? 1.0 : 0.3;
qreal highlightOpaque = 1.0;
int highlightedIndex = m_vehicleHighlightElementIndexes[m_currentWizardIndex];
for(int i = 0; i < m_vehicleItems.size(); i++) {
QGraphicsSvgItem* item = m_vehicleItems[i];
item->setOpacity((highlightedIndex == i) ? highlightOpaque : dimOpaque);
}
}
void OutputCalibrationPage::setWizardPage()
{
m_calibrationUtil->stopChannelOutput();
ui->backPageButton->setEnabled(m_currentWizardIndex > 0);
ui->nextPageButton->setEnabled(m_currentWizardIndex < (m_wizardIndexes.size() - 1));
ui->calibrationStack->setCurrentIndex(m_wizardIndexes.at(m_currentWizardIndex));
setupVehicleHighlightedPart();
}
void OutputCalibrationPage::initializePage()
{
if(m_vehicleScene) {
setupVehicle();
startWizard();
}
}
void OutputCalibrationPage::showEvent(QShowEvent *event)
{
Q_UNUSED(event);
if(m_vehicleBoundsItem) {
ui->vehicleView->setSceneRect(m_vehicleBoundsItem->boundingRect());
ui->vehicleView->fitInView(m_vehicleBoundsItem, Qt::KeepAspectRatio);
}
}
void OutputCalibrationPage::on_nextPageButton_clicked()
{
if(m_currentWizardIndex < m_wizardIndexes.size()) {
m_currentWizardIndex++;
setWizardPage();
}
}
void OutputCalibrationPage::on_backPageButton_clicked()
{
if(m_currentWizardIndex > 0) {
m_currentWizardIndex--;
setWizardPage();
}
}
void OutputCalibrationPage::on_motorNeutralButton_toggled(bool checked)
{
if(checked) {
m_calibrationUtil->startChannelOutput(m_vehicleHighlightElementIndexes[m_currentWizardIndex]);
m_calibrationUtil->setChannelOutputValue(ui->motorNeutralSlider->value());
}
else {
m_calibrationUtil->setChannelOutputValue(ui->motorNeutralSlider->minimum());
m_calibrationUtil->stopChannelOutput();
}
}
void OutputCalibrationPage::on_motorNeutralSlider_valueChanged(int value)
{
if(ui->motorNeutralButton->isChecked())
{
m_calibrationUtil->setChannelOutputValue(ui->motorNeutralSlider->value());
}
}
void OutputCalibrationPage::on_motorMaxButton_toggled(bool checked)
{
}
void OutputCalibrationPage::on_motorMaxSlider_valueChanged(int position)
{
}
void OutputCalibrationPage::on_servoCenterButton_toggled(bool checked)
{
}
void OutputCalibrationPage::on_servoAngleButton_toggled(bool checked)
{
}
void OutputCalibrationPage::on_servoMaxAngleSlider_valueChanged(int position)
{
}
void OutputCalibrationPage::on_servoMinAngleSlider_valueChanged(int position)
{
}
void OutputCalibrationPage::on_servoCenterSlider_valueChanged(int position)
{
}

View File

@ -28,7 +28,10 @@
#ifndef OUTPUTCALIBRATIONPAGE_H
#define OUTPUTCALIBRATIONPAGE_H
#include <QtSvg>
#include "abstractwizardpage.h"
#include "setupwizard.h"
#include "outputcalibrationutil.h"
namespace Ui {
class OutputCalibrationPage;
@ -41,9 +44,49 @@ class OutputCalibrationPage : public AbstractWizardPage
public:
explicit OutputCalibrationPage(SetupWizard *wizard, QWidget *parent = 0);
~OutputCalibrationPage();
void initializePage();
protected:
void showEvent(QShowEvent *event);
private slots:
void on_nextPageButton_clicked();
void on_backPageButton_clicked();
void on_motorNeutralButton_toggled(bool checked);
void on_motorNeutralSlider_valueChanged(int value);
void on_motorMaxButton_toggled(bool checked);
void on_motorMaxSlider_valueChanged(int position);
void on_servoCenterButton_toggled(bool checked);
void on_servoCenterSlider_valueChanged(int position);
void on_servoAngleButton_toggled(bool checked);
void on_servoMaxAngleSlider_valueChanged(int position);
void on_servoMinAngleSlider_valueChanged(int position);
private:
void setupVehicle();
void startWizard();
void setupVehicleItems();
void setupVehicleHighlightedPart();
void setWizardPage();
Ui::OutputCalibrationPage *ui;
QSvgRenderer *m_vehicleRenderer;
QGraphicsScene *m_vehicleScene;
QGraphicsSvgItem *m_vehicleBoundsItem;
quint16 m_currentWizardIndex;
QList<QString> m_vehicleElementIds;
QList<QGraphicsSvgItem*> m_vehicleItems;
QList<quint16> m_vehicleHighlightElementIndexes;
QList<quint16> m_wizardIndexes;
OutputCalibrationUtil *m_calibrationUtil;
};
#endif // OUTPUTCALIBRATIONPAGE_H

View File

@ -13,104 +13,617 @@
<property name="windowTitle">
<string>WizardPage</string>
</property>
<widget class="QGraphicsView" name="graphicsView">
<widget class="QGraphicsView" name="vehicleView">
<property name="geometry">
<rect>
<x>310</x>
<x>300</x>
<y>40</y>
<width>250</width>
<height>250</height>
<width>270</width>
<height>270</height>
</rect>
</property>
<property name="frameShape">
<enum>QFrame::NoFrame</enum>
</property>
</widget>
<widget class="QSlider" name="verticalSlider">
<widget class="QStackedWidget" name="calibrationStack">
<property name="geometry">
<rect>
<x>110</x>
<y>341</y>
<width>380</width>
<height>20</height>
<x>20</x>
<y>40</y>
<width>270</width>
<height>291</height>
</rect>
</property>
<property name="orientation">
<enum>Qt::Horizontal</enum>
</property>
<property name="tickPosition">
<enum>QSlider::TicksBelow</enum>
</property>
<property name="tickInterval">
<number>10</number>
<property name="currentIndex">
<number>1</number>
</property>
<widget class="QWidget" name="intro">
<widget class="QLabel" name="label_3">
<property name="geometry">
<rect>
<x>0</x>
<y>10</y>
<width>261</width>
<height>281</height>
</rect>
</property>
<property name="text">
<string>&lt;html&gt;&lt;head/&gt;&lt;body&gt;&lt;p&gt;&lt;span style=&quot; font-size:10pt;&quot;&gt;It is now time to calibrate the output levels for the signal controlling your vehichle. &lt;/span&gt;&lt;/p&gt;&lt;p&gt;&lt;span style=&quot; font-size:10pt;&quot;&gt;Depending on what vehichle you have selected, both motors controlled by ESC and servos controlled directly by the OpenPilot controller may have to be calibrated. &lt;br/&gt;The following steps will guide you safely through this process.&lt;br/&gt;&lt;/span&gt;&lt;/p&gt;&lt;p align=&quot;center&quot;&gt;&lt;span style=&quot; font-size:14pt; font-weight:600; color:#ff0000;&quot;&gt;VERY IMPORTANT!&lt;/span&gt;&lt;/p&gt;&lt;p align=&quot;center&quot;&gt;&lt;br/&gt;&lt;span style=&quot; font-size:12pt; font-weight:600; color:#ff0000;&quot;&gt;REMOVE ALL PROPELLERS FROM THE VEHICHLE BEFORE PROCEEDING!&lt;/span&gt;&lt;/p&gt;&lt;/body&gt;&lt;/html&gt;</string>
</property>
<property name="alignment">
<set>Qt::AlignLeading|Qt::AlignLeft|Qt::AlignTop</set>
</property>
<property name="wordWrap">
<bool>true</bool>
</property>
</widget>
</widget>
<widget class="QWidget" name="motorNeutral">
<widget class="QLabel" name="label_4">
<property name="geometry">
<rect>
<x>0</x>
<y>10</y>
<width>261</width>
<height>141</height>
</rect>
</property>
<property name="text">
<string>&lt;html&gt;&lt;head/&gt;&lt;body&gt;&lt;p&gt;In this step we will set the neutral rate for the motor highlighted in the illustration to the right. &lt;br/&gt;Plase pay attention to the details and in particular the motors position and its rotation direction.&lt;/p&gt;&lt;p&gt;To find the neutral rate for this engine, press the Start button below and slide the slider to the right until the engine just starts to spin stably. &lt;br/&gt;&lt;br/&gt;When done press button again to stop.&lt;/p&gt;&lt;/body&gt;&lt;/html&gt;</string>
</property>
<property name="alignment">
<set>Qt::AlignLeading|Qt::AlignLeft|Qt::AlignTop</set>
</property>
<property name="wordWrap">
<bool>true</bool>
</property>
</widget>
<widget class="QSlider" name="motorNeutralSlider">
<property name="enabled">
<bool>false</bool>
</property>
<property name="geometry">
<rect>
<x>10</x>
<y>200</y>
<width>241</width>
<height>19</height>
</rect>
</property>
<property name="minimum">
<number>1000</number>
</property>
<property name="maximum">
<number>1400</number>
</property>
<property name="singleStep">
<number>10</number>
</property>
<property name="pageStep">
<number>20</number>
</property>
<property name="orientation">
<enum>Qt::Horizontal</enum>
</property>
<property name="invertedAppearance">
<bool>false</bool>
</property>
<property name="tickPosition">
<enum>QSlider::TicksBelow</enum>
</property>
<property name="tickInterval">
<number>20</number>
</property>
</widget>
<widget class="QPushButton" name="motorNeutralButton">
<property name="geometry">
<rect>
<x>90</x>
<y>240</y>
<width>75</width>
<height>23</height>
</rect>
</property>
<property name="text">
<string>Start</string>
</property>
<property name="checkable">
<bool>true</bool>
</property>
<property name="checked">
<bool>false</bool>
</property>
</widget>
</widget>
<widget class="QWidget" name="motorMax">
<widget class="QPushButton" name="motorMaxButton">
<property name="geometry">
<rect>
<x>90</x>
<y>240</y>
<width>75</width>
<height>23</height>
</rect>
</property>
<property name="text">
<string>Start</string>
</property>
<property name="checkable">
<bool>true</bool>
</property>
<property name="checked">
<bool>false</bool>
</property>
</widget>
<widget class="QLabel" name="label_5">
<property name="geometry">
<rect>
<x>0</x>
<y>10</y>
<width>261</width>
<height>171</height>
</rect>
</property>
<property name="text">
<string>&lt;html&gt;&lt;head/&gt;&lt;body&gt;&lt;p&gt;Now it is time to find out the maximum rate for the motor highlighted in the illustration to the right. &lt;/p&gt;&lt;p&gt;To find the maximum rate for this engine, press the Start button below and slide the slider to the left until the engine just starts to slow down.&lt;/p&gt;&lt;p&gt;Running a brushless motor for a long time without proper cooling can in theory damage it. Therefore do not leave the motor running at full rate longer than neccesary.&lt;br/&gt;&lt;br/&gt;When done press button again to stop.&lt;/p&gt;&lt;/body&gt;&lt;/html&gt;</string>
</property>
<property name="alignment">
<set>Qt::AlignLeading|Qt::AlignLeft|Qt::AlignTop</set>
</property>
<property name="wordWrap">
<bool>true</bool>
</property>
</widget>
<widget class="QSlider" name="motorMaxSlider">
<property name="enabled">
<bool>false</bool>
</property>
<property name="geometry">
<rect>
<x>10</x>
<y>200</y>
<width>241</width>
<height>19</height>
</rect>
</property>
<property name="minimum">
<number>1600</number>
</property>
<property name="maximum">
<number>2000</number>
</property>
<property name="singleStep">
<number>10</number>
</property>
<property name="pageStep">
<number>20</number>
</property>
<property name="value">
<number>2000</number>
</property>
<property name="orientation">
<enum>Qt::Horizontal</enum>
</property>
<property name="invertedAppearance">
<bool>false</bool>
</property>
<property name="invertedControls">
<bool>false</bool>
</property>
<property name="tickPosition">
<enum>QSlider::TicksBelow</enum>
</property>
<property name="tickInterval">
<number>20</number>
</property>
</widget>
</widget>
<widget class="QWidget" name="servoNeutral">
<widget class="QLabel" name="label_6">
<property name="geometry">
<rect>
<x>0</x>
<y>10</y>
<width>261</width>
<height>141</height>
</rect>
</property>
<property name="text">
<string>&lt;html&gt;&lt;head/&gt;&lt;body&gt;&lt;p&gt;This step calibrates the center position of the servo. To set the center position for this servo, press the Start button below and slide the slider to center the servo. &lt;/p&gt;&lt;p&gt;When done press button again to stop.&lt;/p&gt;&lt;/body&gt;&lt;/html&gt;</string>
</property>
<property name="alignment">
<set>Qt::AlignLeading|Qt::AlignLeft|Qt::AlignTop</set>
</property>
<property name="wordWrap">
<bool>true</bool>
</property>
</widget>
<widget class="QSlider" name="servoCenterSlider">
<property name="enabled">
<bool>false</bool>
</property>
<property name="geometry">
<rect>
<x>10</x>
<y>200</y>
<width>241</width>
<height>19</height>
</rect>
</property>
<property name="minimum">
<number>1000</number>
</property>
<property name="maximum">
<number>2000</number>
</property>
<property name="singleStep">
<number>10</number>
</property>
<property name="pageStep">
<number>20</number>
</property>
<property name="value">
<number>1500</number>
</property>
<property name="tracking">
<bool>false</bool>
</property>
<property name="orientation">
<enum>Qt::Horizontal</enum>
</property>
<property name="invertedAppearance">
<bool>false</bool>
</property>
<property name="invertedControls">
<bool>false</bool>
</property>
<property name="tickPosition">
<enum>QSlider::TicksBelow</enum>
</property>
<property name="tickInterval">
<number>40</number>
</property>
</widget>
<widget class="QPushButton" name="servoCenterButton">
<property name="geometry">
<rect>
<x>90</x>
<y>240</y>
<width>75</width>
<height>23</height>
</rect>
</property>
<property name="text">
<string>Start</string>
</property>
<property name="checkable">
<bool>true</bool>
</property>
<property name="checked">
<bool>false</bool>
</property>
</widget>
</widget>
<widget class="QWidget" name="servoMinMax">
<widget class="QPushButton" name="servoAngleButton">
<property name="geometry">
<rect>
<x>90</x>
<y>240</y>
<width>75</width>
<height>23</height>
</rect>
</property>
<property name="text">
<string>Start</string>
</property>
<property name="checkable">
<bool>true</bool>
</property>
<property name="checked">
<bool>false</bool>
</property>
</widget>
<widget class="QLabel" name="label_7">
<property name="geometry">
<rect>
<x>0</x>
<y>10</y>
<width>261</width>
<height>151</height>
</rect>
</property>
<property name="text">
<string>&lt;html&gt;&lt;head/&gt;&lt;body&gt;&lt;p&gt;To save the servo and other hardware from damage we have to set the max and min angles for the servo. &lt;/p&gt;&lt;p&gt;To set the extreme angles for the servo, press the Start button below and select the top slider and slide it to the right until max angle is reached. Then select the lower slider and slide it left until the minimum angle is set.&lt;/p&gt;&lt;p&gt;When done press button again to stop.&lt;/p&gt;&lt;/body&gt;&lt;/html&gt;</string>
</property>
<property name="alignment">
<set>Qt::AlignLeading|Qt::AlignLeft|Qt::AlignTop</set>
</property>
<property name="wordWrap">
<bool>true</bool>
</property>
</widget>
<widget class="QWidget" name="sliderWidget" native="true">
<property name="geometry">
<rect>
<x>0</x>
<y>160</y>
<width>261</width>
<height>80</height>
</rect>
</property>
<widget class="QRadioButton" name="servoMinAngleSliderRB">
<property name="geometry">
<rect>
<x>10</x>
<y>40</y>
<width>16</width>
<height>17</height>
</rect>
</property>
<property name="text">
<string/>
</property>
</widget>
<widget class="QRadioButton" name="servoMaxAngleSliderRB">
<property name="geometry">
<rect>
<x>10</x>
<y>0</y>
<width>16</width>
<height>17</height>
</rect>
</property>
<property name="text">
<string/>
</property>
<property name="checked">
<bool>true</bool>
</property>
</widget>
<widget class="QSlider" name="servoMaxAngleSlider">
<property name="geometry">
<rect>
<x>39</x>
<y>0</y>
<width>211</width>
<height>20</height>
</rect>
</property>
<property name="minimum">
<number>1500</number>
</property>
<property name="maximum">
<number>2000</number>
</property>
<property name="singleStep">
<number>10</number>
</property>
<property name="pageStep">
<number>20</number>
</property>
<property name="value">
<number>1500</number>
</property>
<property name="tracking">
<bool>false</bool>
</property>
<property name="orientation">
<enum>Qt::Horizontal</enum>
</property>
<property name="invertedAppearance">
<bool>false</bool>
</property>
<property name="invertedControls">
<bool>false</bool>
</property>
<property name="tickPosition">
<enum>QSlider::TicksBelow</enum>
</property>
<property name="tickInterval">
<number>40</number>
</property>
</widget>
<widget class="QSlider" name="servoMinAngleSlider">
<property name="enabled">
<bool>false</bool>
</property>
<property name="geometry">
<rect>
<x>39</x>
<y>40</y>
<width>211</width>
<height>20</height>
</rect>
</property>
<property name="minimum">
<number>1000</number>
</property>
<property name="maximum">
<number>1500</number>
</property>
<property name="singleStep">
<number>10</number>
</property>
<property name="pageStep">
<number>20</number>
</property>
<property name="value">
<number>1500</number>
</property>
<property name="tracking">
<bool>false</bool>
</property>
<property name="orientation">
<enum>Qt::Horizontal</enum>
</property>
<property name="invertedAppearance">
<bool>false</bool>
</property>
<property name="invertedControls">
<bool>false</bool>
</property>
<property name="tickPosition">
<enum>QSlider::TicksBelow</enum>
</property>
<property name="tickInterval">
<number>40</number>
</property>
</widget>
</widget>
</widget>
</widget>
<widget class="QSpinBox" name="spinBox">
<widget class="QLabel" name="label_2">
<property name="geometry">
<rect>
<x>40</x>
<y>340</y>
<width>50</width>
<height>22</height>
<x>20</x>
<y>20</y>
<width>531</width>
<height>16</height>
</rect>
</property>
<property name="layoutDirection">
<enum>Qt::LeftToRight</enum>
<property name="font">
<font>
<pointsize>12</pointsize>
<weight>75</weight>
<bold>true</bold>
</font>
</property>
<property name="text">
<string>Output calibration</string>
</property>
<property name="alignment">
<set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
<set>Qt::AlignLeading|Qt::AlignLeft|Qt::AlignVCenter</set>
</property>
<property name="readOnly">
</widget>
<widget class="QPushButton" name="nextPageButton">
<property name="geometry">
<rect>
<x>148</x>
<y>340</y>
<width>75</width>
<height>23</height>
</rect>
</property>
<property name="text">
<string>&gt;</string>
</property>
</widget>
<widget class="QPushButton" name="backPageButton">
<property name="enabled">
<bool>false</bool>
</property>
<property name="buttonSymbols">
<enum>QAbstractSpinBox::UpDownArrows</enum>
</property>
<property name="specialValueText">
<string/>
</property>
<property name="suffix">
<string/>
</property>
<property name="maximum">
<number>2500</number>
</property>
<property name="value">
<number>1000</number>
</property>
</widget>
<widget class="QSpinBox" name="spinBox_2">
<property name="geometry">
<rect>
<x>510</x>
<x>68</x>
<y>340</y>
<width>50</width>
<height>22</height>
<width>75</width>
<height>23</height>
</rect>
</property>
<property name="layoutDirection">
<enum>Qt::LeftToRight</enum>
</property>
<property name="alignment">
<set>Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter</set>
</property>
<property name="buttonSymbols">
<enum>QAbstractSpinBox::UpDownArrows</enum>
</property>
<property name="specialValueText">
<string/>
</property>
<property name="suffix">
<string/>
</property>
<property name="maximum">
<number>2500</number>
</property>
<property name="value">
<number>2000</number>
<property name="text">
<string>&lt;</string>
</property>
</widget>
</widget>
<resources/>
<connections/>
<connections>
<connection>
<sender>servoMaxAngleSliderRB</sender>
<signal>toggled(bool)</signal>
<receiver>servoMaxAngleSlider</receiver>
<slot>setEnabled(bool)</slot>
<hints>
<hint type="sourcelabel">
<x>37</x>
<y>208</y>
</hint>
<hint type="destinationlabel">
<x>164</x>
<y>209</y>
</hint>
</hints>
</connection>
<connection>
<sender>servoMinAngleSliderRB</sender>
<signal>toggled(bool)</signal>
<receiver>servoMinAngleSlider</receiver>
<slot>setEnabled(bool)</slot>
<hints>
<hint type="sourcelabel">
<x>37</x>
<y>248</y>
</hint>
<hint type="destinationlabel">
<x>164</x>
<y>249</y>
</hint>
</hints>
</connection>
<connection>
<sender>motorNeutralButton</sender>
<signal>toggled(bool)</signal>
<receiver>motorNeutralSlider</receiver>
<slot>setEnabled(bool)</slot>
<hints>
<hint type="sourcelabel">
<x>147</x>
<y>291</y>
</hint>
<hint type="destinationlabel">
<x>150</x>
<y>249</y>
</hint>
</hints>
</connection>
<connection>
<sender>motorMaxButton</sender>
<signal>toggled(bool)</signal>
<receiver>motorMaxSlider</receiver>
<slot>setEnabled(bool)</slot>
<hints>
<hint type="sourcelabel">
<x>147</x>
<y>291</y>
</hint>
<hint type="destinationlabel">
<x>150</x>
<y>249</y>
</hint>
</hints>
</connection>
<connection>
<sender>servoCenterButton</sender>
<signal>toggled(bool)</signal>
<receiver>servoCenterSlider</receiver>
<slot>setEnabled(bool)</slot>
<hints>
<hint type="sourcelabel">
<x>147</x>
<y>291</y>
</hint>
<hint type="destinationlabel">
<x>150</x>
<y>249</y>
</hint>
</hints>
</connection>
<connection>
<sender>servoAngleButton</sender>
<signal>toggled(bool)</signal>
<receiver>sliderWidget</receiver>
<slot>setEnabled(bool)</slot>
<hints>
<hint type="sourcelabel">
<x>147</x>
<y>291</y>
</hint>
<hint type="destinationlabel">
<x>150</x>
<y>239</y>
</hint>
</hints>
</connection>
</connections>
</ui>

View File

@ -45,7 +45,7 @@ p, li { white-space: pre-wrap; }
&lt;p align=&quot;center&quot; style=&quot; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;&quot;&gt;&lt;span style=&quot; font-size:12pt; font-weight:600; color:#ff0000;&quot;&gt;REMOVE ALL PROPELLERS FROM THE VEHICHLE &lt;/span&gt;&lt;/p&gt;
&lt;p align=&quot;center&quot; style=&quot; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;&quot;&gt;&lt;span style=&quot; font-size:12pt; font-weight:600; color:#ff0000;&quot;&gt;BEFORE PROCEEDING!&lt;/span&gt;&lt;/p&gt;
&lt;p style=&quot;-qt-paragraph-type:empty; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px; font-size:10pt;&quot;&gt;&lt;br /&gt;&lt;/p&gt;
&lt;p style=&quot; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;&quot;&gt;&lt;span style=&quot; font-size:10pt;&quot;&gt;Ignoring the above request will put you in a&lt;/span&gt;&lt;span style=&quot; font-size:10pt; font-weight:600; color:#ff0000;&quot;&gt; risk of serious injury&lt;/span&gt;&lt;span style=&quot; font-size:10pt;&quot;&gt;!&lt;/span&gt;&lt;/p&gt;
&lt;p style=&quot; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;&quot;&gt;&lt;span style=&quot; font-size:10pt;&quot;&gt;Ignoring the above request will put you in a&lt;/span&gt;&lt;span style=&quot; font-size:10pt; font-weight:600; color:#000000;&quot;&gt; risk of serious injury&lt;/span&gt;&lt;span style=&quot; font-size:10pt;&quot;&gt;!&lt;/span&gt;&lt;/p&gt;
&lt;p style=&quot;-qt-paragraph-type:empty; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px; font-size:10pt;&quot;&gt;&lt;br /&gt;&lt;/p&gt;
&lt;p style=&quot; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;&quot;&gt;&lt;span style=&quot; font-size:10pt;&quot;&gt;Ok, lets start the configuration by clicking on the 'Next'/'Continue' button below.&lt;/span&gt;&lt;/p&gt;&lt;/body&gt;&lt;/html&gt;</string>
</property>

View File

@ -26,13 +26,15 @@
<string>&lt;!DOCTYPE HTML PUBLIC &quot;-//W3C//DTD HTML 4.0//EN&quot; &quot;http://www.w3.org/TR/REC-html40/strict.dtd&quot;&gt;
&lt;html&gt;&lt;head&gt;&lt;meta name=&quot;qrichtext&quot; content=&quot;1&quot; /&gt;&lt;style type=&quot;text/css&quot;&gt;
p, li { white-space: pre-wrap; }
&lt;/style&gt;&lt;/head&gt;&lt;body style=&quot; font-family:'MS Shell Dlg 2'; font-size:8.25pt; font-weight:400; font-style:normal;&quot;&gt;
&lt;/style&gt;&lt;/head&gt;&lt;body style=&quot; font-family:'MS Shell Dlg 2'; font-size:8pt; font-weight:400; font-style:normal;&quot;&gt;
&lt;p style=&quot; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;&quot;&gt;&lt;span style=&quot; font-size:12pt; font-weight:600;&quot;&gt;OpenPilot configuration summary&lt;/span&gt;&lt;/p&gt;
&lt;p style=&quot;-qt-paragraph-type:empty; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px; font-size:12pt; font-weight:600;&quot;&gt;&lt;/p&gt;
&lt;p style=&quot; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;&quot;&gt;&lt;span style=&quot; font-size:10pt;&quot;&gt;The first part of this wizard is now complete. The information required to create a basic OpenPilot controller configuration has been collected and a configuration can be created and saved.&lt;/span&gt;&lt;/p&gt;
&lt;p style=&quot;-qt-paragraph-type:empty; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px; font-size:12pt; font-weight:600;&quot;&gt;&lt;br /&gt;&lt;/p&gt;
&lt;p style=&quot; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;&quot;&gt;&lt;span style=&quot; font-size:10pt;&quot;&gt;The first part of this wizard is now complete. All information required to create a basic OpenPilot controller configuration for a specific vehichle has been collected.&lt;/span&gt;&lt;/p&gt;
&lt;p style=&quot; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;&quot;&gt;&lt;span style=&quot; font-size:10pt;&quot;&gt;Below is a summary of the configuration and a button that links to a diagram illustrating how to connect required hardware and the OpenPilotController with the current configuration.&lt;/span&gt;&lt;/p&gt;
&lt;p style=&quot;-qt-paragraph-type:empty; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px; font-size:10pt;&quot;&gt;&lt;/p&gt;
&lt;p style=&quot; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;&quot;&gt;&lt;span style=&quot; font-size:10pt;&quot;&gt;To complete the wizard and write the configuration directly to the OpenPilot controller please continue to the next and last step of this wizard.&lt;/span&gt;&lt;/p&gt;&lt;/body&gt;&lt;/html&gt;</string>
&lt;p style=&quot;-qt-paragraph-type:empty; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px; font-size:10pt;&quot;&gt;&lt;br /&gt;&lt;/p&gt;
&lt;p style=&quot; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;&quot;&gt;&lt;span style=&quot; font-size:10pt;&quot;&gt;To continue the wizard and go through some basic configuration steps please continue to the next step of this wizard.&lt;/span&gt;&lt;/p&gt;
&lt;p style=&quot;-qt-paragraph-type:empty; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;&quot;&gt;&lt;br /&gt;&lt;/p&gt;
&lt;p style=&quot; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;&quot;&gt;&lt;span style=&quot; font-size:10pt;&quot;&gt;The following steps requires that your OpenPilot controller is set up according to the diagram and that the vehicle is &lt;/span&gt;&lt;span style=&quot; font-size:10pt; font-weight:600;&quot;&gt;powered by a battery&lt;/span&gt;&lt;span style=&quot; font-size:10pt;&quot;&gt; as well as &lt;/span&gt;&lt;span style=&quot; font-size:10pt; font-weight:600;&quot;&gt;connected to the computer&lt;/span&gt;&lt;span style=&quot; font-size:10pt;&quot;&gt;.&lt;/span&gt;&lt;/p&gt;&lt;/body&gt;&lt;/html&gt;</string>
</property>
<property name="alignment">
<set>Qt::AlignLeading|Qt::AlignLeft|Qt::AlignTop</set>
@ -45,7 +47,7 @@ p, li { white-space: pre-wrap; }
<property name="geometry">
<rect>
<x>460</x>
<y>250</y>
<y>260</y>
<width>100</width>
<height>100</height>
</rect>
@ -75,9 +77,9 @@ Illustration</string>
<property name="geometry">
<rect>
<x>40</x>
<y>230</y>
<y>249</y>
<width>400</width>
<height>140</height>
<height>121</height>
</rect>
</property>
<property name="font">

File diff suppressed because one or more lines are too long

Before

Width:  |  Height:  |  Size: 676 KiB

After

Width:  |  Height:  |  Size: 360 KiB

File diff suppressed because one or more lines are too long

After

Width:  |  Height:  |  Size: 408 KiB

View File

@ -39,6 +39,7 @@
#include "pages/levellingpage.h"
#include "pages/summarypage.h"
#include "pages/flashpage.h"
#include "pages/outputcalibrationpage.h"
#include "pages/notyetimplementedpage.h"
#include "extensionsystem/pluginmanager.h"
#include "vehicleconfigurationhelper.h"
@ -91,11 +92,13 @@ int SetupWizard::nextId() const
case PAGE_INPUT:
return PAGE_VEHICLES;
case PAGE_OUTPUT:
return PAGE_LEVELLING;
case PAGE_LEVELLING:
return PAGE_SUMMARY;
case PAGE_SUMMARY:
case PAGE_LEVELLING:
return PAGE_CALIBRATION;
case PAGE_CALIBRATION:
return PAGE_FLASH;
case PAGE_SUMMARY:
return PAGE_LEVELLING;
case PAGE_FLASH:
return PAGE_END;
case PAGE_NOTYETIMPLEMENTED:
@ -222,15 +225,6 @@ QString SetupWizard::getSummaryText()
summary.append(tr("Unknown"));
}
summary.append("<br>");
summary.append("<b>").append(tr("Accel & Gyro bias calibrated: ")).append("</b>");
if (isLevellingPerformed()) {
summary.append(tr("Yes"));
}
else {
summary.append(tr("No"));
}
return summary;
}
@ -246,6 +240,7 @@ void SetupWizard::createPages()
setPage(PAGE_INPUT, new InputPage(this));
setPage(PAGE_OUTPUT, new OutputPage(this));
setPage(PAGE_LEVELLING, new LevellingPage(this));
setPage(PAGE_CALIBRATION, new OutputCalibrationPage(this));
setPage(PAGE_SUMMARY, new SummaryPage(this));
setPage(PAGE_FLASH, new FlashPage(this));
setPage(PAGE_NOTYETIMPLEMENTED, new NotYetImplementedPage(this));

View File

@ -78,7 +78,7 @@ public:
private:
enum {PAGE_START, PAGE_CONTROLLER, PAGE_VEHICLES, PAGE_MULTI, PAGE_FIXEDWING,
PAGE_HELI, PAGE_SURFACE, PAGE_INPUT, PAGE_OUTPUT, PAGE_LEVELLING,
PAGE_HELI, PAGE_SURFACE, PAGE_INPUT, PAGE_OUTPUT, PAGE_LEVELLING, PAGE_CALIBRATION,
PAGE_FLASH, PAGE_SUMMARY, PAGE_NOTYETIMPLEMENTED, PAGE_END};
void createPages();

View File

@ -29,7 +29,8 @@ HEADERS += setupwizardplugin.h \
vehicleconfigurationsource.h \
vehicleconfigurationhelper.h \
connectiondiagram.h \
pages/outputcalibrationpage.h
pages/outputcalibrationpage.h \
outputcalibrationutil.h
SOURCES += setupwizardplugin.cpp \
setupwizard.cpp \
@ -52,7 +53,8 @@ SOURCES += setupwizardplugin.cpp \
vehicleconfigurationsource.cpp \
vehicleconfigurationhelper.cpp \
connectiondiagram.cpp \
pages/outputcalibrationpage.cpp
pages/outputcalibrationpage.cpp \
outputcalibrationutil.cpp
OTHER_FILES += SetupWizard.pluginspec

View File

@ -29,5 +29,6 @@
<file>resources/bttn-calculate-up.png</file>
<file>resources/bttn-turbo-down.png</file>
<file>resources/bttn-turbo-up.png</file>
<file>resources/multirotor-shapes.svg</file>
</qresource>
</RCC>