Merge branch 'thread/OP-39' of ssh://git.openpilot.org/OpenPilot into next
@ -6,13 +6,12 @@ SUBDIRS = openpilotgcs/translations
|
||||
DATACOLLECTIONS = dials models pfd sounds diagrams mapicons stylesheets default_configurations
|
||||
|
||||
equals(copydata, 1) {
|
||||
for(dir, DATACOLLECTIONS) {
|
||||
exists($$GCS_SOURCE_TREE/share/openpilotgcs/$$dir) {
|
||||
macx:data_copy.commands += $(COPY_DIR) $$targetPath(\"$$GCS_SOURCE_TREE/share/openpilotgcs/$$dir\") $$targetPath(\"$$GCS_DATA_PATH/\") $$addNewline()
|
||||
!macx:data_copy.commands += $(MKDIR) $$targetPath(\"$$GCS_DATA_PATH/$$dir\") $$addNewline()
|
||||
!macx:data_copy.commands += $(COPY_DIR) $$targetPath(\"$$GCS_SOURCE_TREE/share/openpilotgcs/$$dir\") $$targetPath(\"$$GCS_DATA_PATH/\") $$addNewline()
|
||||
}
|
||||
}
|
||||
for(dir, DATACOLLECTIONS) {
|
||||
exists($$GCS_SOURCE_TREE/share/openpilotgcs/$$dir) {
|
||||
macx:data_copy.commands += $(COPY_DIR) $$targetPath(\"$$GCS_SOURCE_TREE/share/openpilotgcs/$$dir\") $$targetPath(\"$$GCS_DATA_PATH/\") $$addNewline()
|
||||
!macx:data_copy.commands += $(COPY_DIR) $$targetPath(\"$$GCS_SOURCE_TREE/share/openpilotgcs/$$dir\") $$targetPath(\"$$GCS_DATA_PATH/$$dir\") $$addNewline()
|
||||
}
|
||||
}
|
||||
|
||||
data_copy.target = FORCE
|
||||
QMAKE_EXTRA_TARGETS += data_copy
|
||||
|
@ -3,25 +3,25 @@
|
||||
*
|
||||
* @file lks94projection.h
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012.
|
||||
* @brief
|
||||
* @brief
|
||||
* @see The GNU Public License (GPL) Version 3
|
||||
* @defgroup OPMapWidget
|
||||
* @{
|
||||
*
|
||||
*
|
||||
*****************************************************************************/
|
||||
/*
|
||||
* 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
|
||||
/*
|
||||
* 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
|
||||
*
|
||||
* 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.,
|
||||
*
|
||||
* 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 LKS94PROJECTION_H
|
||||
@ -30,7 +30,7 @@
|
||||
#include "cmath"
|
||||
#include "../pureprojection.h"
|
||||
|
||||
|
||||
|
||||
namespace projections {
|
||||
class LKS94Projection:public internals::PureProjection
|
||||
{
|
||||
|
@ -52,6 +52,7 @@ public:
|
||||
void insertCornerWidget(int index, QWidget *widget);
|
||||
int cornerWidgetCount() { return m_cornerWidgetCount; }
|
||||
QWidget * currentWidget(){return m_stackWidget->currentWidget();}
|
||||
QWidget * getWidget(int index) {return m_stackWidget->widget(index);}
|
||||
|
||||
signals:
|
||||
void currentAboutToShow(int index,bool * proceed);
|
||||
|
@ -1,4 +1,4 @@
|
||||
<plugin name="Config" version="0.0.1" compatVersion="1.0.0">
|
||||
<plugin name="Config" version="1.0.0" compatVersion="1.0.0">
|
||||
<vendor>The OpenPilot Project</vendor>
|
||||
<copyright>(C) 2010 OpenPilot Project</copyright>
|
||||
<license>GNU Public License (GPL) Version 3</license>
|
||||
|
@ -25,14 +25,18 @@
|
||||
* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA
|
||||
*/
|
||||
#include "configgadgetfactory.h"
|
||||
#include "configgadgetwidget.h"
|
||||
#include "configgadget.h"
|
||||
#include "configgadgetconfiguration.h"
|
||||
#include "configgadgetoptionspage.h"
|
||||
#include <coreplugin/iuavgadget.h>
|
||||
#include <coreplugin/coreconstants.h>
|
||||
#include <coreplugin/actionmanager/actionmanager.h>
|
||||
#include <coreplugin/icore.h>
|
||||
#include <coreplugin/modemanager.h>
|
||||
|
||||
ConfigGadgetFactory::ConfigGadgetFactory(QObject *parent) :
|
||||
IUAVGadgetFactory(QString("ConfigGadget"), tr("Config Gadget"), parent)
|
||||
IUAVGadgetFactory(QString("ConfigGadget"), tr("Config Gadget"), parent),
|
||||
gadgetWidget(0)
|
||||
{
|
||||
}
|
||||
|
||||
@ -42,7 +46,26 @@ ConfigGadgetFactory::~ConfigGadgetFactory()
|
||||
|
||||
Core::IUAVGadget* ConfigGadgetFactory::createGadget(QWidget *parent)
|
||||
{
|
||||
ConfigGadgetWidget* gadgetWidget = new ConfigGadgetWidget(parent);
|
||||
gadgetWidget = new ConfigGadgetWidget(parent);
|
||||
|
||||
// Add Menu entry
|
||||
Core::ActionManager* am = Core::ICore::instance()->actionManager();
|
||||
Core::ActionContainer* ac = am->actionContainer(Core::Constants::M_TOOLS);
|
||||
|
||||
Core::Command* cmd = am->registerAction(new QAction(this),
|
||||
"ConfigPlugin.ShowInputWizard",
|
||||
QList<int>() <<
|
||||
Core::Constants::C_GLOBAL_ID);
|
||||
cmd->setDefaultKeySequence(QKeySequence("Ctrl+R"));
|
||||
cmd->action()->setText(tr("Radio Setup Wizard"));
|
||||
|
||||
Core::ModeManager::instance()->addAction(cmd, 1);
|
||||
|
||||
ac->appendGroup("Wizard");
|
||||
ac->addAction(cmd, "Wizard");
|
||||
|
||||
connect(cmd->action(), SIGNAL(triggered(bool)), this, SLOT(startInputWizard()));
|
||||
|
||||
return new ConfigGadget(QString("ConfigGadget"), gadgetWidget, parent);
|
||||
}
|
||||
|
||||
@ -55,3 +78,12 @@ IOptionsPage *ConfigGadgetFactory::createOptionsPage(IUAVGadgetConfiguration *co
|
||||
{
|
||||
return new ConfigGadgetOptionsPage(qobject_cast<ConfigGadgetConfiguration*>(config));
|
||||
}
|
||||
|
||||
void ConfigGadgetFactory::startInputWizard()
|
||||
{
|
||||
if(gadgetWidget)
|
||||
{
|
||||
Core::ModeManager::instance()->activateModeByWorkspaceName("Configuration");
|
||||
gadgetWidget->startInputWizard();
|
||||
}
|
||||
}
|
||||
|
@ -28,6 +28,9 @@
|
||||
#define CONFIGGADGETFACTORY_H
|
||||
|
||||
#include <coreplugin/iuavgadgetfactory.h>
|
||||
#include "configgadgetwidget.h"
|
||||
#include "config_global.h"
|
||||
|
||||
|
||||
namespace Core {
|
||||
class IUAVGadget;
|
||||
@ -36,7 +39,7 @@ class IUAVGadgetFactory;
|
||||
|
||||
using namespace Core;
|
||||
|
||||
class ConfigGadgetFactory: public Core::IUAVGadgetFactory
|
||||
class CONFIG_EXPORT ConfigGadgetFactory: public Core::IUAVGadgetFactory
|
||||
{
|
||||
Q_OBJECT
|
||||
public:
|
||||
@ -47,6 +50,12 @@ public:
|
||||
IUAVGadget *createGadget(QWidget *parent);
|
||||
IUAVGadgetConfiguration *createConfiguration(QSettings* qSettings);
|
||||
IOptionsPage *createOptionsPage(IUAVGadgetConfiguration *config);
|
||||
|
||||
public slots:
|
||||
void startInputWizard();
|
||||
|
||||
private:
|
||||
ConfigGadgetWidget* gadgetWidget;
|
||||
};
|
||||
|
||||
#endif // CONFIGGADGETFACTORY_H
|
||||
|
@ -131,6 +131,14 @@ ConfigGadgetWidget::~ConfigGadgetWidget()
|
||||
// TODO: properly delete all the tabs in ftw before exiting
|
||||
}
|
||||
|
||||
void ConfigGadgetWidget::startInputWizard()
|
||||
{
|
||||
ftw->setCurrentIndex(ConfigGadgetWidget::input);
|
||||
ConfigInputWidget* inputWidget = dynamic_cast<ConfigInputWidget*>(ftw->getWidget(ConfigGadgetWidget::input));
|
||||
Q_ASSERT(inputWidget);
|
||||
inputWidget->startInputWizard();
|
||||
}
|
||||
|
||||
void ConfigGadgetWidget::resizeEvent(QResizeEvent *event)
|
||||
{
|
||||
|
||||
|
@ -49,6 +49,7 @@ public:
|
||||
ConfigGadgetWidget(QWidget *parent = 0);
|
||||
~ConfigGadgetWidget();
|
||||
enum widgetTabs {hardware=0, aircraft, input, output, sensors, stabilization, camerastabilization, txpid, pipxtreme, autotune};
|
||||
void startInputWizard();
|
||||
|
||||
public slots:
|
||||
void onAutopilotConnect();
|
||||
|
2707
ground/openpilotgcs/src/plugins/config/configinputwidget.cpp
Executable file → Normal file
@ -1,1349 +1,1358 @@
|
||||
/**
|
||||
******************************************************************************
|
||||
*
|
||||
* @file configinputwidget.cpp
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
|
||||
* @addtogroup GCSPlugins GCS Plugins
|
||||
* @{
|
||||
* @addtogroup ConfigPlugin Config Plugin
|
||||
* @{
|
||||
* @brief Servo input/output configuration panel for the config gadget
|
||||
*****************************************************************************/
|
||||
/*
|
||||
* 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 "configinputwidget.h"
|
||||
|
||||
#include "uavtalk/telemetrymanager.h"
|
||||
|
||||
#include <QDebug>
|
||||
#include <QStringList>
|
||||
#include <QtGui/QWidget>
|
||||
#include <QtGui/QTextEdit>
|
||||
#include <QtGui/QVBoxLayout>
|
||||
#include <QtGui/QPushButton>
|
||||
#include <QDesktopServices>
|
||||
#include <QUrl>
|
||||
#include <QMessageBox>
|
||||
#include <utils/stylehelper.h>
|
||||
#include <QMessageBox>
|
||||
|
||||
#include <extensionsystem/pluginmanager.h>
|
||||
#include <coreplugin/generalsettings.h>
|
||||
|
||||
#define ACCESS_MIN_MOVE -3
|
||||
#define ACCESS_MAX_MOVE 3
|
||||
#define STICK_MIN_MOVE -8
|
||||
#define STICK_MAX_MOVE 8
|
||||
|
||||
ConfigInputWidget::ConfigInputWidget(QWidget *parent) : ConfigTaskWidget(parent),wizardStep(wizardNone),transmitterType(heli),loop(NULL),skipflag(false)
|
||||
{
|
||||
manualCommandObj = ManualControlCommand::GetInstance(getObjectManager());
|
||||
manualSettingsObj = ManualControlSettings::GetInstance(getObjectManager());
|
||||
flightStatusObj = FlightStatus::GetInstance(getObjectManager());
|
||||
receiverActivityObj=ReceiverActivity::GetInstance(getObjectManager());
|
||||
m_config = new Ui_InputWidget();
|
||||
m_config->setupUi(this);
|
||||
|
||||
addApplySaveButtons(m_config->saveRCInputToRAM,m_config->saveRCInputToSD);
|
||||
|
||||
ExtensionSystem::PluginManager *pm=ExtensionSystem::PluginManager::instance();
|
||||
Core::Internal::GeneralSettings * settings=pm->getObject<Core::Internal::GeneralSettings>();
|
||||
if(!settings->useExpertMode())
|
||||
m_config->saveRCInputToRAM->setVisible(false);
|
||||
|
||||
addApplySaveButtons(m_config->saveRCInputToRAM,m_config->saveRCInputToSD);
|
||||
|
||||
//Generate the rows of buttons in the input channel form GUI
|
||||
unsigned int index=0;
|
||||
foreach (QString name, manualSettingsObj->getField("ChannelNumber")->getElementNames())
|
||||
{
|
||||
Q_ASSERT(index < ManualControlSettings::CHANNELGROUPS_NUMELEM);
|
||||
inputChannelForm * inpForm=new inputChannelForm(this,index==0);
|
||||
m_config->channelSettings->layout()->addWidget(inpForm); //Add the row to the UI
|
||||
inpForm->setName(name);
|
||||
addUAVObjectToWidgetRelation("ManualControlSettings","ChannelGroups",inpForm->ui->channelGroup,index);
|
||||
addUAVObjectToWidgetRelation("ManualControlSettings","ChannelNumber",inpForm->ui->channelNumber,index);
|
||||
addUAVObjectToWidgetRelation("ManualControlSettings","ChannelMin",inpForm->ui->channelMin,index);
|
||||
addUAVObjectToWidgetRelation("ManualControlSettings","ChannelNeutral",inpForm->ui->channelNeutral,index);
|
||||
addUAVObjectToWidgetRelation("ManualControlSettings","ChannelMax",inpForm->ui->channelMax,index);
|
||||
++index;
|
||||
}
|
||||
|
||||
addUAVObjectToWidgetRelation("ManualControlSettings", "Deadband", m_config->deadband, 0, 0.01f);
|
||||
|
||||
connect(m_config->configurationWizard,SIGNAL(clicked()),this,SLOT(goToWizard()));
|
||||
connect(m_config->stackedWidget,SIGNAL(currentChanged(int)),this,SLOT(disableWizardButton(int)));
|
||||
connect(m_config->runCalibration,SIGNAL(toggled(bool)),this, SLOT(simpleCalibration(bool)));
|
||||
|
||||
connect(m_config->wzNext,SIGNAL(clicked()),this,SLOT(wzNext()));
|
||||
connect(m_config->wzCancel,SIGNAL(clicked()),this,SLOT(wzCancel()));
|
||||
connect(m_config->wzBack,SIGNAL(clicked()),this,SLOT(wzBack()));
|
||||
|
||||
m_config->stackedWidget->setCurrentIndex(0);
|
||||
addUAVObjectToWidgetRelation("ManualControlSettings","FlightModePosition",m_config->fmsModePos1,0,1,true);
|
||||
addUAVObjectToWidgetRelation("ManualControlSettings","FlightModePosition",m_config->fmsModePos2,1,1,true);
|
||||
addUAVObjectToWidgetRelation("ManualControlSettings","FlightModePosition",m_config->fmsModePos3,2,1,true);
|
||||
addUAVObjectToWidgetRelation("ManualControlSettings","FlightModePosition",m_config->fmsModePos4,3,1,true);
|
||||
addUAVObjectToWidgetRelation("ManualControlSettings","FlightModePosition",m_config->fmsModePos5,4,1,true);
|
||||
addUAVObjectToWidgetRelation("ManualControlSettings","FlightModePosition",m_config->fmsModePos6,5,1,true);
|
||||
addUAVObjectToWidgetRelation("ManualControlSettings","FlightModeNumber",m_config->fmsPosNum);
|
||||
|
||||
addUAVObjectToWidgetRelation("ManualControlSettings","Stabilization1Settings",m_config->fmsSsPos1Roll,"Roll");
|
||||
addUAVObjectToWidgetRelation("ManualControlSettings","Stabilization2Settings",m_config->fmsSsPos2Roll,"Roll");
|
||||
addUAVObjectToWidgetRelation("ManualControlSettings","Stabilization3Settings",m_config->fmsSsPos3Roll,"Roll");
|
||||
addUAVObjectToWidgetRelation("ManualControlSettings","Stabilization1Settings",m_config->fmsSsPos1Pitch,"Pitch");
|
||||
addUAVObjectToWidgetRelation("ManualControlSettings","Stabilization2Settings",m_config->fmsSsPos2Pitch,"Pitch");
|
||||
addUAVObjectToWidgetRelation("ManualControlSettings","Stabilization3Settings",m_config->fmsSsPos3Pitch,"Pitch");
|
||||
addUAVObjectToWidgetRelation("ManualControlSettings","Stabilization1Settings",m_config->fmsSsPos1Yaw,"Yaw");
|
||||
addUAVObjectToWidgetRelation("ManualControlSettings","Stabilization2Settings",m_config->fmsSsPos2Yaw,"Yaw");
|
||||
addUAVObjectToWidgetRelation("ManualControlSettings","Stabilization3Settings",m_config->fmsSsPos3Yaw,"Yaw");
|
||||
|
||||
addUAVObjectToWidgetRelation("ManualControlSettings","Arming",m_config->armControl);
|
||||
addUAVObjectToWidgetRelation("ManualControlSettings","ArmedTimeout",m_config->armTimeout,0,1000);
|
||||
connect( ManualControlCommand::GetInstance(getObjectManager()),SIGNAL(objectUpdated(UAVObject*)),this,SLOT(moveFMSlider()));
|
||||
connect( ManualControlSettings::GetInstance(getObjectManager()),SIGNAL(objectUpdated(UAVObject*)),this,SLOT(updatePositionSlider()));
|
||||
enableControls(false);
|
||||
|
||||
populateWidgets();
|
||||
refreshWidgetsValues();
|
||||
// Connect the help button
|
||||
connect(m_config->inputHelp, SIGNAL(clicked()), this, SLOT(openHelp()));
|
||||
|
||||
m_config->graphicsView->setScene(new QGraphicsScene(this));
|
||||
m_config->graphicsView->setViewportUpdateMode(QGraphicsView::FullViewportUpdate);
|
||||
m_renderer = new QSvgRenderer();
|
||||
QGraphicsScene *l_scene = m_config->graphicsView->scene();
|
||||
m_config->graphicsView->setBackgroundBrush(QBrush(Utils::StyleHelper::baseColor()));
|
||||
if (QFile::exists(":/configgadget/images/TX2.svg") && m_renderer->load(QString(":/configgadget/images/TX2.svg")) && m_renderer->isValid())
|
||||
{
|
||||
l_scene->clear(); // Deletes all items contained in the scene as well.
|
||||
|
||||
m_txBackground = new QGraphicsSvgItem();
|
||||
// All other items will be clipped to the shape of the background
|
||||
m_txBackground->setFlags(QGraphicsItem::ItemClipsChildrenToShape|
|
||||
QGraphicsItem::ItemClipsToShape);
|
||||
m_txBackground->setSharedRenderer(m_renderer);
|
||||
m_txBackground->setElementId("background");
|
||||
l_scene->addItem(m_txBackground);
|
||||
|
||||
m_txMainBody = new QGraphicsSvgItem();
|
||||
m_txMainBody->setParentItem(m_txBackground);
|
||||
m_txMainBody->setSharedRenderer(m_renderer);
|
||||
m_txMainBody->setElementId("body");
|
||||
l_scene->addItem(m_txMainBody);
|
||||
|
||||
m_txLeftStick = new QGraphicsSvgItem();
|
||||
m_txLeftStick->setParentItem(m_txBackground);
|
||||
m_txLeftStick->setSharedRenderer(m_renderer);
|
||||
m_txLeftStick->setElementId("ljoy");
|
||||
|
||||
m_txRightStick = new QGraphicsSvgItem();
|
||||
m_txRightStick->setParentItem(m_txBackground);
|
||||
m_txRightStick->setSharedRenderer(m_renderer);
|
||||
m_txRightStick->setElementId("rjoy");
|
||||
|
||||
m_txAccess0 = new QGraphicsSvgItem();
|
||||
m_txAccess0->setParentItem(m_txBackground);
|
||||
m_txAccess0->setSharedRenderer(m_renderer);
|
||||
m_txAccess0->setElementId("access0");
|
||||
|
||||
m_txAccess1 = new QGraphicsSvgItem();
|
||||
m_txAccess1->setParentItem(m_txBackground);
|
||||
m_txAccess1->setSharedRenderer(m_renderer);
|
||||
m_txAccess1->setElementId("access1");
|
||||
|
||||
m_txAccess2 = new QGraphicsSvgItem();
|
||||
m_txAccess2->setParentItem(m_txBackground);
|
||||
m_txAccess2->setSharedRenderer(m_renderer);
|
||||
m_txAccess2->setElementId("access2");
|
||||
|
||||
m_txFlightMode = new QGraphicsSvgItem();
|
||||
m_txFlightMode->setParentItem(m_txBackground);
|
||||
m_txFlightMode->setSharedRenderer(m_renderer);
|
||||
m_txFlightMode->setElementId("flightModeCenter");
|
||||
m_txFlightMode->setZValue(-10);
|
||||
|
||||
m_txArrows = new QGraphicsSvgItem();
|
||||
m_txArrows->setParentItem(m_txBackground);
|
||||
m_txArrows->setSharedRenderer(m_renderer);
|
||||
m_txArrows->setElementId("arrows");
|
||||
m_txArrows->setVisible(false);
|
||||
|
||||
QRectF orig=m_renderer->boundsOnElement("ljoy");
|
||||
QMatrix Matrix = m_renderer->matrixForElement("ljoy");
|
||||
orig=Matrix.mapRect(orig);
|
||||
m_txLeftStickOrig.translate(orig.x(),orig.y());
|
||||
m_txLeftStick->setTransform(m_txLeftStickOrig,false);
|
||||
|
||||
orig=m_renderer->boundsOnElement("arrows");
|
||||
Matrix = m_renderer->matrixForElement("arrows");
|
||||
orig=Matrix.mapRect(orig);
|
||||
m_txArrowsOrig.translate(orig.x(),orig.y());
|
||||
m_txArrows->setTransform(m_txArrowsOrig,false);
|
||||
|
||||
orig=m_renderer->boundsOnElement("body");
|
||||
Matrix = m_renderer->matrixForElement("body");
|
||||
orig=Matrix.mapRect(orig);
|
||||
m_txMainBodyOrig.translate(orig.x(),orig.y());
|
||||
m_txMainBody->setTransform(m_txMainBodyOrig,false);
|
||||
|
||||
orig=m_renderer->boundsOnElement("flightModeCenter");
|
||||
Matrix = m_renderer->matrixForElement("flightModeCenter");
|
||||
orig=Matrix.mapRect(orig);
|
||||
m_txFlightModeCOrig.translate(orig.x(),orig.y());
|
||||
m_txFlightMode->setTransform(m_txFlightModeCOrig,false);
|
||||
|
||||
orig=m_renderer->boundsOnElement("flightModeLeft");
|
||||
Matrix = m_renderer->matrixForElement("flightModeLeft");
|
||||
orig=Matrix.mapRect(orig);
|
||||
m_txFlightModeLOrig.translate(orig.x(),orig.y());
|
||||
orig=m_renderer->boundsOnElement("flightModeRight");
|
||||
Matrix = m_renderer->matrixForElement("flightModeRight");
|
||||
orig=Matrix.mapRect(orig);
|
||||
m_txFlightModeROrig.translate(orig.x(),orig.y());
|
||||
|
||||
orig=m_renderer->boundsOnElement("rjoy");
|
||||
Matrix = m_renderer->matrixForElement("rjoy");
|
||||
orig=Matrix.mapRect(orig);
|
||||
m_txRightStickOrig.translate(orig.x(),orig.y());
|
||||
m_txRightStick->setTransform(m_txRightStickOrig,false);
|
||||
|
||||
orig=m_renderer->boundsOnElement("access0");
|
||||
Matrix = m_renderer->matrixForElement("access0");
|
||||
orig=Matrix.mapRect(orig);
|
||||
m_txAccess0Orig.translate(orig.x(),orig.y());
|
||||
m_txAccess0->setTransform(m_txAccess0Orig,false);
|
||||
|
||||
orig=m_renderer->boundsOnElement("access1");
|
||||
Matrix = m_renderer->matrixForElement("access1");
|
||||
orig=Matrix.mapRect(orig);
|
||||
m_txAccess1Orig.translate(orig.x(),orig.y());
|
||||
m_txAccess1->setTransform(m_txAccess1Orig,false);
|
||||
|
||||
orig=m_renderer->boundsOnElement("access2");
|
||||
Matrix = m_renderer->matrixForElement("access2");
|
||||
orig=Matrix.mapRect(orig);
|
||||
m_txAccess2Orig.translate(orig.x(),orig.y());
|
||||
m_txAccess2->setTransform(m_txAccess2Orig,true);
|
||||
}
|
||||
m_config->graphicsView->fitInView(m_txMainBody, Qt::KeepAspectRatio );
|
||||
animate=new QTimer(this);
|
||||
connect(animate,SIGNAL(timeout()),this,SLOT(moveTxControls()));
|
||||
|
||||
heliChannelOrder << ManualControlSettings::CHANNELGROUPS_COLLECTIVE <<
|
||||
ManualControlSettings::CHANNELGROUPS_THROTTLE <<
|
||||
ManualControlSettings::CHANNELGROUPS_ROLL <<
|
||||
ManualControlSettings::CHANNELGROUPS_PITCH <<
|
||||
ManualControlSettings::CHANNELGROUPS_YAW <<
|
||||
ManualControlSettings::CHANNELGROUPS_FLIGHTMODE <<
|
||||
ManualControlSettings::CHANNELGROUPS_ACCESSORY0 <<
|
||||
ManualControlSettings::CHANNELGROUPS_ACCESSORY1 <<
|
||||
ManualControlSettings::CHANNELGROUPS_ACCESSORY2;
|
||||
|
||||
acroChannelOrder << ManualControlSettings::CHANNELGROUPS_THROTTLE <<
|
||||
ManualControlSettings::CHANNELGROUPS_ROLL <<
|
||||
ManualControlSettings::CHANNELGROUPS_PITCH <<
|
||||
ManualControlSettings::CHANNELGROUPS_YAW <<
|
||||
ManualControlSettings::CHANNELGROUPS_FLIGHTMODE <<
|
||||
ManualControlSettings::CHANNELGROUPS_ACCESSORY0 <<
|
||||
ManualControlSettings::CHANNELGROUPS_ACCESSORY1 <<
|
||||
ManualControlSettings::CHANNELGROUPS_ACCESSORY2;
|
||||
}
|
||||
void ConfigInputWidget::resetTxControls()
|
||||
{
|
||||
|
||||
m_txLeftStick->setTransform(m_txLeftStickOrig,false);
|
||||
m_txRightStick->setTransform(m_txRightStickOrig,false);
|
||||
m_txAccess0->setTransform(m_txAccess0Orig,false);
|
||||
m_txAccess1->setTransform(m_txAccess1Orig,false);
|
||||
m_txAccess2->setTransform(m_txAccess2Orig,false);
|
||||
m_txFlightMode->setElementId("flightModeCenter");
|
||||
m_txFlightMode->setTransform(m_txFlightModeCOrig,false);
|
||||
m_txArrows->setVisible(false);
|
||||
}
|
||||
|
||||
ConfigInputWidget::~ConfigInputWidget()
|
||||
{
|
||||
|
||||
}
|
||||
|
||||
void ConfigInputWidget::resizeEvent(QResizeEvent *event)
|
||||
{
|
||||
QWidget::resizeEvent(event);
|
||||
m_config->graphicsView->fitInView(m_txBackground, Qt::KeepAspectRatio );
|
||||
}
|
||||
|
||||
void ConfigInputWidget::openHelp()
|
||||
{
|
||||
|
||||
QDesktopServices::openUrl( QUrl("http://wiki.openpilot.org/x/04Cf", QUrl::StrictMode) );
|
||||
}
|
||||
void ConfigInputWidget::goToWizard()
|
||||
{
|
||||
QMessageBox msgBox;
|
||||
msgBox.setText(tr("Arming Settings are now set to Always Disarmed for your safety."));
|
||||
msgBox.setDetailedText(tr("You will have to reconfigure the arming settings manually when the wizard is finished."));
|
||||
msgBox.setStandardButtons(QMessageBox::Ok);
|
||||
msgBox.setDefaultButton(QMessageBox::Ok);
|
||||
msgBox.exec();
|
||||
wizardSetUpStep(wizardWelcome);
|
||||
m_config->graphicsView->fitInView(m_txBackground, Qt::KeepAspectRatio );
|
||||
}
|
||||
|
||||
void ConfigInputWidget::disableWizardButton(int value)
|
||||
{
|
||||
if(value!=0)
|
||||
m_config->configurationWizard->setVisible(false);
|
||||
else
|
||||
m_config->configurationWizard->setVisible(true);
|
||||
}
|
||||
|
||||
void ConfigInputWidget::wzCancel()
|
||||
{
|
||||
dimOtherControls(false);
|
||||
manualCommandObj->setMetadata(manualCommandObj->getDefaultMetadata());
|
||||
m_config->stackedWidget->setCurrentIndex(0);
|
||||
|
||||
if(wizardStep != wizardNone)
|
||||
wizardTearDownStep(wizardStep);
|
||||
wizardStep=wizardNone;
|
||||
m_config->stackedWidget->setCurrentIndex(0);
|
||||
|
||||
// Load settings back from beginning of wizard
|
||||
manualSettingsObj->setData(previousManualSettingsData);
|
||||
}
|
||||
|
||||
void ConfigInputWidget::wzNext()
|
||||
{
|
||||
// In identify sticks mode the next button can indicate
|
||||
// channel advance
|
||||
if(wizardStep != wizardNone &&
|
||||
wizardStep != wizardIdentifySticks)
|
||||
wizardTearDownStep(wizardStep);
|
||||
|
||||
// State transitions for next button
|
||||
switch(wizardStep) {
|
||||
case wizardWelcome:
|
||||
wizardSetUpStep(wizardChooseMode);
|
||||
break;
|
||||
case wizardChooseMode:
|
||||
wizardSetUpStep(wizardChooseType);
|
||||
break;
|
||||
case wizardChooseType:
|
||||
wizardSetUpStep(wizardIdentifySticks);
|
||||
break;
|
||||
case wizardIdentifySticks:
|
||||
nextChannel();
|
||||
if(currentChannelNum==-1) { // Gone through all channels
|
||||
wizardTearDownStep(wizardIdentifySticks);
|
||||
wizardSetUpStep(wizardIdentifyCenter);
|
||||
}
|
||||
break;
|
||||
case wizardIdentifyCenter:
|
||||
wizardSetUpStep(wizardIdentifyLimits);
|
||||
break;
|
||||
case wizardIdentifyLimits:
|
||||
wizardSetUpStep(wizardIdentifyInverted);
|
||||
break;
|
||||
case wizardIdentifyInverted:
|
||||
wizardSetUpStep(wizardFinish);
|
||||
break;
|
||||
case wizardFinish:
|
||||
wizardStep=wizardNone;
|
||||
m_config->stackedWidget->setCurrentIndex(0);
|
||||
break;
|
||||
default:
|
||||
Q_ASSERT(0);
|
||||
}
|
||||
}
|
||||
|
||||
void ConfigInputWidget::wzBack()
|
||||
{
|
||||
if(wizardStep != wizardNone &&
|
||||
wizardStep != wizardIdentifySticks)
|
||||
wizardTearDownStep(wizardStep);
|
||||
|
||||
// State transitions for next button
|
||||
switch(wizardStep) {
|
||||
case wizardChooseMode:
|
||||
wizardSetUpStep(wizardWelcome);
|
||||
break;
|
||||
case wizardChooseType:
|
||||
wizardSetUpStep(wizardChooseMode);
|
||||
break;
|
||||
case wizardIdentifySticks:
|
||||
prevChannel();
|
||||
if(currentChannelNum == -1) {
|
||||
wizardTearDownStep(wizardIdentifySticks);
|
||||
wizardSetUpStep(wizardChooseType);
|
||||
}
|
||||
break;
|
||||
case wizardIdentifyCenter:
|
||||
wizardSetUpStep(wizardIdentifySticks);
|
||||
break;
|
||||
case wizardIdentifyLimits:
|
||||
wizardSetUpStep(wizardIdentifyCenter);
|
||||
break;
|
||||
case wizardIdentifyInverted:
|
||||
wizardSetUpStep(wizardIdentifyLimits);
|
||||
break;
|
||||
case wizardFinish:
|
||||
wizardSetUpStep(wizardIdentifyInverted);
|
||||
break;
|
||||
default:
|
||||
Q_ASSERT(0);
|
||||
}
|
||||
}
|
||||
|
||||
void ConfigInputWidget::wizardSetUpStep(enum wizardSteps step)
|
||||
{
|
||||
switch(step) {
|
||||
case wizardWelcome:
|
||||
foreach(QPointer<QWidget> wd,extraWidgets)
|
||||
{
|
||||
if(!wd.isNull())
|
||||
delete wd;
|
||||
}
|
||||
extraWidgets.clear();
|
||||
m_config->graphicsView->setVisible(false);
|
||||
setTxMovement(nothing);
|
||||
manualSettingsData=manualSettingsObj->getData();
|
||||
manualSettingsData.Arming=ManualControlSettings::ARMING_ALWAYSDISARMED;
|
||||
previousManualSettingsData = manualSettingsData;
|
||||
manualSettingsObj->setData(manualSettingsData);
|
||||
m_config->wzText->setText(tr("Welcome to the inputs configuration wizard.\n"
|
||||
"Please follow the instructions on the screen and only move your controls when asked to.\n"
|
||||
"Make sure you already configured your hardware settings on the proper tab and restarted your board.\n"
|
||||
"You can press 'back' at any time to return to the previous screeen or press 'Cancel' to quit the wizard.\n"));
|
||||
m_config->stackedWidget->setCurrentIndex(1);
|
||||
m_config->wzBack->setEnabled(false);
|
||||
break;
|
||||
case wizardChooseMode:
|
||||
{
|
||||
m_config->graphicsView->setVisible(true);
|
||||
m_config->graphicsView->fitInView(m_txBackground, Qt::KeepAspectRatio );
|
||||
setTxMovement(nothing);
|
||||
m_config->wzText->setText(tr("Please choose your transmitter type.\n"
|
||||
"Mode 1 means your throttle stick is on the right.\n"
|
||||
"Mode 2 means your throttle stick is on the left.\n"));
|
||||
m_config->wzBack->setEnabled(true);
|
||||
QRadioButton * mode1=new QRadioButton(tr("Mode 1"),this);
|
||||
QRadioButton * mode2=new QRadioButton(tr("Mode 2"),this);
|
||||
mode2->setChecked(true);
|
||||
extraWidgets.clear();
|
||||
extraWidgets.append(mode1);
|
||||
extraWidgets.append(mode2);
|
||||
m_config->checkBoxesLayout->layout()->addWidget(mode1);
|
||||
m_config->checkBoxesLayout->layout()->addWidget(mode2);
|
||||
}
|
||||
break;
|
||||
case wizardChooseType:
|
||||
{
|
||||
m_config->wzText->setText(tr("Please choose your transmitter mode.\n"
|
||||
"Acro means normal transmitter.\n"
|
||||
"Heli means there is a collective pitch and throttle input.\n"
|
||||
"If you are using a heli transmitter please engage throttle hold now.\n"));
|
||||
m_config->wzBack->setEnabled(true);
|
||||
QRadioButton * typeAcro=new QRadioButton(tr("Acro"),this);
|
||||
QRadioButton * typeHeli=new QRadioButton(tr("Heli"),this);
|
||||
typeAcro->setChecked(true);
|
||||
typeHeli->setChecked(false);
|
||||
extraWidgets.clear();
|
||||
extraWidgets.append(typeAcro);
|
||||
extraWidgets.append(typeHeli);
|
||||
m_config->checkBoxesLayout->layout()->addWidget(typeAcro);
|
||||
m_config->checkBoxesLayout->layout()->addWidget(typeHeli);
|
||||
wizardStep=wizardChooseType;
|
||||
}
|
||||
break;
|
||||
case wizardIdentifySticks:
|
||||
usedChannels.clear();
|
||||
currentChannelNum=-1;
|
||||
nextChannel();
|
||||
manualSettingsData=manualSettingsObj->getData();
|
||||
connect(receiverActivityObj, SIGNAL(objectUpdated(UAVObject*)), this, SLOT(identifyControls()));
|
||||
m_config->wzNext->setEnabled(false);
|
||||
break;
|
||||
case wizardIdentifyCenter:
|
||||
setTxMovement(centerAll);
|
||||
m_config->wzText->setText(QString(tr("Please center all controls and press next when ready (if your FlightMode switch has only two positions, leave it in either position).")));
|
||||
break;
|
||||
case wizardIdentifyLimits:
|
||||
{
|
||||
accessoryDesiredObj0 = AccessoryDesired::GetInstance(getObjectManager(),0);
|
||||
accessoryDesiredObj1 = AccessoryDesired::GetInstance(getObjectManager(),1);
|
||||
accessoryDesiredObj2 = AccessoryDesired::GetInstance(getObjectManager(),2);
|
||||
setTxMovement(nothing);
|
||||
m_config->wzText->setText(QString(tr("Please move all controls to their maximum extents on both directions and press next when ready.")));
|
||||
fastMdata();
|
||||
manualSettingsData=manualSettingsObj->getData();
|
||||
for(uint i=0;i<ManualControlSettings::CHANNELMAX_NUMELEM;++i)
|
||||
{
|
||||
// Preserve the inverted status
|
||||
if(manualSettingsData.ChannelMin[i] <= manualSettingsData.ChannelMax[i]) {
|
||||
manualSettingsData.ChannelMin[i]=manualSettingsData.ChannelNeutral[i];
|
||||
manualSettingsData.ChannelMax[i]=manualSettingsData.ChannelNeutral[i];
|
||||
} else {
|
||||
// Make this detect as still inverted
|
||||
manualSettingsData.ChannelMin[i]=manualSettingsData.ChannelNeutral[i] + 1;
|
||||
manualSettingsData.ChannelMax[i]=manualSettingsData.ChannelNeutral[i];
|
||||
}
|
||||
}
|
||||
connect(manualCommandObj, SIGNAL(objectUpdated(UAVObject*)), this, SLOT(identifyLimits()));
|
||||
connect(manualCommandObj, SIGNAL(objectUpdated(UAVObject*)), this, SLOT(moveSticks()));
|
||||
connect(flightStatusObj, SIGNAL(objectUpdated(UAVObject*)), this, SLOT(moveSticks()));
|
||||
connect(accessoryDesiredObj0, SIGNAL(objectUpdated(UAVObject*)), this, SLOT(moveSticks()));
|
||||
}
|
||||
break;
|
||||
case wizardIdentifyInverted:
|
||||
dimOtherControls(true);
|
||||
setTxMovement(nothing);
|
||||
extraWidgets.clear();
|
||||
|
||||
for (int index = 0; index < manualSettingsObj->getField("ChannelMax")->getElementNames().length(); index++)
|
||||
{
|
||||
QString name = manualSettingsObj->getField("ChannelMax")->getElementNames().at(index);
|
||||
if(!name.contains("Access") && !name.contains("Flight"))
|
||||
{
|
||||
QCheckBox * cb=new QCheckBox(name,this);
|
||||
// Make sure checked status matches current one
|
||||
cb->setChecked(manualSettingsData.ChannelMax[index] < manualSettingsData.ChannelMin[index]);
|
||||
|
||||
extraWidgets.append(cb);
|
||||
m_config->checkBoxesLayout->layout()->addWidget(cb);
|
||||
|
||||
connect(cb,SIGNAL(toggled(bool)),this,SLOT(invertControls()));
|
||||
}
|
||||
}
|
||||
connect(manualCommandObj, SIGNAL(objectUpdated(UAVObject*)), this, SLOT(moveSticks()));
|
||||
m_config->wzText->setText(QString(tr("Please check the picture below and correct all the sticks which show an inverted movement, press next when ready.")));
|
||||
fastMdata();
|
||||
break;
|
||||
case wizardFinish:
|
||||
dimOtherControls(false);
|
||||
connect(manualCommandObj, SIGNAL(objectUpdated(UAVObject*)), this, SLOT(moveSticks()));
|
||||
connect(flightStatusObj, SIGNAL(objectUpdated(UAVObject*)), this, SLOT(moveSticks()));
|
||||
connect(accessoryDesiredObj0, SIGNAL(objectUpdated(UAVObject*)), this, SLOT(moveSticks()));
|
||||
m_config->wzText->setText(QString(tr("You have completed this wizard, please check below if the picture mimics your sticks movement.\n"
|
||||
"These new settings aren't saved to the board yet, after pressing next you will go to the initial screen where you can save the configuration.")));
|
||||
fastMdata();
|
||||
|
||||
manualSettingsData.ChannelNeutral[ManualControlSettings::CHANNELNEUTRAL_THROTTLE]=
|
||||
manualSettingsData.ChannelMin[ManualControlSettings::CHANNELMIN_THROTTLE]+
|
||||
((manualSettingsData.ChannelMax[ManualControlSettings::CHANNELMAX_THROTTLE]-
|
||||
manualSettingsData.ChannelMin[ManualControlSettings::CHANNELMIN_THROTTLE])*0.02);
|
||||
if((abs(manualSettingsData.ChannelMax[ManualControlSettings::CHANNELMAX_FLIGHTMODE]-manualSettingsData.ChannelNeutral[ManualControlSettings::CHANNELNEUTRAL_FLIGHTMODE])<100) ||
|
||||
(abs(manualSettingsData.ChannelMin[ManualControlSettings::CHANNELMIN_FLIGHTMODE]-manualSettingsData.ChannelNeutral[ManualControlSettings::CHANNELNEUTRAL_FLIGHTMODE])<100))
|
||||
{
|
||||
manualSettingsData.ChannelNeutral[ManualControlSettings::CHANNELNEUTRAL_FLIGHTMODE]=manualSettingsData.ChannelMin[ManualControlSettings::CHANNELMIN_FLIGHTMODE]+
|
||||
(manualSettingsData.ChannelMax[ManualControlSettings::CHANNELMAX_FLIGHTMODE]-manualSettingsData.ChannelMin[ManualControlSettings::CHANNELMIN_FLIGHTMODE])/2;
|
||||
}
|
||||
manualSettingsObj->setData(manualSettingsData);
|
||||
break;
|
||||
default:
|
||||
Q_ASSERT(0);
|
||||
}
|
||||
wizardStep = step;
|
||||
}
|
||||
|
||||
void ConfigInputWidget::wizardTearDownStep(enum wizardSteps step)
|
||||
{
|
||||
QRadioButton * mode, * type;
|
||||
Q_ASSERT(step == wizardStep);
|
||||
switch(step) {
|
||||
case wizardWelcome:
|
||||
break;
|
||||
case wizardChooseMode:
|
||||
mode=qobject_cast<QRadioButton *>(extraWidgets.at(0));
|
||||
if(mode->isChecked())
|
||||
transmitterMode=mode1;
|
||||
else
|
||||
transmitterMode=mode2;
|
||||
delete extraWidgets.at(0);
|
||||
delete extraWidgets.at(1);
|
||||
extraWidgets.clear();
|
||||
break;
|
||||
case wizardChooseType:
|
||||
type=qobject_cast<QRadioButton *>(extraWidgets.at(0));
|
||||
if(type->isChecked())
|
||||
transmitterType=acro;
|
||||
else
|
||||
transmitterType=heli;
|
||||
delete extraWidgets.at(0);
|
||||
delete extraWidgets.at(1);
|
||||
extraWidgets.clear();
|
||||
break;
|
||||
case wizardIdentifySticks:
|
||||
disconnect(receiverActivityObj, SIGNAL(objectUpdated(UAVObject*)), this, SLOT(identifyControls()));
|
||||
m_config->wzNext->setEnabled(true);
|
||||
setTxMovement(nothing);
|
||||
break;
|
||||
case wizardIdentifyCenter:
|
||||
manualCommandData=manualCommandObj->getData();
|
||||
manualSettingsData=manualSettingsObj->getData();
|
||||
for(unsigned int i=0;i<ManualControlCommand::CHANNEL_NUMELEM;++i)
|
||||
{
|
||||
manualSettingsData.ChannelNeutral[i]=manualCommandData.Channel[i];
|
||||
}
|
||||
manualSettingsObj->setData(manualSettingsData);
|
||||
setTxMovement(nothing);
|
||||
break;
|
||||
case wizardIdentifyLimits:
|
||||
disconnect(manualCommandObj, SIGNAL(objectUpdated(UAVObject*)), this, SLOT(identifyLimits()));
|
||||
disconnect(manualCommandObj, SIGNAL(objectUpdated(UAVObject*)), this, SLOT(moveSticks()));
|
||||
disconnect(flightStatusObj, SIGNAL(objectUpdated(UAVObject*)), this, SLOT(moveSticks()));
|
||||
disconnect(accessoryDesiredObj0, SIGNAL(objectUpdated(UAVObject*)), this, SLOT(moveSticks()));
|
||||
manualSettingsObj->setData(manualSettingsData);
|
||||
restoreMdata();
|
||||
setTxMovement(nothing);
|
||||
break;
|
||||
case wizardIdentifyInverted:
|
||||
dimOtherControls(false);
|
||||
foreach(QWidget * wd,extraWidgets)
|
||||
{
|
||||
QCheckBox * cb=qobject_cast<QCheckBox *>(wd);
|
||||
if(cb)
|
||||
{
|
||||
disconnect(cb,SIGNAL(toggled(bool)),this,SLOT(invertControls()));
|
||||
delete cb;
|
||||
}
|
||||
}
|
||||
extraWidgets.clear();
|
||||
disconnect(manualCommandObj, SIGNAL(objectUpdated(UAVObject*)), this, SLOT(moveSticks()));
|
||||
restoreMdata();
|
||||
break;
|
||||
case wizardFinish:
|
||||
dimOtherControls(false);
|
||||
setTxMovement(nothing);
|
||||
disconnect(manualCommandObj, SIGNAL(objectUpdated(UAVObject*)), this, SLOT(moveSticks()));
|
||||
disconnect(flightStatusObj, SIGNAL(objectUpdated(UAVObject*)), this, SLOT(moveSticks()));
|
||||
disconnect(accessoryDesiredObj0, SIGNAL(objectUpdated(UAVObject*)), this, SLOT(moveSticks()));
|
||||
restoreMdata();
|
||||
break;
|
||||
default:
|
||||
Q_ASSERT(0);
|
||||
}
|
||||
}
|
||||
|
||||
/**
|
||||
* Set manual control command to fast updates
|
||||
*/
|
||||
void ConfigInputWidget::fastMdata()
|
||||
{
|
||||
manualControlMdata = manualCommandObj->getMetadata();
|
||||
UAVObject::Metadata mdata = manualControlMdata;
|
||||
UAVObject::SetFlightTelemetryUpdateMode(mdata, UAVObject::UPDATEMODE_PERIODIC);
|
||||
mdata.flightTelemetryUpdatePeriod = 150;
|
||||
manualCommandObj->setMetadata(mdata);
|
||||
}
|
||||
|
||||
/**
|
||||
* Restore previous update settings for manual control data
|
||||
*/
|
||||
void ConfigInputWidget::restoreMdata()
|
||||
{
|
||||
manualCommandObj->setMetadata(manualControlMdata);
|
||||
}
|
||||
|
||||
/**
|
||||
* Set the display to indicate which channel the person should move
|
||||
*/
|
||||
void ConfigInputWidget::setChannel(int newChan)
|
||||
{
|
||||
if(newChan == ManualControlSettings::CHANNELGROUPS_COLLECTIVE)
|
||||
m_config->wzText->setText(QString(tr("Please enable the throttle hold mode and move the collective pitch stick.")));
|
||||
else if (newChan == ManualControlSettings::CHANNELGROUPS_FLIGHTMODE)
|
||||
m_config->wzText->setText(QString(tr("Please toggle the flight mode switch. For switches you may have to repeat this rapidly.")));
|
||||
else if((transmitterType == heli) && (newChan == ManualControlSettings::CHANNELGROUPS_THROTTLE))
|
||||
m_config->wzText->setText(QString(tr("Please disable throttle hold mode and move the throttle stick.")));
|
||||
else
|
||||
m_config->wzText->setText(QString(tr("Please move each control once at a time according to the instructions and picture below.\n\n"
|
||||
"Move the %1 stick")).arg(manualSettingsObj->getField("ChannelGroups")->getElementNames().at(newChan)));
|
||||
|
||||
if(manualSettingsObj->getField("ChannelGroups")->getElementNames().at(newChan).contains("Accessory") ||
|
||||
manualSettingsObj->getField("ChannelGroups")->getElementNames().at(newChan).contains("FlightMode")) {
|
||||
m_config->wzNext->setEnabled(true);
|
||||
m_config->wzText->setText(m_config->wzText->text() + tr(" or click next to skip this channel."));
|
||||
} else
|
||||
m_config->wzNext->setEnabled(false);
|
||||
|
||||
setMoveFromCommand(newChan);
|
||||
|
||||
currentChannelNum = newChan;
|
||||
channelDetected = false;
|
||||
}
|
||||
|
||||
/**
|
||||
* Unfortunately order of channel should be different in different conditions. Selects
|
||||
* next channel based on heli or acro mode
|
||||
*/
|
||||
void ConfigInputWidget::nextChannel()
|
||||
{
|
||||
QList <int> order = (transmitterType == heli) ? heliChannelOrder : acroChannelOrder;
|
||||
|
||||
if(currentChannelNum == -1) {
|
||||
setChannel(order[0]);
|
||||
return;
|
||||
}
|
||||
for (int i = 0; i < order.length() - 1; i++) {
|
||||
if(order[i] == currentChannelNum) {
|
||||
setChannel(order[i+1]);
|
||||
return;
|
||||
}
|
||||
}
|
||||
currentChannelNum = -1; // hit end of list
|
||||
}
|
||||
|
||||
/**
|
||||
* Unfortunately order of channel should be different in different conditions. Selects
|
||||
* previous channel based on heli or acro mode
|
||||
*/
|
||||
void ConfigInputWidget::prevChannel()
|
||||
{
|
||||
QList <int> order = transmitterType == heli ? heliChannelOrder : acroChannelOrder;
|
||||
|
||||
// No previous from unset channel or next state
|
||||
if(currentChannelNum == -1)
|
||||
return;
|
||||
|
||||
for (int i = 1; i < order.length(); i++) {
|
||||
if(order[i] == currentChannelNum) {
|
||||
setChannel(order[i-1]);
|
||||
usedChannels.removeLast();
|
||||
return;
|
||||
}
|
||||
}
|
||||
currentChannelNum = -1; // hit end of list
|
||||
}
|
||||
|
||||
void ConfigInputWidget::identifyControls()
|
||||
{
|
||||
static int debounce=0;
|
||||
|
||||
receiverActivityData=receiverActivityObj->getData();
|
||||
if(receiverActivityData.ActiveChannel==255)
|
||||
return;
|
||||
if(channelDetected)
|
||||
return;
|
||||
else
|
||||
{
|
||||
receiverActivityData=receiverActivityObj->getData();
|
||||
currentChannel.group=receiverActivityData.ActiveGroup;
|
||||
currentChannel.number=receiverActivityData.ActiveChannel;
|
||||
if(currentChannel==lastChannel)
|
||||
++debounce;
|
||||
lastChannel.group= currentChannel.group;
|
||||
lastChannel.number=currentChannel.number;
|
||||
if(!usedChannels.contains(lastChannel) && debounce>1)
|
||||
{
|
||||
channelDetected = true;
|
||||
debounce=0;
|
||||
usedChannels.append(lastChannel);
|
||||
manualSettingsData=manualSettingsObj->getData();
|
||||
manualSettingsData.ChannelGroups[currentChannelNum]=currentChannel.group;
|
||||
manualSettingsData.ChannelNumber[currentChannelNum]=currentChannel.number;
|
||||
manualSettingsObj->setData(manualSettingsData);
|
||||
}
|
||||
else
|
||||
return;
|
||||
}
|
||||
|
||||
m_config->wzText->clear();
|
||||
setTxMovement(nothing);
|
||||
|
||||
QTimer::singleShot(2500, this, SLOT(wzNext()));
|
||||
}
|
||||
|
||||
void ConfigInputWidget::identifyLimits()
|
||||
{
|
||||
manualCommandData=manualCommandObj->getData();
|
||||
for(uint i=0;i<ManualControlSettings::CHANNELMAX_NUMELEM;++i)
|
||||
{
|
||||
if(manualSettingsData.ChannelMin[i] <= manualSettingsData.ChannelMax[i]) {
|
||||
// Non inverted channel
|
||||
if(manualSettingsData.ChannelMin[i]>manualCommandData.Channel[i])
|
||||
manualSettingsData.ChannelMin[i]=manualCommandData.Channel[i];
|
||||
if(manualSettingsData.ChannelMax[i]<manualCommandData.Channel[i])
|
||||
manualSettingsData.ChannelMax[i]=manualCommandData.Channel[i];
|
||||
} else {
|
||||
// Inverted channel
|
||||
if(manualSettingsData.ChannelMax[i]>manualCommandData.Channel[i])
|
||||
manualSettingsData.ChannelMax[i]=manualCommandData.Channel[i];
|
||||
if(manualSettingsData.ChannelMin[i]<manualCommandData.Channel[i])
|
||||
manualSettingsData.ChannelMin[i]=manualCommandData.Channel[i];
|
||||
}
|
||||
}
|
||||
manualSettingsObj->setData(manualSettingsData);
|
||||
}
|
||||
void ConfigInputWidget::setMoveFromCommand(int command)
|
||||
{
|
||||
//CHANNELNUMBER_ROLL=0, CHANNELNUMBER_PITCH=1, CHANNELNUMBER_YAW=2, CHANNELNUMBER_THROTTLE=3, CHANNELNUMBER_FLIGHTMODE=4, CHANNELNUMBER_ACCESSORY0=5, CHANNELNUMBER_ACCESSORY1=6, CHANNELNUMBER_ACCESSORY2=7 } ChannelNumberElem;
|
||||
if(command==ManualControlSettings::CHANNELNUMBER_ROLL)
|
||||
{
|
||||
setTxMovement(moveRightHorizontalStick);
|
||||
}
|
||||
else if(command==ManualControlSettings::CHANNELNUMBER_PITCH)
|
||||
{
|
||||
if(transmitterMode==mode2)
|
||||
setTxMovement(moveRightVerticalStick);
|
||||
else
|
||||
setTxMovement(moveLeftVerticalStick);
|
||||
}
|
||||
else if(command==ManualControlSettings::CHANNELNUMBER_YAW)
|
||||
{
|
||||
setTxMovement(moveLeftHorizontalStick);
|
||||
}
|
||||
else if(command==ManualControlSettings::CHANNELNUMBER_THROTTLE)
|
||||
{
|
||||
if(transmitterMode==mode2)
|
||||
setTxMovement(moveLeftVerticalStick);
|
||||
else
|
||||
setTxMovement(moveRightVerticalStick);
|
||||
}
|
||||
else if(command==ManualControlSettings::CHANNELNUMBER_COLLECTIVE)
|
||||
{
|
||||
if(transmitterMode==mode2)
|
||||
setTxMovement(moveLeftVerticalStick);
|
||||
else
|
||||
setTxMovement(moveRightVerticalStick);
|
||||
}
|
||||
else if(command==ManualControlSettings::CHANNELNUMBER_FLIGHTMODE)
|
||||
{
|
||||
setTxMovement(moveFlightMode);
|
||||
}
|
||||
else if(command==ManualControlSettings::CHANNELNUMBER_ACCESSORY0)
|
||||
{
|
||||
setTxMovement(moveAccess0);
|
||||
}
|
||||
else if(command==ManualControlSettings::CHANNELNUMBER_ACCESSORY1)
|
||||
{
|
||||
setTxMovement(moveAccess1);
|
||||
}
|
||||
else if(command==ManualControlSettings::CHANNELNUMBER_ACCESSORY2)
|
||||
{
|
||||
setTxMovement(moveAccess2);
|
||||
}
|
||||
|
||||
}
|
||||
|
||||
void ConfigInputWidget::setTxMovement(txMovements movement)
|
||||
{
|
||||
resetTxControls();
|
||||
switch(movement)
|
||||
{
|
||||
case moveLeftVerticalStick:
|
||||
movePos=0;
|
||||
growing=true;
|
||||
currentMovement=moveLeftVerticalStick;
|
||||
animate->start(100);
|
||||
break;
|
||||
case moveRightVerticalStick:
|
||||
movePos=0;
|
||||
growing=true;
|
||||
currentMovement=moveRightVerticalStick;
|
||||
animate->start(100);
|
||||
break;
|
||||
case moveLeftHorizontalStick:
|
||||
movePos=0;
|
||||
growing=true;
|
||||
currentMovement=moveLeftHorizontalStick;
|
||||
animate->start(100);
|
||||
break;
|
||||
case moveRightHorizontalStick:
|
||||
movePos=0;
|
||||
growing=true;
|
||||
currentMovement=moveRightHorizontalStick;
|
||||
animate->start(100);
|
||||
break;
|
||||
case moveAccess0:
|
||||
movePos=0;
|
||||
growing=true;
|
||||
currentMovement=moveAccess0;
|
||||
animate->start(100);
|
||||
break;
|
||||
case moveAccess1:
|
||||
movePos=0;
|
||||
growing=true;
|
||||
currentMovement=moveAccess1;
|
||||
animate->start(100);
|
||||
break;
|
||||
case moveAccess2:
|
||||
movePos=0;
|
||||
growing=true;
|
||||
currentMovement=moveAccess2;
|
||||
animate->start(100);
|
||||
break;
|
||||
case moveFlightMode:
|
||||
movePos=0;
|
||||
growing=true;
|
||||
currentMovement=moveFlightMode;
|
||||
animate->start(1000);
|
||||
break;
|
||||
case centerAll:
|
||||
movePos=0;
|
||||
currentMovement=centerAll;
|
||||
animate->start(1000);
|
||||
break;
|
||||
case moveAll:
|
||||
movePos=0;
|
||||
growing=true;
|
||||
currentMovement=moveAll;
|
||||
animate->start(50);
|
||||
break;
|
||||
case nothing:
|
||||
movePos=0;
|
||||
animate->stop();
|
||||
break;
|
||||
default:
|
||||
break;
|
||||
}
|
||||
}
|
||||
|
||||
void ConfigInputWidget::moveTxControls()
|
||||
{
|
||||
QTransform trans;
|
||||
QGraphicsItem * item;
|
||||
txMovementType move;
|
||||
int limitMax;
|
||||
int limitMin;
|
||||
static bool auxFlag=false;
|
||||
switch(currentMovement)
|
||||
{
|
||||
case moveLeftVerticalStick:
|
||||
item=m_txLeftStick;
|
||||
trans=m_txLeftStickOrig;
|
||||
limitMax=STICK_MAX_MOVE;
|
||||
limitMin=STICK_MIN_MOVE;
|
||||
move=vertical;
|
||||
break;
|
||||
case moveRightVerticalStick:
|
||||
item=m_txRightStick;
|
||||
trans=m_txRightStickOrig;
|
||||
limitMax=STICK_MAX_MOVE;
|
||||
limitMin=STICK_MIN_MOVE;
|
||||
move=vertical;
|
||||
break;
|
||||
case moveLeftHorizontalStick:
|
||||
item=m_txLeftStick;
|
||||
trans=m_txLeftStickOrig;
|
||||
limitMax=STICK_MAX_MOVE;
|
||||
limitMin=STICK_MIN_MOVE;
|
||||
move=horizontal;
|
||||
break;
|
||||
case moveRightHorizontalStick:
|
||||
item=m_txRightStick;
|
||||
trans=m_txRightStickOrig;
|
||||
limitMax=STICK_MAX_MOVE;
|
||||
limitMin=STICK_MIN_MOVE;
|
||||
move=horizontal;
|
||||
break;
|
||||
case moveAccess0:
|
||||
item=m_txAccess0;
|
||||
trans=m_txAccess0Orig;
|
||||
limitMax=ACCESS_MAX_MOVE;
|
||||
limitMin=ACCESS_MIN_MOVE;
|
||||
move=horizontal;
|
||||
break;
|
||||
case moveAccess1:
|
||||
item=m_txAccess1;
|
||||
trans=m_txAccess1Orig;
|
||||
limitMax=ACCESS_MAX_MOVE;
|
||||
limitMin=ACCESS_MIN_MOVE;
|
||||
move=horizontal;
|
||||
break;
|
||||
case moveAccess2:
|
||||
item=m_txAccess2;
|
||||
trans=m_txAccess2Orig;
|
||||
limitMax=ACCESS_MAX_MOVE;
|
||||
limitMin=ACCESS_MIN_MOVE;
|
||||
move=horizontal;
|
||||
break;
|
||||
case moveFlightMode:
|
||||
item=m_txFlightMode;
|
||||
move=jump;
|
||||
break;
|
||||
case centerAll:
|
||||
item=m_txArrows;
|
||||
move=jump;
|
||||
break;
|
||||
case moveAll:
|
||||
limitMax=STICK_MAX_MOVE;
|
||||
limitMin=STICK_MIN_MOVE;
|
||||
move=mix;
|
||||
break;
|
||||
default:
|
||||
break;
|
||||
}
|
||||
if(move==vertical)
|
||||
item->setTransform(trans.translate(0,movePos*10),false);
|
||||
else if(move==horizontal)
|
||||
item->setTransform(trans.translate(movePos*10,0),false);
|
||||
else if(move==jump)
|
||||
{
|
||||
if(item==m_txArrows)
|
||||
{
|
||||
m_txArrows->setVisible(!m_txArrows->isVisible());
|
||||
}
|
||||
else if(item==m_txFlightMode)
|
||||
{
|
||||
QGraphicsSvgItem * svg;
|
||||
svg=(QGraphicsSvgItem *)item;
|
||||
if (svg)
|
||||
{
|
||||
if(svg->elementId()=="flightModeCenter")
|
||||
{
|
||||
if(growing)
|
||||
{
|
||||
svg->setElementId("flightModeRight");
|
||||
m_txFlightMode->setTransform(m_txFlightModeROrig,false);
|
||||
}
|
||||
else
|
||||
{
|
||||
svg->setElementId("flightModeLeft");
|
||||
m_txFlightMode->setTransform(m_txFlightModeLOrig,false);
|
||||
}
|
||||
}
|
||||
else if(svg->elementId()=="flightModeRight")
|
||||
{
|
||||
growing=false;
|
||||
svg->setElementId("flightModeCenter");
|
||||
m_txFlightMode->setTransform(m_txFlightModeCOrig,false);
|
||||
}
|
||||
else if(svg->elementId()=="flightModeLeft")
|
||||
{
|
||||
growing=true;
|
||||
svg->setElementId("flightModeCenter");
|
||||
m_txFlightMode->setTransform(m_txFlightModeCOrig,false);
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
else if(move==mix)
|
||||
{
|
||||
trans=m_txAccess0Orig;
|
||||
m_txAccess0->setTransform(trans.translate(movePos*10*ACCESS_MAX_MOVE/STICK_MAX_MOVE,0),false);
|
||||
trans=m_txAccess1Orig;
|
||||
m_txAccess1->setTransform(trans.translate(movePos*10*ACCESS_MAX_MOVE/STICK_MAX_MOVE,0),false);
|
||||
trans=m_txAccess2Orig;
|
||||
m_txAccess2->setTransform(trans.translate(movePos*10*ACCESS_MAX_MOVE/STICK_MAX_MOVE,0),false);
|
||||
|
||||
if(auxFlag)
|
||||
{
|
||||
trans=m_txLeftStickOrig;
|
||||
m_txLeftStick->setTransform(trans.translate(0,movePos*10),false);
|
||||
trans=m_txRightStickOrig;
|
||||
m_txRightStick->setTransform(trans.translate(0,movePos*10),false);
|
||||
}
|
||||
else
|
||||
{
|
||||
trans=m_txLeftStickOrig;
|
||||
m_txLeftStick->setTransform(trans.translate(movePos*10,0),false);
|
||||
trans=m_txRightStickOrig;
|
||||
m_txRightStick->setTransform(trans.translate(movePos*10,0),false);
|
||||
}
|
||||
|
||||
if(movePos==0)
|
||||
{
|
||||
m_txFlightMode->setElementId("flightModeCenter");
|
||||
m_txFlightMode->setTransform(m_txFlightModeCOrig,false);
|
||||
}
|
||||
else if(movePos==ACCESS_MAX_MOVE/2)
|
||||
{
|
||||
m_txFlightMode->setElementId("flightModeRight");
|
||||
m_txFlightMode->setTransform(m_txFlightModeROrig,false);
|
||||
}
|
||||
else if(movePos==ACCESS_MIN_MOVE/2)
|
||||
{
|
||||
m_txFlightMode->setElementId("flightModeLeft");
|
||||
m_txFlightMode->setTransform(m_txFlightModeLOrig,false);
|
||||
}
|
||||
}
|
||||
if(move==horizontal || move==vertical ||move==mix)
|
||||
{
|
||||
if(movePos==0 && growing)
|
||||
auxFlag=!auxFlag;
|
||||
if(growing)
|
||||
++movePos;
|
||||
else
|
||||
--movePos;
|
||||
if(movePos>limitMax)
|
||||
{
|
||||
movePos=movePos-2;
|
||||
growing=false;
|
||||
}
|
||||
if(movePos<limitMin)
|
||||
{
|
||||
movePos=movePos+2;
|
||||
growing=true;
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
void ConfigInputWidget::moveSticks()
|
||||
{
|
||||
QTransform trans;
|
||||
manualCommandData=manualCommandObj->getData();
|
||||
flightStatusData=flightStatusObj->getData();
|
||||
accessoryDesiredData0=accessoryDesiredObj0->getData();
|
||||
accessoryDesiredData1=accessoryDesiredObj1->getData();
|
||||
accessoryDesiredData2=accessoryDesiredObj2->getData();
|
||||
|
||||
if(transmitterMode==mode2)
|
||||
{
|
||||
trans=m_txLeftStickOrig;
|
||||
m_txLeftStick->setTransform(trans.translate(manualCommandData.Yaw*STICK_MAX_MOVE*10,-manualCommandData.Throttle*STICK_MAX_MOVE*10),false);
|
||||
trans=m_txRightStickOrig;
|
||||
m_txRightStick->setTransform(trans.translate(manualCommandData.Roll*STICK_MAX_MOVE*10,manualCommandData.Pitch*STICK_MAX_MOVE*10),false);
|
||||
}
|
||||
else
|
||||
{
|
||||
trans=m_txRightStickOrig;
|
||||
m_txRightStick->setTransform(trans.translate(manualCommandData.Roll*STICK_MAX_MOVE*10,-manualCommandData.Throttle*STICK_MAX_MOVE*10),false);
|
||||
trans=m_txLeftStickOrig;
|
||||
m_txLeftStick->setTransform(trans.translate(manualCommandData.Yaw*STICK_MAX_MOVE*10,manualCommandData.Pitch*STICK_MAX_MOVE*10),false);
|
||||
}
|
||||
if(flightStatusData.FlightMode==manualSettingsData.FlightModePosition[0])
|
||||
{
|
||||
m_txFlightMode->setElementId("flightModeLeft");
|
||||
m_txFlightMode->setTransform(m_txFlightModeLOrig,false);
|
||||
}
|
||||
else if (flightStatusData.FlightMode==manualSettingsData.FlightModePosition[1])
|
||||
{
|
||||
m_txFlightMode->setElementId("flightModeCenter");
|
||||
m_txFlightMode->setTransform(m_txFlightModeCOrig,false);
|
||||
}
|
||||
else if (flightStatusData.FlightMode==manualSettingsData.FlightModePosition[2])
|
||||
{
|
||||
m_txFlightMode->setElementId("flightModeRight");
|
||||
m_txFlightMode->setTransform(m_txFlightModeROrig,false);
|
||||
}
|
||||
m_txAccess0->setTransform(QTransform(m_txAccess0Orig).translate(accessoryDesiredData0.AccessoryVal*ACCESS_MAX_MOVE*10,0),false);
|
||||
m_txAccess1->setTransform(QTransform(m_txAccess1Orig).translate(accessoryDesiredData1.AccessoryVal*ACCESS_MAX_MOVE*10,0),false);
|
||||
m_txAccess2->setTransform(QTransform(m_txAccess2Orig).translate(accessoryDesiredData2.AccessoryVal*ACCESS_MAX_MOVE*10,0),false);
|
||||
}
|
||||
|
||||
void ConfigInputWidget::dimOtherControls(bool value)
|
||||
{
|
||||
qreal opac;
|
||||
if(value)
|
||||
opac=0.1;
|
||||
else
|
||||
opac=1;
|
||||
m_txAccess0->setOpacity(opac);
|
||||
m_txAccess1->setOpacity(opac);
|
||||
m_txAccess2->setOpacity(opac);
|
||||
m_txFlightMode->setOpacity(opac);
|
||||
}
|
||||
|
||||
void ConfigInputWidget::enableControls(bool enable)
|
||||
{
|
||||
m_config->configurationWizard->setEnabled(enable);
|
||||
m_config->runCalibration->setEnabled(enable);
|
||||
|
||||
ConfigTaskWidget::enableControls(enable);
|
||||
|
||||
}
|
||||
|
||||
void ConfigInputWidget::invertControls()
|
||||
{
|
||||
manualSettingsData=manualSettingsObj->getData();
|
||||
foreach(QWidget * wd,extraWidgets)
|
||||
{
|
||||
QCheckBox * cb=qobject_cast<QCheckBox *>(wd);
|
||||
if(cb)
|
||||
{
|
||||
int index = manualSettingsObj->getField("ChannelNumber")->getElementNames().indexOf(cb->text());
|
||||
if((cb->isChecked() && (manualSettingsData.ChannelMax[index]>manualSettingsData.ChannelMin[index])) ||
|
||||
(!cb->isChecked() && (manualSettingsData.ChannelMax[index]<manualSettingsData.ChannelMin[index])))
|
||||
{
|
||||
qint16 aux;
|
||||
aux=manualSettingsData.ChannelMax[index];
|
||||
manualSettingsData.ChannelMax[index]=manualSettingsData.ChannelMin[index];
|
||||
manualSettingsData.ChannelMin[index]=aux;
|
||||
}
|
||||
}
|
||||
}
|
||||
manualSettingsObj->setData(manualSettingsData);
|
||||
}
|
||||
|
||||
void ConfigInputWidget::moveFMSlider()
|
||||
{
|
||||
ManualControlSettings::DataFields manualSettingsDataPriv = manualSettingsObj->getData();
|
||||
ManualControlCommand::DataFields manualCommandDataPriv = manualCommandObj->getData();
|
||||
|
||||
float valueScaled;
|
||||
int chMin = manualSettingsDataPriv.ChannelMin[ManualControlSettings::CHANNELMIN_FLIGHTMODE];
|
||||
int chMax = manualSettingsDataPriv.ChannelMax[ManualControlSettings::CHANNELMAX_FLIGHTMODE];
|
||||
int chNeutral = manualSettingsDataPriv.ChannelNeutral[ManualControlSettings::CHANNELNEUTRAL_FLIGHTMODE];
|
||||
|
||||
int value = manualCommandDataPriv.Channel[ManualControlSettings::CHANNELMIN_FLIGHTMODE];
|
||||
if ((chMax > chMin && value >= chNeutral) || (chMin > chMax && value <= chNeutral))
|
||||
{
|
||||
if (chMax != chNeutral)
|
||||
valueScaled = (float)(value - chNeutral) / (float)(chMax - chNeutral);
|
||||
else
|
||||
valueScaled = 0;
|
||||
}
|
||||
else
|
||||
{
|
||||
if (chMin != chNeutral)
|
||||
valueScaled = (float)(value - chNeutral) / (float)(chNeutral - chMin);
|
||||
else
|
||||
valueScaled = 0;
|
||||
}
|
||||
|
||||
// Bound and scale FlightMode from [-1..+1] to [0..1] range
|
||||
if (valueScaled < -1.0)
|
||||
valueScaled = -1.0;
|
||||
else
|
||||
if (valueScaled > 1.0)
|
||||
valueScaled = 1.0;
|
||||
|
||||
// Convert flightMode value into the switch position in the range [0..N-1]
|
||||
// This uses the same optimized computation as flight code to be consistent
|
||||
uint8_t pos = ((int16_t)(valueScaled * 256) + 256) * manualSettingsDataPriv.FlightModeNumber >> 9;
|
||||
if (pos >= manualSettingsDataPriv.FlightModeNumber)
|
||||
pos = manualSettingsDataPriv.FlightModeNumber - 1;
|
||||
m_config->fmsSlider->setValue(pos);
|
||||
}
|
||||
|
||||
void ConfigInputWidget::updatePositionSlider()
|
||||
{
|
||||
ManualControlSettings::DataFields manualSettingsDataPriv = manualSettingsObj->getData();
|
||||
|
||||
switch(manualSettingsDataPriv.FlightModeNumber) {
|
||||
default:
|
||||
case 6:
|
||||
m_config->fmsModePos6->setEnabled(true);
|
||||
// pass through
|
||||
case 5:
|
||||
m_config->fmsModePos5->setEnabled(true);
|
||||
// pass through
|
||||
case 4:
|
||||
m_config->fmsModePos4->setEnabled(true);
|
||||
// pass through
|
||||
case 3:
|
||||
m_config->fmsModePos3->setEnabled(true);
|
||||
// pass through
|
||||
case 2:
|
||||
m_config->fmsModePos2->setEnabled(true);
|
||||
// pass through
|
||||
case 1:
|
||||
m_config->fmsModePos1->setEnabled(true);
|
||||
// pass through
|
||||
case 0:
|
||||
break;
|
||||
}
|
||||
|
||||
switch(manualSettingsDataPriv.FlightModeNumber) {
|
||||
case 0:
|
||||
m_config->fmsModePos1->setEnabled(false);
|
||||
// pass through
|
||||
case 1:
|
||||
m_config->fmsModePos2->setEnabled(false);
|
||||
// pass through
|
||||
case 2:
|
||||
m_config->fmsModePos3->setEnabled(false);
|
||||
// pass through
|
||||
case 3:
|
||||
m_config->fmsModePos4->setEnabled(false);
|
||||
// pass through
|
||||
case 4:
|
||||
m_config->fmsModePos5->setEnabled(false);
|
||||
// pass through
|
||||
case 5:
|
||||
m_config->fmsModePos6->setEnabled(false);
|
||||
// pass through
|
||||
case 6:
|
||||
default:
|
||||
break;
|
||||
}
|
||||
}
|
||||
|
||||
void ConfigInputWidget::updateCalibration()
|
||||
{
|
||||
manualCommandData=manualCommandObj->getData();
|
||||
for(uint i=0;i<ManualControlSettings::CHANNELMAX_NUMELEM;++i)
|
||||
{
|
||||
if((!reverse[i] && manualSettingsData.ChannelMin[i]>manualCommandData.Channel[i]) ||
|
||||
(reverse[i] && manualSettingsData.ChannelMin[i]<manualCommandData.Channel[i]))
|
||||
manualSettingsData.ChannelMin[i]=manualCommandData.Channel[i];
|
||||
if((!reverse[i] && manualSettingsData.ChannelMax[i]<manualCommandData.Channel[i]) ||
|
||||
(reverse[i] && manualSettingsData.ChannelMax[i]>manualCommandData.Channel[i]))
|
||||
manualSettingsData.ChannelMax[i]=manualCommandData.Channel[i];
|
||||
manualSettingsData.ChannelNeutral[i] = manualCommandData.Channel[i];
|
||||
}
|
||||
|
||||
manualSettingsObj->setData(manualSettingsData);
|
||||
manualSettingsObj->updated();
|
||||
}
|
||||
|
||||
void ConfigInputWidget::simpleCalibration(bool enable)
|
||||
{
|
||||
if (enable) {
|
||||
m_config->configurationWizard->setEnabled(false);
|
||||
|
||||
QMessageBox msgBox;
|
||||
msgBox.setText(tr("Arming Settings are now set to Always Disarmed for your safety."));
|
||||
msgBox.setDetailedText(tr("You will have to reconfigure the arming settings manually when the wizard is finished."));
|
||||
msgBox.setStandardButtons(QMessageBox::Ok);
|
||||
msgBox.setDefaultButton(QMessageBox::Ok);
|
||||
msgBox.exec();
|
||||
|
||||
manualCommandData = manualCommandObj->getData();
|
||||
|
||||
manualSettingsData=manualSettingsObj->getData();
|
||||
manualSettingsData.Arming=ManualControlSettings::ARMING_ALWAYSDISARMED;
|
||||
manualSettingsObj->setData(manualSettingsData);
|
||||
|
||||
for (unsigned int i = 0; i < ManualControlCommand::CHANNEL_NUMELEM; i++) {
|
||||
reverse[i] = manualSettingsData.ChannelMax[i] < manualSettingsData.ChannelMin[i];
|
||||
manualSettingsData.ChannelMin[i] = manualCommandData.Channel[i];
|
||||
manualSettingsData.ChannelNeutral[i] = manualCommandData.Channel[i];
|
||||
manualSettingsData.ChannelMax[i] = manualCommandData.Channel[i];
|
||||
}
|
||||
|
||||
fastMdata();
|
||||
|
||||
connect(manualCommandObj, SIGNAL(objectUnpacked(UAVObject*)), this, SLOT(updateCalibration()));
|
||||
} else {
|
||||
m_config->configurationWizard->setEnabled(true);
|
||||
|
||||
manualCommandData = manualCommandObj->getData();
|
||||
manualSettingsData = manualSettingsObj->getData();
|
||||
|
||||
restoreMdata();
|
||||
|
||||
for (int i = 0; i < ManualControlCommand::CHANNEL_NUMELEM; i++)
|
||||
manualSettingsData.ChannelNeutral[i] = manualCommandData.Channel[i];
|
||||
|
||||
// Force flight mode neutral to middle
|
||||
manualSettingsData.ChannelNeutral[ManualControlSettings::CHANNELNUMBER_FLIGHTMODE] =
|
||||
(manualSettingsData.ChannelMax[ManualControlSettings::CHANNELNUMBER_FLIGHTMODE] +
|
||||
manualSettingsData.ChannelMin[ManualControlSettings::CHANNELNUMBER_FLIGHTMODE]) / 2;
|
||||
|
||||
// Force throttle to be near min
|
||||
manualSettingsData.ChannelNeutral[ManualControlSettings::CHANNELNEUTRAL_THROTTLE]=
|
||||
manualSettingsData.ChannelMin[ManualControlSettings::CHANNELMIN_THROTTLE]+
|
||||
((manualSettingsData.ChannelMax[ManualControlSettings::CHANNELMAX_THROTTLE]-
|
||||
manualSettingsData.ChannelMin[ManualControlSettings::CHANNELMIN_THROTTLE])*0.02);
|
||||
|
||||
manualSettingsObj->setData(manualSettingsData);
|
||||
|
||||
disconnect(manualCommandObj, SIGNAL(objectUnpacked(UAVObject*)), this, SLOT(updateCalibration()));
|
||||
}
|
||||
}
|
||||
/**
|
||||
******************************************************************************
|
||||
*
|
||||
* @file configinputwidget.cpp
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010.
|
||||
* @addtogroup GCSPlugins GCS Plugins
|
||||
* @{
|
||||
* @addtogroup ConfigPlugin Config Plugin
|
||||
* @{
|
||||
* @brief Servo input/output configuration panel for the config gadget
|
||||
*****************************************************************************/
|
||||
/*
|
||||
* 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 "configinputwidget.h"
|
||||
|
||||
#include "uavtalk/telemetrymanager.h"
|
||||
|
||||
#include <QDebug>
|
||||
#include <QStringList>
|
||||
#include <QtGui/QWidget>
|
||||
#include <QtGui/QTextEdit>
|
||||
#include <QtGui/QVBoxLayout>
|
||||
#include <QtGui/QPushButton>
|
||||
#include <QDesktopServices>
|
||||
#include <QUrl>
|
||||
#include <QMessageBox>
|
||||
#include <utils/stylehelper.h>
|
||||
#include <QMessageBox>
|
||||
|
||||
#include <extensionsystem/pluginmanager.h>
|
||||
#include <coreplugin/generalsettings.h>
|
||||
|
||||
#define ACCESS_MIN_MOVE -3
|
||||
#define ACCESS_MAX_MOVE 3
|
||||
#define STICK_MIN_MOVE -8
|
||||
#define STICK_MAX_MOVE 8
|
||||
|
||||
ConfigInputWidget::ConfigInputWidget(QWidget *parent) : ConfigTaskWidget(parent),wizardStep(wizardNone),transmitterType(heli),loop(NULL),skipflag(false)
|
||||
{
|
||||
manualCommandObj = ManualControlCommand::GetInstance(getObjectManager());
|
||||
manualSettingsObj = ManualControlSettings::GetInstance(getObjectManager());
|
||||
flightStatusObj = FlightStatus::GetInstance(getObjectManager());
|
||||
receiverActivityObj=ReceiverActivity::GetInstance(getObjectManager());
|
||||
m_config = new Ui_InputWidget();
|
||||
m_config->setupUi(this);
|
||||
|
||||
addApplySaveButtons(m_config->saveRCInputToRAM,m_config->saveRCInputToSD);
|
||||
|
||||
ExtensionSystem::PluginManager *pm=ExtensionSystem::PluginManager::instance();
|
||||
Core::Internal::GeneralSettings * settings=pm->getObject<Core::Internal::GeneralSettings>();
|
||||
if(!settings->useExpertMode())
|
||||
m_config->saveRCInputToRAM->setVisible(false);
|
||||
|
||||
addApplySaveButtons(m_config->saveRCInputToRAM,m_config->saveRCInputToSD);
|
||||
|
||||
//Generate the rows of buttons in the input channel form GUI
|
||||
unsigned int index=0;
|
||||
foreach (QString name, manualSettingsObj->getField("ChannelNumber")->getElementNames())
|
||||
{
|
||||
Q_ASSERT(index < ManualControlSettings::CHANNELGROUPS_NUMELEM);
|
||||
inputChannelForm * inpForm=new inputChannelForm(this,index==0);
|
||||
m_config->channelSettings->layout()->addWidget(inpForm); //Add the row to the UI
|
||||
inpForm->setName(name);
|
||||
addUAVObjectToWidgetRelation("ManualControlSettings","ChannelGroups",inpForm->ui->channelGroup,index);
|
||||
addUAVObjectToWidgetRelation("ManualControlSettings","ChannelNumber",inpForm->ui->channelNumber,index);
|
||||
addUAVObjectToWidgetRelation("ManualControlSettings","ChannelMin",inpForm->ui->channelMin,index);
|
||||
addUAVObjectToWidgetRelation("ManualControlSettings","ChannelNeutral",inpForm->ui->channelNeutral,index);
|
||||
addUAVObjectToWidgetRelation("ManualControlSettings","ChannelMax",inpForm->ui->channelMax,index);
|
||||
++index;
|
||||
}
|
||||
|
||||
addUAVObjectToWidgetRelation("ManualControlSettings", "Deadband", m_config->deadband, 0, 0.01f);
|
||||
|
||||
connect(m_config->configurationWizard,SIGNAL(clicked()),this,SLOT(goToWizard()));
|
||||
connect(m_config->stackedWidget,SIGNAL(currentChanged(int)),this,SLOT(disableWizardButton(int)));
|
||||
connect(m_config->runCalibration,SIGNAL(toggled(bool)),this, SLOT(simpleCalibration(bool)));
|
||||
|
||||
connect(m_config->wzNext,SIGNAL(clicked()),this,SLOT(wzNext()));
|
||||
connect(m_config->wzCancel,SIGNAL(clicked()),this,SLOT(wzCancel()));
|
||||
connect(m_config->wzBack,SIGNAL(clicked()),this,SLOT(wzBack()));
|
||||
|
||||
m_config->stackedWidget->setCurrentIndex(0);
|
||||
addUAVObjectToWidgetRelation("ManualControlSettings","FlightModePosition",m_config->fmsModePos1,0,1,true);
|
||||
addUAVObjectToWidgetRelation("ManualControlSettings","FlightModePosition",m_config->fmsModePos2,1,1,true);
|
||||
addUAVObjectToWidgetRelation("ManualControlSettings","FlightModePosition",m_config->fmsModePos3,2,1,true);
|
||||
addUAVObjectToWidgetRelation("ManualControlSettings","FlightModePosition",m_config->fmsModePos4,3,1,true);
|
||||
addUAVObjectToWidgetRelation("ManualControlSettings","FlightModePosition",m_config->fmsModePos5,4,1,true);
|
||||
addUAVObjectToWidgetRelation("ManualControlSettings","FlightModePosition",m_config->fmsModePos6,5,1,true);
|
||||
addUAVObjectToWidgetRelation("ManualControlSettings","FlightModeNumber",m_config->fmsPosNum);
|
||||
|
||||
addUAVObjectToWidgetRelation("ManualControlSettings","Stabilization1Settings",m_config->fmsSsPos1Roll,"Roll");
|
||||
addUAVObjectToWidgetRelation("ManualControlSettings","Stabilization2Settings",m_config->fmsSsPos2Roll,"Roll");
|
||||
addUAVObjectToWidgetRelation("ManualControlSettings","Stabilization3Settings",m_config->fmsSsPos3Roll,"Roll");
|
||||
addUAVObjectToWidgetRelation("ManualControlSettings","Stabilization1Settings",m_config->fmsSsPos1Pitch,"Pitch");
|
||||
addUAVObjectToWidgetRelation("ManualControlSettings","Stabilization2Settings",m_config->fmsSsPos2Pitch,"Pitch");
|
||||
addUAVObjectToWidgetRelation("ManualControlSettings","Stabilization3Settings",m_config->fmsSsPos3Pitch,"Pitch");
|
||||
addUAVObjectToWidgetRelation("ManualControlSettings","Stabilization1Settings",m_config->fmsSsPos1Yaw,"Yaw");
|
||||
addUAVObjectToWidgetRelation("ManualControlSettings","Stabilization2Settings",m_config->fmsSsPos2Yaw,"Yaw");
|
||||
addUAVObjectToWidgetRelation("ManualControlSettings","Stabilization3Settings",m_config->fmsSsPos3Yaw,"Yaw");
|
||||
|
||||
addUAVObjectToWidgetRelation("ManualControlSettings","Arming",m_config->armControl);
|
||||
addUAVObjectToWidgetRelation("ManualControlSettings","ArmedTimeout",m_config->armTimeout,0,1000);
|
||||
connect( ManualControlCommand::GetInstance(getObjectManager()),SIGNAL(objectUpdated(UAVObject*)),this,SLOT(moveFMSlider()));
|
||||
connect( ManualControlSettings::GetInstance(getObjectManager()),SIGNAL(objectUpdated(UAVObject*)),this,SLOT(updatePositionSlider()));
|
||||
enableControls(false);
|
||||
|
||||
populateWidgets();
|
||||
refreshWidgetsValues();
|
||||
// Connect the help button
|
||||
connect(m_config->inputHelp, SIGNAL(clicked()), this, SLOT(openHelp()));
|
||||
|
||||
m_config->graphicsView->setScene(new QGraphicsScene(this));
|
||||
m_config->graphicsView->setViewportUpdateMode(QGraphicsView::FullViewportUpdate);
|
||||
m_renderer = new QSvgRenderer();
|
||||
QGraphicsScene *l_scene = m_config->graphicsView->scene();
|
||||
m_config->graphicsView->setBackgroundBrush(QBrush(Utils::StyleHelper::baseColor()));
|
||||
if (QFile::exists(":/configgadget/images/TX2.svg") && m_renderer->load(QString(":/configgadget/images/TX2.svg")) && m_renderer->isValid())
|
||||
{
|
||||
l_scene->clear(); // Deletes all items contained in the scene as well.
|
||||
|
||||
m_txBackground = new QGraphicsSvgItem();
|
||||
// All other items will be clipped to the shape of the background
|
||||
m_txBackground->setFlags(QGraphicsItem::ItemClipsChildrenToShape|
|
||||
QGraphicsItem::ItemClipsToShape);
|
||||
m_txBackground->setSharedRenderer(m_renderer);
|
||||
m_txBackground->setElementId("background");
|
||||
l_scene->addItem(m_txBackground);
|
||||
|
||||
m_txMainBody = new QGraphicsSvgItem();
|
||||
m_txMainBody->setParentItem(m_txBackground);
|
||||
m_txMainBody->setSharedRenderer(m_renderer);
|
||||
m_txMainBody->setElementId("body");
|
||||
l_scene->addItem(m_txMainBody);
|
||||
|
||||
m_txLeftStick = new QGraphicsSvgItem();
|
||||
m_txLeftStick->setParentItem(m_txBackground);
|
||||
m_txLeftStick->setSharedRenderer(m_renderer);
|
||||
m_txLeftStick->setElementId("ljoy");
|
||||
|
||||
m_txRightStick = new QGraphicsSvgItem();
|
||||
m_txRightStick->setParentItem(m_txBackground);
|
||||
m_txRightStick->setSharedRenderer(m_renderer);
|
||||
m_txRightStick->setElementId("rjoy");
|
||||
|
||||
m_txAccess0 = new QGraphicsSvgItem();
|
||||
m_txAccess0->setParentItem(m_txBackground);
|
||||
m_txAccess0->setSharedRenderer(m_renderer);
|
||||
m_txAccess0->setElementId("access0");
|
||||
|
||||
m_txAccess1 = new QGraphicsSvgItem();
|
||||
m_txAccess1->setParentItem(m_txBackground);
|
||||
m_txAccess1->setSharedRenderer(m_renderer);
|
||||
m_txAccess1->setElementId("access1");
|
||||
|
||||
m_txAccess2 = new QGraphicsSvgItem();
|
||||
m_txAccess2->setParentItem(m_txBackground);
|
||||
m_txAccess2->setSharedRenderer(m_renderer);
|
||||
m_txAccess2->setElementId("access2");
|
||||
|
||||
m_txFlightMode = new QGraphicsSvgItem();
|
||||
m_txFlightMode->setParentItem(m_txBackground);
|
||||
m_txFlightMode->setSharedRenderer(m_renderer);
|
||||
m_txFlightMode->setElementId("flightModeCenter");
|
||||
m_txFlightMode->setZValue(-10);
|
||||
|
||||
m_txArrows = new QGraphicsSvgItem();
|
||||
m_txArrows->setParentItem(m_txBackground);
|
||||
m_txArrows->setSharedRenderer(m_renderer);
|
||||
m_txArrows->setElementId("arrows");
|
||||
m_txArrows->setVisible(false);
|
||||
|
||||
QRectF orig=m_renderer->boundsOnElement("ljoy");
|
||||
QMatrix Matrix = m_renderer->matrixForElement("ljoy");
|
||||
orig=Matrix.mapRect(orig);
|
||||
m_txLeftStickOrig.translate(orig.x(),orig.y());
|
||||
m_txLeftStick->setTransform(m_txLeftStickOrig,false);
|
||||
|
||||
orig=m_renderer->boundsOnElement("arrows");
|
||||
Matrix = m_renderer->matrixForElement("arrows");
|
||||
orig=Matrix.mapRect(orig);
|
||||
m_txArrowsOrig.translate(orig.x(),orig.y());
|
||||
m_txArrows->setTransform(m_txArrowsOrig,false);
|
||||
|
||||
orig=m_renderer->boundsOnElement("body");
|
||||
Matrix = m_renderer->matrixForElement("body");
|
||||
orig=Matrix.mapRect(orig);
|
||||
m_txMainBodyOrig.translate(orig.x(),orig.y());
|
||||
m_txMainBody->setTransform(m_txMainBodyOrig,false);
|
||||
|
||||
orig=m_renderer->boundsOnElement("flightModeCenter");
|
||||
Matrix = m_renderer->matrixForElement("flightModeCenter");
|
||||
orig=Matrix.mapRect(orig);
|
||||
m_txFlightModeCOrig.translate(orig.x(),orig.y());
|
||||
m_txFlightMode->setTransform(m_txFlightModeCOrig,false);
|
||||
|
||||
orig=m_renderer->boundsOnElement("flightModeLeft");
|
||||
Matrix = m_renderer->matrixForElement("flightModeLeft");
|
||||
orig=Matrix.mapRect(orig);
|
||||
m_txFlightModeLOrig.translate(orig.x(),orig.y());
|
||||
orig=m_renderer->boundsOnElement("flightModeRight");
|
||||
Matrix = m_renderer->matrixForElement("flightModeRight");
|
||||
orig=Matrix.mapRect(orig);
|
||||
m_txFlightModeROrig.translate(orig.x(),orig.y());
|
||||
|
||||
orig=m_renderer->boundsOnElement("rjoy");
|
||||
Matrix = m_renderer->matrixForElement("rjoy");
|
||||
orig=Matrix.mapRect(orig);
|
||||
m_txRightStickOrig.translate(orig.x(),orig.y());
|
||||
m_txRightStick->setTransform(m_txRightStickOrig,false);
|
||||
|
||||
orig=m_renderer->boundsOnElement("access0");
|
||||
Matrix = m_renderer->matrixForElement("access0");
|
||||
orig=Matrix.mapRect(orig);
|
||||
m_txAccess0Orig.translate(orig.x(),orig.y());
|
||||
m_txAccess0->setTransform(m_txAccess0Orig,false);
|
||||
|
||||
orig=m_renderer->boundsOnElement("access1");
|
||||
Matrix = m_renderer->matrixForElement("access1");
|
||||
orig=Matrix.mapRect(orig);
|
||||
m_txAccess1Orig.translate(orig.x(),orig.y());
|
||||
m_txAccess1->setTransform(m_txAccess1Orig,false);
|
||||
|
||||
orig=m_renderer->boundsOnElement("access2");
|
||||
Matrix = m_renderer->matrixForElement("access2");
|
||||
orig=Matrix.mapRect(orig);
|
||||
m_txAccess2Orig.translate(orig.x(),orig.y());
|
||||
m_txAccess2->setTransform(m_txAccess2Orig,true);
|
||||
}
|
||||
m_config->graphicsView->fitInView(m_txMainBody, Qt::KeepAspectRatio );
|
||||
animate=new QTimer(this);
|
||||
connect(animate,SIGNAL(timeout()),this,SLOT(moveTxControls()));
|
||||
|
||||
heliChannelOrder << ManualControlSettings::CHANNELGROUPS_COLLECTIVE <<
|
||||
ManualControlSettings::CHANNELGROUPS_THROTTLE <<
|
||||
ManualControlSettings::CHANNELGROUPS_ROLL <<
|
||||
ManualControlSettings::CHANNELGROUPS_PITCH <<
|
||||
ManualControlSettings::CHANNELGROUPS_YAW <<
|
||||
ManualControlSettings::CHANNELGROUPS_FLIGHTMODE <<
|
||||
ManualControlSettings::CHANNELGROUPS_ACCESSORY0 <<
|
||||
ManualControlSettings::CHANNELGROUPS_ACCESSORY1 <<
|
||||
ManualControlSettings::CHANNELGROUPS_ACCESSORY2;
|
||||
|
||||
acroChannelOrder << ManualControlSettings::CHANNELGROUPS_THROTTLE <<
|
||||
ManualControlSettings::CHANNELGROUPS_ROLL <<
|
||||
ManualControlSettings::CHANNELGROUPS_PITCH <<
|
||||
ManualControlSettings::CHANNELGROUPS_YAW <<
|
||||
ManualControlSettings::CHANNELGROUPS_FLIGHTMODE <<
|
||||
ManualControlSettings::CHANNELGROUPS_ACCESSORY0 <<
|
||||
ManualControlSettings::CHANNELGROUPS_ACCESSORY1 <<
|
||||
ManualControlSettings::CHANNELGROUPS_ACCESSORY2;
|
||||
}
|
||||
void ConfigInputWidget::resetTxControls()
|
||||
{
|
||||
|
||||
m_txLeftStick->setTransform(m_txLeftStickOrig,false);
|
||||
m_txRightStick->setTransform(m_txRightStickOrig,false);
|
||||
m_txAccess0->setTransform(m_txAccess0Orig,false);
|
||||
m_txAccess1->setTransform(m_txAccess1Orig,false);
|
||||
m_txAccess2->setTransform(m_txAccess2Orig,false);
|
||||
m_txFlightMode->setElementId("flightModeCenter");
|
||||
m_txFlightMode->setTransform(m_txFlightModeCOrig,false);
|
||||
m_txArrows->setVisible(false);
|
||||
}
|
||||
|
||||
ConfigInputWidget::~ConfigInputWidget()
|
||||
{
|
||||
|
||||
}
|
||||
|
||||
void ConfigInputWidget::resizeEvent(QResizeEvent *event)
|
||||
{
|
||||
QWidget::resizeEvent(event);
|
||||
m_config->graphicsView->fitInView(m_txBackground, Qt::KeepAspectRatio );
|
||||
}
|
||||
|
||||
void ConfigInputWidget::openHelp()
|
||||
{
|
||||
QDesktopServices::openUrl( QUrl("http://wiki.openpilot.org/x/04Cf", QUrl::StrictMode) );
|
||||
}
|
||||
|
||||
void ConfigInputWidget::goToWizard()
|
||||
{
|
||||
QMessageBox msgBox;
|
||||
msgBox.setText(tr("Arming Settings are now set to Always Disarmed for your safety."));
|
||||
msgBox.setDetailedText(tr("You will have to reconfigure the arming settings manually "
|
||||
"when the wizard is finished. After the last step of the "
|
||||
"wizard you will be taken to the Arming Settings screen."));
|
||||
msgBox.setStandardButtons(QMessageBox::Ok);
|
||||
msgBox.setDefaultButton(QMessageBox::Ok);
|
||||
msgBox.exec();
|
||||
|
||||
// Set correct tab visible before starting wizard.
|
||||
if(m_config->tabWidget->currentIndex() != 0) {
|
||||
m_config->tabWidget->setCurrentIndex(0);
|
||||
}
|
||||
wizardSetUpStep(wizardWelcome);
|
||||
m_config->graphicsView->fitInView(m_txBackground, Qt::KeepAspectRatio );
|
||||
}
|
||||
|
||||
void ConfigInputWidget::disableWizardButton(int value)
|
||||
{
|
||||
if(value!=0)
|
||||
m_config->configurationWizard->setVisible(false);
|
||||
else
|
||||
m_config->configurationWizard->setVisible(true);
|
||||
}
|
||||
|
||||
void ConfigInputWidget::wzCancel()
|
||||
{
|
||||
dimOtherControls(false);
|
||||
manualCommandObj->setMetadata(manualCommandObj->getDefaultMetadata());
|
||||
m_config->stackedWidget->setCurrentIndex(0);
|
||||
|
||||
if(wizardStep != wizardNone)
|
||||
wizardTearDownStep(wizardStep);
|
||||
wizardStep=wizardNone;
|
||||
m_config->stackedWidget->setCurrentIndex(0);
|
||||
|
||||
// Load settings back from beginning of wizard
|
||||
manualSettingsObj->setData(previousManualSettingsData);
|
||||
}
|
||||
|
||||
void ConfigInputWidget::wzNext()
|
||||
{
|
||||
// In identify sticks mode the next button can indicate
|
||||
// channel advance
|
||||
if(wizardStep != wizardNone &&
|
||||
wizardStep != wizardIdentifySticks)
|
||||
wizardTearDownStep(wizardStep);
|
||||
|
||||
// State transitions for next button
|
||||
switch(wizardStep) {
|
||||
case wizardWelcome:
|
||||
wizardSetUpStep(wizardChooseMode);
|
||||
break;
|
||||
case wizardChooseMode:
|
||||
wizardSetUpStep(wizardChooseType);
|
||||
break;
|
||||
case wizardChooseType:
|
||||
wizardSetUpStep(wizardIdentifySticks);
|
||||
break;
|
||||
case wizardIdentifySticks:
|
||||
nextChannel();
|
||||
if(currentChannelNum==-1) { // Gone through all channels
|
||||
wizardTearDownStep(wizardIdentifySticks);
|
||||
wizardSetUpStep(wizardIdentifyCenter);
|
||||
}
|
||||
break;
|
||||
case wizardIdentifyCenter:
|
||||
wizardSetUpStep(wizardIdentifyLimits);
|
||||
break;
|
||||
case wizardIdentifyLimits:
|
||||
wizardSetUpStep(wizardIdentifyInverted);
|
||||
break;
|
||||
case wizardIdentifyInverted:
|
||||
wizardSetUpStep(wizardFinish);
|
||||
break;
|
||||
case wizardFinish:
|
||||
wizardStep=wizardNone;
|
||||
m_config->stackedWidget->setCurrentIndex(0);
|
||||
m_config->tabWidget->setCurrentIndex(2);
|
||||
break;
|
||||
default:
|
||||
Q_ASSERT(0);
|
||||
}
|
||||
}
|
||||
|
||||
void ConfigInputWidget::wzBack()
|
||||
{
|
||||
if(wizardStep != wizardNone &&
|
||||
wizardStep != wizardIdentifySticks)
|
||||
wizardTearDownStep(wizardStep);
|
||||
|
||||
// State transitions for next button
|
||||
switch(wizardStep) {
|
||||
case wizardChooseMode:
|
||||
wizardSetUpStep(wizardWelcome);
|
||||
break;
|
||||
case wizardChooseType:
|
||||
wizardSetUpStep(wizardChooseMode);
|
||||
break;
|
||||
case wizardIdentifySticks:
|
||||
prevChannel();
|
||||
if(currentChannelNum == -1) {
|
||||
wizardTearDownStep(wizardIdentifySticks);
|
||||
wizardSetUpStep(wizardChooseType);
|
||||
}
|
||||
break;
|
||||
case wizardIdentifyCenter:
|
||||
wizardSetUpStep(wizardIdentifySticks);
|
||||
break;
|
||||
case wizardIdentifyLimits:
|
||||
wizardSetUpStep(wizardIdentifyCenter);
|
||||
break;
|
||||
case wizardIdentifyInverted:
|
||||
wizardSetUpStep(wizardIdentifyLimits);
|
||||
break;
|
||||
case wizardFinish:
|
||||
wizardSetUpStep(wizardIdentifyInverted);
|
||||
break;
|
||||
default:
|
||||
Q_ASSERT(0);
|
||||
}
|
||||
}
|
||||
|
||||
void ConfigInputWidget::wizardSetUpStep(enum wizardSteps step)
|
||||
{
|
||||
switch(step) {
|
||||
case wizardWelcome:
|
||||
foreach(QPointer<QWidget> wd,extraWidgets)
|
||||
{
|
||||
if(!wd.isNull())
|
||||
delete wd;
|
||||
}
|
||||
extraWidgets.clear();
|
||||
m_config->graphicsView->setVisible(false);
|
||||
setTxMovement(nothing);
|
||||
manualSettingsData=manualSettingsObj->getData();
|
||||
manualSettingsData.Arming=ManualControlSettings::ARMING_ALWAYSDISARMED;
|
||||
previousManualSettingsData = manualSettingsData;
|
||||
manualSettingsObj->setData(manualSettingsData);
|
||||
m_config->wzText->setText(tr("Welcome to the inputs configuration wizard.\n"
|
||||
"Please follow the instructions on the screen and only move your controls when asked to.\n"
|
||||
"Make sure you already configured your hardware settings on the proper tab and restarted your board.\n"
|
||||
"You can press 'back' at any time to return to the previous screeen or press 'Cancel' to quit the wizard.\n"));
|
||||
m_config->stackedWidget->setCurrentIndex(1);
|
||||
m_config->wzBack->setEnabled(false);
|
||||
break;
|
||||
case wizardChooseMode:
|
||||
{
|
||||
m_config->graphicsView->setVisible(true);
|
||||
m_config->graphicsView->fitInView(m_txBackground, Qt::KeepAspectRatio );
|
||||
setTxMovement(nothing);
|
||||
m_config->wzText->setText(tr("Please choose your transmitter type.\n"
|
||||
"Mode 1 means your throttle stick is on the right.\n"
|
||||
"Mode 2 means your throttle stick is on the left.\n"));
|
||||
m_config->wzBack->setEnabled(true);
|
||||
QRadioButton * mode1=new QRadioButton(tr("Mode 1"),this);
|
||||
QRadioButton * mode2=new QRadioButton(tr("Mode 2"),this);
|
||||
mode2->setChecked(true);
|
||||
extraWidgets.clear();
|
||||
extraWidgets.append(mode1);
|
||||
extraWidgets.append(mode2);
|
||||
m_config->checkBoxesLayout->layout()->addWidget(mode1);
|
||||
m_config->checkBoxesLayout->layout()->addWidget(mode2);
|
||||
}
|
||||
break;
|
||||
case wizardChooseType:
|
||||
{
|
||||
m_config->wzText->setText(tr("Please choose your transmitter mode.\n"
|
||||
"Acro means normal transmitter.\n"
|
||||
"Heli means there is a collective pitch and throttle input.\n"
|
||||
"If you are using a heli transmitter please engage throttle hold now.\n"));
|
||||
m_config->wzBack->setEnabled(true);
|
||||
QRadioButton * typeAcro=new QRadioButton(tr("Acro"),this);
|
||||
QRadioButton * typeHeli=new QRadioButton(tr("Heli"),this);
|
||||
typeAcro->setChecked(true);
|
||||
typeHeli->setChecked(false);
|
||||
extraWidgets.clear();
|
||||
extraWidgets.append(typeAcro);
|
||||
extraWidgets.append(typeHeli);
|
||||
m_config->checkBoxesLayout->layout()->addWidget(typeAcro);
|
||||
m_config->checkBoxesLayout->layout()->addWidget(typeHeli);
|
||||
wizardStep=wizardChooseType;
|
||||
}
|
||||
break;
|
||||
case wizardIdentifySticks:
|
||||
usedChannels.clear();
|
||||
currentChannelNum=-1;
|
||||
nextChannel();
|
||||
manualSettingsData=manualSettingsObj->getData();
|
||||
connect(receiverActivityObj, SIGNAL(objectUpdated(UAVObject*)), this, SLOT(identifyControls()));
|
||||
m_config->wzNext->setEnabled(false);
|
||||
break;
|
||||
case wizardIdentifyCenter:
|
||||
setTxMovement(centerAll);
|
||||
m_config->wzText->setText(QString(tr("Please center all controls and press next when ready (if your FlightMode switch has only two positions, leave it in either position).")));
|
||||
break;
|
||||
case wizardIdentifyLimits:
|
||||
{
|
||||
accessoryDesiredObj0 = AccessoryDesired::GetInstance(getObjectManager(),0);
|
||||
accessoryDesiredObj1 = AccessoryDesired::GetInstance(getObjectManager(),1);
|
||||
accessoryDesiredObj2 = AccessoryDesired::GetInstance(getObjectManager(),2);
|
||||
setTxMovement(nothing);
|
||||
m_config->wzText->setText(QString(tr("Please move all controls to their maximum extents on both directions and press next when ready.")));
|
||||
fastMdata();
|
||||
manualSettingsData=manualSettingsObj->getData();
|
||||
for(uint i=0;i<ManualControlSettings::CHANNELMAX_NUMELEM;++i)
|
||||
{
|
||||
// Preserve the inverted status
|
||||
if(manualSettingsData.ChannelMin[i] <= manualSettingsData.ChannelMax[i]) {
|
||||
manualSettingsData.ChannelMin[i]=manualSettingsData.ChannelNeutral[i];
|
||||
manualSettingsData.ChannelMax[i]=manualSettingsData.ChannelNeutral[i];
|
||||
} else {
|
||||
// Make this detect as still inverted
|
||||
manualSettingsData.ChannelMin[i]=manualSettingsData.ChannelNeutral[i] + 1;
|
||||
manualSettingsData.ChannelMax[i]=manualSettingsData.ChannelNeutral[i];
|
||||
}
|
||||
}
|
||||
connect(manualCommandObj, SIGNAL(objectUpdated(UAVObject*)), this, SLOT(identifyLimits()));
|
||||
connect(manualCommandObj, SIGNAL(objectUpdated(UAVObject*)), this, SLOT(moveSticks()));
|
||||
connect(flightStatusObj, SIGNAL(objectUpdated(UAVObject*)), this, SLOT(moveSticks()));
|
||||
connect(accessoryDesiredObj0, SIGNAL(objectUpdated(UAVObject*)), this, SLOT(moveSticks()));
|
||||
}
|
||||
break;
|
||||
case wizardIdentifyInverted:
|
||||
dimOtherControls(true);
|
||||
setTxMovement(nothing);
|
||||
extraWidgets.clear();
|
||||
|
||||
for (int index = 0; index < manualSettingsObj->getField("ChannelMax")->getElementNames().length(); index++)
|
||||
{
|
||||
QString name = manualSettingsObj->getField("ChannelMax")->getElementNames().at(index);
|
||||
if(!name.contains("Access") && !name.contains("Flight"))
|
||||
{
|
||||
QCheckBox * cb=new QCheckBox(name,this);
|
||||
// Make sure checked status matches current one
|
||||
cb->setChecked(manualSettingsData.ChannelMax[index] < manualSettingsData.ChannelMin[index]);
|
||||
|
||||
extraWidgets.append(cb);
|
||||
m_config->checkBoxesLayout->layout()->addWidget(cb);
|
||||
|
||||
connect(cb,SIGNAL(toggled(bool)),this,SLOT(invertControls()));
|
||||
}
|
||||
}
|
||||
connect(manualCommandObj, SIGNAL(objectUpdated(UAVObject*)), this, SLOT(moveSticks()));
|
||||
m_config->wzText->setText(QString(tr("Please check the picture below and correct all the sticks which show an inverted movement, press next when ready.")));
|
||||
fastMdata();
|
||||
break;
|
||||
case wizardFinish:
|
||||
dimOtherControls(false);
|
||||
connect(manualCommandObj, SIGNAL(objectUpdated(UAVObject*)), this, SLOT(moveSticks()));
|
||||
connect(flightStatusObj, SIGNAL(objectUpdated(UAVObject*)), this, SLOT(moveSticks()));
|
||||
connect(accessoryDesiredObj0, SIGNAL(objectUpdated(UAVObject*)), this, SLOT(moveSticks()));
|
||||
m_config->wzText->setText(QString(tr("You have completed this wizard, please check below if the picture mimics your sticks movement.\n"
|
||||
"These new settings aren't saved to the board yet, after pressing next you will go to the Arming Settings "
|
||||
"screen where you can set your desired arming sequence and save the configuration.")));
|
||||
fastMdata();
|
||||
|
||||
manualSettingsData.ChannelNeutral[ManualControlSettings::CHANNELNEUTRAL_THROTTLE]=
|
||||
manualSettingsData.ChannelMin[ManualControlSettings::CHANNELMIN_THROTTLE]+
|
||||
((manualSettingsData.ChannelMax[ManualControlSettings::CHANNELMAX_THROTTLE]-
|
||||
manualSettingsData.ChannelMin[ManualControlSettings::CHANNELMIN_THROTTLE])*0.02);
|
||||
if((abs(manualSettingsData.ChannelMax[ManualControlSettings::CHANNELMAX_FLIGHTMODE]-manualSettingsData.ChannelNeutral[ManualControlSettings::CHANNELNEUTRAL_FLIGHTMODE])<100) ||
|
||||
(abs(manualSettingsData.ChannelMin[ManualControlSettings::CHANNELMIN_FLIGHTMODE]-manualSettingsData.ChannelNeutral[ManualControlSettings::CHANNELNEUTRAL_FLIGHTMODE])<100))
|
||||
{
|
||||
manualSettingsData.ChannelNeutral[ManualControlSettings::CHANNELNEUTRAL_FLIGHTMODE]=manualSettingsData.ChannelMin[ManualControlSettings::CHANNELMIN_FLIGHTMODE]+
|
||||
(manualSettingsData.ChannelMax[ManualControlSettings::CHANNELMAX_FLIGHTMODE]-manualSettingsData.ChannelMin[ManualControlSettings::CHANNELMIN_FLIGHTMODE])/2;
|
||||
}
|
||||
manualSettingsObj->setData(manualSettingsData);
|
||||
break;
|
||||
default:
|
||||
Q_ASSERT(0);
|
||||
}
|
||||
wizardStep = step;
|
||||
}
|
||||
|
||||
void ConfigInputWidget::wizardTearDownStep(enum wizardSteps step)
|
||||
{
|
||||
QRadioButton * mode, * type;
|
||||
Q_ASSERT(step == wizardStep);
|
||||
switch(step) {
|
||||
case wizardWelcome:
|
||||
break;
|
||||
case wizardChooseMode:
|
||||
mode=qobject_cast<QRadioButton *>(extraWidgets.at(0));
|
||||
if(mode->isChecked())
|
||||
transmitterMode=mode1;
|
||||
else
|
||||
transmitterMode=mode2;
|
||||
delete extraWidgets.at(0);
|
||||
delete extraWidgets.at(1);
|
||||
extraWidgets.clear();
|
||||
break;
|
||||
case wizardChooseType:
|
||||
type=qobject_cast<QRadioButton *>(extraWidgets.at(0));
|
||||
if(type->isChecked())
|
||||
transmitterType=acro;
|
||||
else
|
||||
transmitterType=heli;
|
||||
delete extraWidgets.at(0);
|
||||
delete extraWidgets.at(1);
|
||||
extraWidgets.clear();
|
||||
break;
|
||||
case wizardIdentifySticks:
|
||||
disconnect(receiverActivityObj, SIGNAL(objectUpdated(UAVObject*)), this, SLOT(identifyControls()));
|
||||
m_config->wzNext->setEnabled(true);
|
||||
setTxMovement(nothing);
|
||||
break;
|
||||
case wizardIdentifyCenter:
|
||||
manualCommandData=manualCommandObj->getData();
|
||||
manualSettingsData=manualSettingsObj->getData();
|
||||
for(unsigned int i=0;i<ManualControlCommand::CHANNEL_NUMELEM;++i)
|
||||
{
|
||||
manualSettingsData.ChannelNeutral[i]=manualCommandData.Channel[i];
|
||||
}
|
||||
manualSettingsObj->setData(manualSettingsData);
|
||||
setTxMovement(nothing);
|
||||
break;
|
||||
case wizardIdentifyLimits:
|
||||
disconnect(manualCommandObj, SIGNAL(objectUpdated(UAVObject*)), this, SLOT(identifyLimits()));
|
||||
disconnect(manualCommandObj, SIGNAL(objectUpdated(UAVObject*)), this, SLOT(moveSticks()));
|
||||
disconnect(flightStatusObj, SIGNAL(objectUpdated(UAVObject*)), this, SLOT(moveSticks()));
|
||||
disconnect(accessoryDesiredObj0, SIGNAL(objectUpdated(UAVObject*)), this, SLOT(moveSticks()));
|
||||
manualSettingsObj->setData(manualSettingsData);
|
||||
restoreMdata();
|
||||
setTxMovement(nothing);
|
||||
break;
|
||||
case wizardIdentifyInverted:
|
||||
dimOtherControls(false);
|
||||
foreach(QWidget * wd,extraWidgets)
|
||||
{
|
||||
QCheckBox * cb=qobject_cast<QCheckBox *>(wd);
|
||||
if(cb)
|
||||
{
|
||||
disconnect(cb,SIGNAL(toggled(bool)),this,SLOT(invertControls()));
|
||||
delete cb;
|
||||
}
|
||||
}
|
||||
extraWidgets.clear();
|
||||
disconnect(manualCommandObj, SIGNAL(objectUpdated(UAVObject*)), this, SLOT(moveSticks()));
|
||||
restoreMdata();
|
||||
break;
|
||||
case wizardFinish:
|
||||
dimOtherControls(false);
|
||||
setTxMovement(nothing);
|
||||
disconnect(manualCommandObj, SIGNAL(objectUpdated(UAVObject*)), this, SLOT(moveSticks()));
|
||||
disconnect(flightStatusObj, SIGNAL(objectUpdated(UAVObject*)), this, SLOT(moveSticks()));
|
||||
disconnect(accessoryDesiredObj0, SIGNAL(objectUpdated(UAVObject*)), this, SLOT(moveSticks()));
|
||||
restoreMdata();
|
||||
break;
|
||||
default:
|
||||
Q_ASSERT(0);
|
||||
}
|
||||
}
|
||||
|
||||
/**
|
||||
* Set manual control command to fast updates
|
||||
*/
|
||||
void ConfigInputWidget::fastMdata()
|
||||
{
|
||||
manualControlMdata = manualCommandObj->getMetadata();
|
||||
UAVObject::Metadata mdata = manualControlMdata;
|
||||
UAVObject::SetFlightTelemetryUpdateMode(mdata, UAVObject::UPDATEMODE_PERIODIC);
|
||||
mdata.flightTelemetryUpdatePeriod = 150;
|
||||
manualCommandObj->setMetadata(mdata);
|
||||
}
|
||||
|
||||
/**
|
||||
* Restore previous update settings for manual control data
|
||||
*/
|
||||
void ConfigInputWidget::restoreMdata()
|
||||
{
|
||||
manualCommandObj->setMetadata(manualControlMdata);
|
||||
}
|
||||
|
||||
/**
|
||||
* Set the display to indicate which channel the person should move
|
||||
*/
|
||||
void ConfigInputWidget::setChannel(int newChan)
|
||||
{
|
||||
if(newChan == ManualControlSettings::CHANNELGROUPS_COLLECTIVE)
|
||||
m_config->wzText->setText(QString(tr("Please enable the throttle hold mode and move the collective pitch stick.")));
|
||||
else if (newChan == ManualControlSettings::CHANNELGROUPS_FLIGHTMODE)
|
||||
m_config->wzText->setText(QString(tr("Please toggle the flight mode switch. For switches you may have to repeat this rapidly.")));
|
||||
else if((transmitterType == heli) && (newChan == ManualControlSettings::CHANNELGROUPS_THROTTLE))
|
||||
m_config->wzText->setText(QString(tr("Please disable throttle hold mode and move the throttle stick.")));
|
||||
else
|
||||
m_config->wzText->setText(QString(tr("Please move each control once at a time according to the instructions and picture below.\n\n"
|
||||
"Move the %1 stick")).arg(manualSettingsObj->getField("ChannelGroups")->getElementNames().at(newChan)));
|
||||
|
||||
if(manualSettingsObj->getField("ChannelGroups")->getElementNames().at(newChan).contains("Accessory") ||
|
||||
manualSettingsObj->getField("ChannelGroups")->getElementNames().at(newChan).contains("FlightMode")) {
|
||||
m_config->wzNext->setEnabled(true);
|
||||
m_config->wzText->setText(m_config->wzText->text() + tr(" or click next to skip this channel."));
|
||||
} else
|
||||
m_config->wzNext->setEnabled(false);
|
||||
|
||||
setMoveFromCommand(newChan);
|
||||
|
||||
currentChannelNum = newChan;
|
||||
channelDetected = false;
|
||||
}
|
||||
|
||||
/**
|
||||
* Unfortunately order of channel should be different in different conditions. Selects
|
||||
* next channel based on heli or acro mode
|
||||
*/
|
||||
void ConfigInputWidget::nextChannel()
|
||||
{
|
||||
QList <int> order = (transmitterType == heli) ? heliChannelOrder : acroChannelOrder;
|
||||
|
||||
if(currentChannelNum == -1) {
|
||||
setChannel(order[0]);
|
||||
return;
|
||||
}
|
||||
for (int i = 0; i < order.length() - 1; i++) {
|
||||
if(order[i] == currentChannelNum) {
|
||||
setChannel(order[i+1]);
|
||||
return;
|
||||
}
|
||||
}
|
||||
currentChannelNum = -1; // hit end of list
|
||||
}
|
||||
|
||||
/**
|
||||
* Unfortunately order of channel should be different in different conditions. Selects
|
||||
* previous channel based on heli or acro mode
|
||||
*/
|
||||
void ConfigInputWidget::prevChannel()
|
||||
{
|
||||
QList <int> order = transmitterType == heli ? heliChannelOrder : acroChannelOrder;
|
||||
|
||||
// No previous from unset channel or next state
|
||||
if(currentChannelNum == -1)
|
||||
return;
|
||||
|
||||
for (int i = 1; i < order.length(); i++) {
|
||||
if(order[i] == currentChannelNum) {
|
||||
setChannel(order[i-1]);
|
||||
usedChannels.removeLast();
|
||||
return;
|
||||
}
|
||||
}
|
||||
currentChannelNum = -1; // hit end of list
|
||||
}
|
||||
|
||||
void ConfigInputWidget::identifyControls()
|
||||
{
|
||||
static int debounce=0;
|
||||
|
||||
receiverActivityData=receiverActivityObj->getData();
|
||||
if(receiverActivityData.ActiveChannel==255)
|
||||
return;
|
||||
if(channelDetected)
|
||||
return;
|
||||
else
|
||||
{
|
||||
receiverActivityData=receiverActivityObj->getData();
|
||||
currentChannel.group=receiverActivityData.ActiveGroup;
|
||||
currentChannel.number=receiverActivityData.ActiveChannel;
|
||||
if(currentChannel==lastChannel)
|
||||
++debounce;
|
||||
lastChannel.group= currentChannel.group;
|
||||
lastChannel.number=currentChannel.number;
|
||||
if(!usedChannels.contains(lastChannel) && debounce>1)
|
||||
{
|
||||
channelDetected = true;
|
||||
debounce=0;
|
||||
usedChannels.append(lastChannel);
|
||||
manualSettingsData=manualSettingsObj->getData();
|
||||
manualSettingsData.ChannelGroups[currentChannelNum]=currentChannel.group;
|
||||
manualSettingsData.ChannelNumber[currentChannelNum]=currentChannel.number;
|
||||
manualSettingsObj->setData(manualSettingsData);
|
||||
}
|
||||
else
|
||||
return;
|
||||
}
|
||||
|
||||
m_config->wzText->clear();
|
||||
setTxMovement(nothing);
|
||||
|
||||
QTimer::singleShot(2500, this, SLOT(wzNext()));
|
||||
}
|
||||
|
||||
void ConfigInputWidget::identifyLimits()
|
||||
{
|
||||
manualCommandData=manualCommandObj->getData();
|
||||
for(uint i=0;i<ManualControlSettings::CHANNELMAX_NUMELEM;++i)
|
||||
{
|
||||
if(manualSettingsData.ChannelMin[i] <= manualSettingsData.ChannelMax[i]) {
|
||||
// Non inverted channel
|
||||
if(manualSettingsData.ChannelMin[i]>manualCommandData.Channel[i])
|
||||
manualSettingsData.ChannelMin[i]=manualCommandData.Channel[i];
|
||||
if(manualSettingsData.ChannelMax[i]<manualCommandData.Channel[i])
|
||||
manualSettingsData.ChannelMax[i]=manualCommandData.Channel[i];
|
||||
} else {
|
||||
// Inverted channel
|
||||
if(manualSettingsData.ChannelMax[i]>manualCommandData.Channel[i])
|
||||
manualSettingsData.ChannelMax[i]=manualCommandData.Channel[i];
|
||||
if(manualSettingsData.ChannelMin[i]<manualCommandData.Channel[i])
|
||||
manualSettingsData.ChannelMin[i]=manualCommandData.Channel[i];
|
||||
}
|
||||
}
|
||||
manualSettingsObj->setData(manualSettingsData);
|
||||
}
|
||||
void ConfigInputWidget::setMoveFromCommand(int command)
|
||||
{
|
||||
//CHANNELNUMBER_ROLL=0, CHANNELNUMBER_PITCH=1, CHANNELNUMBER_YAW=2, CHANNELNUMBER_THROTTLE=3, CHANNELNUMBER_FLIGHTMODE=4, CHANNELNUMBER_ACCESSORY0=5, CHANNELNUMBER_ACCESSORY1=6, CHANNELNUMBER_ACCESSORY2=7 } ChannelNumberElem;
|
||||
if(command==ManualControlSettings::CHANNELNUMBER_ROLL)
|
||||
{
|
||||
setTxMovement(moveRightHorizontalStick);
|
||||
}
|
||||
else if(command==ManualControlSettings::CHANNELNUMBER_PITCH)
|
||||
{
|
||||
if(transmitterMode==mode2)
|
||||
setTxMovement(moveRightVerticalStick);
|
||||
else
|
||||
setTxMovement(moveLeftVerticalStick);
|
||||
}
|
||||
else if(command==ManualControlSettings::CHANNELNUMBER_YAW)
|
||||
{
|
||||
setTxMovement(moveLeftHorizontalStick);
|
||||
}
|
||||
else if(command==ManualControlSettings::CHANNELNUMBER_THROTTLE)
|
||||
{
|
||||
if(transmitterMode==mode2)
|
||||
setTxMovement(moveLeftVerticalStick);
|
||||
else
|
||||
setTxMovement(moveRightVerticalStick);
|
||||
}
|
||||
else if(command==ManualControlSettings::CHANNELNUMBER_COLLECTIVE)
|
||||
{
|
||||
if(transmitterMode==mode2)
|
||||
setTxMovement(moveLeftVerticalStick);
|
||||
else
|
||||
setTxMovement(moveRightVerticalStick);
|
||||
}
|
||||
else if(command==ManualControlSettings::CHANNELNUMBER_FLIGHTMODE)
|
||||
{
|
||||
setTxMovement(moveFlightMode);
|
||||
}
|
||||
else if(command==ManualControlSettings::CHANNELNUMBER_ACCESSORY0)
|
||||
{
|
||||
setTxMovement(moveAccess0);
|
||||
}
|
||||
else if(command==ManualControlSettings::CHANNELNUMBER_ACCESSORY1)
|
||||
{
|
||||
setTxMovement(moveAccess1);
|
||||
}
|
||||
else if(command==ManualControlSettings::CHANNELNUMBER_ACCESSORY2)
|
||||
{
|
||||
setTxMovement(moveAccess2);
|
||||
}
|
||||
|
||||
}
|
||||
|
||||
void ConfigInputWidget::setTxMovement(txMovements movement)
|
||||
{
|
||||
resetTxControls();
|
||||
switch(movement)
|
||||
{
|
||||
case moveLeftVerticalStick:
|
||||
movePos=0;
|
||||
growing=true;
|
||||
currentMovement=moveLeftVerticalStick;
|
||||
animate->start(100);
|
||||
break;
|
||||
case moveRightVerticalStick:
|
||||
movePos=0;
|
||||
growing=true;
|
||||
currentMovement=moveRightVerticalStick;
|
||||
animate->start(100);
|
||||
break;
|
||||
case moveLeftHorizontalStick:
|
||||
movePos=0;
|
||||
growing=true;
|
||||
currentMovement=moveLeftHorizontalStick;
|
||||
animate->start(100);
|
||||
break;
|
||||
case moveRightHorizontalStick:
|
||||
movePos=0;
|
||||
growing=true;
|
||||
currentMovement=moveRightHorizontalStick;
|
||||
animate->start(100);
|
||||
break;
|
||||
case moveAccess0:
|
||||
movePos=0;
|
||||
growing=true;
|
||||
currentMovement=moveAccess0;
|
||||
animate->start(100);
|
||||
break;
|
||||
case moveAccess1:
|
||||
movePos=0;
|
||||
growing=true;
|
||||
currentMovement=moveAccess1;
|
||||
animate->start(100);
|
||||
break;
|
||||
case moveAccess2:
|
||||
movePos=0;
|
||||
growing=true;
|
||||
currentMovement=moveAccess2;
|
||||
animate->start(100);
|
||||
break;
|
||||
case moveFlightMode:
|
||||
movePos=0;
|
||||
growing=true;
|
||||
currentMovement=moveFlightMode;
|
||||
animate->start(1000);
|
||||
break;
|
||||
case centerAll:
|
||||
movePos=0;
|
||||
currentMovement=centerAll;
|
||||
animate->start(1000);
|
||||
break;
|
||||
case moveAll:
|
||||
movePos=0;
|
||||
growing=true;
|
||||
currentMovement=moveAll;
|
||||
animate->start(50);
|
||||
break;
|
||||
case nothing:
|
||||
movePos=0;
|
||||
animate->stop();
|
||||
break;
|
||||
default:
|
||||
break;
|
||||
}
|
||||
}
|
||||
|
||||
void ConfigInputWidget::moveTxControls()
|
||||
{
|
||||
QTransform trans;
|
||||
QGraphicsItem * item;
|
||||
txMovementType move;
|
||||
int limitMax;
|
||||
int limitMin;
|
||||
static bool auxFlag=false;
|
||||
switch(currentMovement)
|
||||
{
|
||||
case moveLeftVerticalStick:
|
||||
item=m_txLeftStick;
|
||||
trans=m_txLeftStickOrig;
|
||||
limitMax=STICK_MAX_MOVE;
|
||||
limitMin=STICK_MIN_MOVE;
|
||||
move=vertical;
|
||||
break;
|
||||
case moveRightVerticalStick:
|
||||
item=m_txRightStick;
|
||||
trans=m_txRightStickOrig;
|
||||
limitMax=STICK_MAX_MOVE;
|
||||
limitMin=STICK_MIN_MOVE;
|
||||
move=vertical;
|
||||
break;
|
||||
case moveLeftHorizontalStick:
|
||||
item=m_txLeftStick;
|
||||
trans=m_txLeftStickOrig;
|
||||
limitMax=STICK_MAX_MOVE;
|
||||
limitMin=STICK_MIN_MOVE;
|
||||
move=horizontal;
|
||||
break;
|
||||
case moveRightHorizontalStick:
|
||||
item=m_txRightStick;
|
||||
trans=m_txRightStickOrig;
|
||||
limitMax=STICK_MAX_MOVE;
|
||||
limitMin=STICK_MIN_MOVE;
|
||||
move=horizontal;
|
||||
break;
|
||||
case moveAccess0:
|
||||
item=m_txAccess0;
|
||||
trans=m_txAccess0Orig;
|
||||
limitMax=ACCESS_MAX_MOVE;
|
||||
limitMin=ACCESS_MIN_MOVE;
|
||||
move=horizontal;
|
||||
break;
|
||||
case moveAccess1:
|
||||
item=m_txAccess1;
|
||||
trans=m_txAccess1Orig;
|
||||
limitMax=ACCESS_MAX_MOVE;
|
||||
limitMin=ACCESS_MIN_MOVE;
|
||||
move=horizontal;
|
||||
break;
|
||||
case moveAccess2:
|
||||
item=m_txAccess2;
|
||||
trans=m_txAccess2Orig;
|
||||
limitMax=ACCESS_MAX_MOVE;
|
||||
limitMin=ACCESS_MIN_MOVE;
|
||||
move=horizontal;
|
||||
break;
|
||||
case moveFlightMode:
|
||||
item=m_txFlightMode;
|
||||
move=jump;
|
||||
break;
|
||||
case centerAll:
|
||||
item=m_txArrows;
|
||||
move=jump;
|
||||
break;
|
||||
case moveAll:
|
||||
limitMax=STICK_MAX_MOVE;
|
||||
limitMin=STICK_MIN_MOVE;
|
||||
move=mix;
|
||||
break;
|
||||
default:
|
||||
break;
|
||||
}
|
||||
if(move==vertical)
|
||||
item->setTransform(trans.translate(0,movePos*10),false);
|
||||
else if(move==horizontal)
|
||||
item->setTransform(trans.translate(movePos*10,0),false);
|
||||
else if(move==jump)
|
||||
{
|
||||
if(item==m_txArrows)
|
||||
{
|
||||
m_txArrows->setVisible(!m_txArrows->isVisible());
|
||||
}
|
||||
else if(item==m_txFlightMode)
|
||||
{
|
||||
QGraphicsSvgItem * svg;
|
||||
svg=(QGraphicsSvgItem *)item;
|
||||
if (svg)
|
||||
{
|
||||
if(svg->elementId()=="flightModeCenter")
|
||||
{
|
||||
if(growing)
|
||||
{
|
||||
svg->setElementId("flightModeRight");
|
||||
m_txFlightMode->setTransform(m_txFlightModeROrig,false);
|
||||
}
|
||||
else
|
||||
{
|
||||
svg->setElementId("flightModeLeft");
|
||||
m_txFlightMode->setTransform(m_txFlightModeLOrig,false);
|
||||
}
|
||||
}
|
||||
else if(svg->elementId()=="flightModeRight")
|
||||
{
|
||||
growing=false;
|
||||
svg->setElementId("flightModeCenter");
|
||||
m_txFlightMode->setTransform(m_txFlightModeCOrig,false);
|
||||
}
|
||||
else if(svg->elementId()=="flightModeLeft")
|
||||
{
|
||||
growing=true;
|
||||
svg->setElementId("flightModeCenter");
|
||||
m_txFlightMode->setTransform(m_txFlightModeCOrig,false);
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
else if(move==mix)
|
||||
{
|
||||
trans=m_txAccess0Orig;
|
||||
m_txAccess0->setTransform(trans.translate(movePos*10*ACCESS_MAX_MOVE/STICK_MAX_MOVE,0),false);
|
||||
trans=m_txAccess1Orig;
|
||||
m_txAccess1->setTransform(trans.translate(movePos*10*ACCESS_MAX_MOVE/STICK_MAX_MOVE,0),false);
|
||||
trans=m_txAccess2Orig;
|
||||
m_txAccess2->setTransform(trans.translate(movePos*10*ACCESS_MAX_MOVE/STICK_MAX_MOVE,0),false);
|
||||
|
||||
if(auxFlag)
|
||||
{
|
||||
trans=m_txLeftStickOrig;
|
||||
m_txLeftStick->setTransform(trans.translate(0,movePos*10),false);
|
||||
trans=m_txRightStickOrig;
|
||||
m_txRightStick->setTransform(trans.translate(0,movePos*10),false);
|
||||
}
|
||||
else
|
||||
{
|
||||
trans=m_txLeftStickOrig;
|
||||
m_txLeftStick->setTransform(trans.translate(movePos*10,0),false);
|
||||
trans=m_txRightStickOrig;
|
||||
m_txRightStick->setTransform(trans.translate(movePos*10,0),false);
|
||||
}
|
||||
|
||||
if(movePos==0)
|
||||
{
|
||||
m_txFlightMode->setElementId("flightModeCenter");
|
||||
m_txFlightMode->setTransform(m_txFlightModeCOrig,false);
|
||||
}
|
||||
else if(movePos==ACCESS_MAX_MOVE/2)
|
||||
{
|
||||
m_txFlightMode->setElementId("flightModeRight");
|
||||
m_txFlightMode->setTransform(m_txFlightModeROrig,false);
|
||||
}
|
||||
else if(movePos==ACCESS_MIN_MOVE/2)
|
||||
{
|
||||
m_txFlightMode->setElementId("flightModeLeft");
|
||||
m_txFlightMode->setTransform(m_txFlightModeLOrig,false);
|
||||
}
|
||||
}
|
||||
if(move==horizontal || move==vertical ||move==mix)
|
||||
{
|
||||
if(movePos==0 && growing)
|
||||
auxFlag=!auxFlag;
|
||||
if(growing)
|
||||
++movePos;
|
||||
else
|
||||
--movePos;
|
||||
if(movePos>limitMax)
|
||||
{
|
||||
movePos=movePos-2;
|
||||
growing=false;
|
||||
}
|
||||
if(movePos<limitMin)
|
||||
{
|
||||
movePos=movePos+2;
|
||||
growing=true;
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
void ConfigInputWidget::moveSticks()
|
||||
{
|
||||
QTransform trans;
|
||||
manualCommandData=manualCommandObj->getData();
|
||||
flightStatusData=flightStatusObj->getData();
|
||||
accessoryDesiredData0=accessoryDesiredObj0->getData();
|
||||
accessoryDesiredData1=accessoryDesiredObj1->getData();
|
||||
accessoryDesiredData2=accessoryDesiredObj2->getData();
|
||||
|
||||
if(transmitterMode==mode2)
|
||||
{
|
||||
trans=m_txLeftStickOrig;
|
||||
m_txLeftStick->setTransform(trans.translate(manualCommandData.Yaw*STICK_MAX_MOVE*10,-manualCommandData.Throttle*STICK_MAX_MOVE*10),false);
|
||||
trans=m_txRightStickOrig;
|
||||
m_txRightStick->setTransform(trans.translate(manualCommandData.Roll*STICK_MAX_MOVE*10,manualCommandData.Pitch*STICK_MAX_MOVE*10),false);
|
||||
}
|
||||
else
|
||||
{
|
||||
trans=m_txRightStickOrig;
|
||||
m_txRightStick->setTransform(trans.translate(manualCommandData.Roll*STICK_MAX_MOVE*10,-manualCommandData.Throttle*STICK_MAX_MOVE*10),false);
|
||||
trans=m_txLeftStickOrig;
|
||||
m_txLeftStick->setTransform(trans.translate(manualCommandData.Yaw*STICK_MAX_MOVE*10,manualCommandData.Pitch*STICK_MAX_MOVE*10),false);
|
||||
}
|
||||
if(flightStatusData.FlightMode==manualSettingsData.FlightModePosition[0])
|
||||
{
|
||||
m_txFlightMode->setElementId("flightModeLeft");
|
||||
m_txFlightMode->setTransform(m_txFlightModeLOrig,false);
|
||||
}
|
||||
else if (flightStatusData.FlightMode==manualSettingsData.FlightModePosition[1])
|
||||
{
|
||||
m_txFlightMode->setElementId("flightModeCenter");
|
||||
m_txFlightMode->setTransform(m_txFlightModeCOrig,false);
|
||||
}
|
||||
else if (flightStatusData.FlightMode==manualSettingsData.FlightModePosition[2])
|
||||
{
|
||||
m_txFlightMode->setElementId("flightModeRight");
|
||||
m_txFlightMode->setTransform(m_txFlightModeROrig,false);
|
||||
}
|
||||
m_txAccess0->setTransform(QTransform(m_txAccess0Orig).translate(accessoryDesiredData0.AccessoryVal*ACCESS_MAX_MOVE*10,0),false);
|
||||
m_txAccess1->setTransform(QTransform(m_txAccess1Orig).translate(accessoryDesiredData1.AccessoryVal*ACCESS_MAX_MOVE*10,0),false);
|
||||
m_txAccess2->setTransform(QTransform(m_txAccess2Orig).translate(accessoryDesiredData2.AccessoryVal*ACCESS_MAX_MOVE*10,0),false);
|
||||
}
|
||||
|
||||
void ConfigInputWidget::dimOtherControls(bool value)
|
||||
{
|
||||
qreal opac;
|
||||
if(value)
|
||||
opac=0.1;
|
||||
else
|
||||
opac=1;
|
||||
m_txAccess0->setOpacity(opac);
|
||||
m_txAccess1->setOpacity(opac);
|
||||
m_txAccess2->setOpacity(opac);
|
||||
m_txFlightMode->setOpacity(opac);
|
||||
}
|
||||
|
||||
void ConfigInputWidget::enableControls(bool enable)
|
||||
{
|
||||
m_config->configurationWizard->setEnabled(enable);
|
||||
m_config->runCalibration->setEnabled(enable);
|
||||
|
||||
ConfigTaskWidget::enableControls(enable);
|
||||
|
||||
}
|
||||
|
||||
void ConfigInputWidget::invertControls()
|
||||
{
|
||||
manualSettingsData=manualSettingsObj->getData();
|
||||
foreach(QWidget * wd,extraWidgets)
|
||||
{
|
||||
QCheckBox * cb=qobject_cast<QCheckBox *>(wd);
|
||||
if(cb)
|
||||
{
|
||||
int index = manualSettingsObj->getField("ChannelNumber")->getElementNames().indexOf(cb->text());
|
||||
if((cb->isChecked() && (manualSettingsData.ChannelMax[index]>manualSettingsData.ChannelMin[index])) ||
|
||||
(!cb->isChecked() && (manualSettingsData.ChannelMax[index]<manualSettingsData.ChannelMin[index])))
|
||||
{
|
||||
qint16 aux;
|
||||
aux=manualSettingsData.ChannelMax[index];
|
||||
manualSettingsData.ChannelMax[index]=manualSettingsData.ChannelMin[index];
|
||||
manualSettingsData.ChannelMin[index]=aux;
|
||||
}
|
||||
}
|
||||
}
|
||||
manualSettingsObj->setData(manualSettingsData);
|
||||
}
|
||||
|
||||
void ConfigInputWidget::moveFMSlider()
|
||||
{
|
||||
ManualControlSettings::DataFields manualSettingsDataPriv = manualSettingsObj->getData();
|
||||
ManualControlCommand::DataFields manualCommandDataPriv = manualCommandObj->getData();
|
||||
|
||||
float valueScaled;
|
||||
int chMin = manualSettingsDataPriv.ChannelMin[ManualControlSettings::CHANNELMIN_FLIGHTMODE];
|
||||
int chMax = manualSettingsDataPriv.ChannelMax[ManualControlSettings::CHANNELMAX_FLIGHTMODE];
|
||||
int chNeutral = manualSettingsDataPriv.ChannelNeutral[ManualControlSettings::CHANNELNEUTRAL_FLIGHTMODE];
|
||||
|
||||
int value = manualCommandDataPriv.Channel[ManualControlSettings::CHANNELMIN_FLIGHTMODE];
|
||||
if ((chMax > chMin && value >= chNeutral) || (chMin > chMax && value <= chNeutral))
|
||||
{
|
||||
if (chMax != chNeutral)
|
||||
valueScaled = (float)(value - chNeutral) / (float)(chMax - chNeutral);
|
||||
else
|
||||
valueScaled = 0;
|
||||
}
|
||||
else
|
||||
{
|
||||
if (chMin != chNeutral)
|
||||
valueScaled = (float)(value - chNeutral) / (float)(chNeutral - chMin);
|
||||
else
|
||||
valueScaled = 0;
|
||||
}
|
||||
|
||||
// Bound and scale FlightMode from [-1..+1] to [0..1] range
|
||||
if (valueScaled < -1.0)
|
||||
valueScaled = -1.0;
|
||||
else
|
||||
if (valueScaled > 1.0)
|
||||
valueScaled = 1.0;
|
||||
|
||||
// Convert flightMode value into the switch position in the range [0..N-1]
|
||||
// This uses the same optimized computation as flight code to be consistent
|
||||
uint8_t pos = ((int16_t)(valueScaled * 256) + 256) * manualSettingsDataPriv.FlightModeNumber >> 9;
|
||||
if (pos >= manualSettingsDataPriv.FlightModeNumber)
|
||||
pos = manualSettingsDataPriv.FlightModeNumber - 1;
|
||||
m_config->fmsSlider->setValue(pos);
|
||||
}
|
||||
|
||||
void ConfigInputWidget::updatePositionSlider()
|
||||
{
|
||||
ManualControlSettings::DataFields manualSettingsDataPriv = manualSettingsObj->getData();
|
||||
|
||||
switch(manualSettingsDataPriv.FlightModeNumber) {
|
||||
default:
|
||||
case 6:
|
||||
m_config->fmsModePos6->setEnabled(true);
|
||||
// pass through
|
||||
case 5:
|
||||
m_config->fmsModePos5->setEnabled(true);
|
||||
// pass through
|
||||
case 4:
|
||||
m_config->fmsModePos4->setEnabled(true);
|
||||
// pass through
|
||||
case 3:
|
||||
m_config->fmsModePos3->setEnabled(true);
|
||||
// pass through
|
||||
case 2:
|
||||
m_config->fmsModePos2->setEnabled(true);
|
||||
// pass through
|
||||
case 1:
|
||||
m_config->fmsModePos1->setEnabled(true);
|
||||
// pass through
|
||||
case 0:
|
||||
break;
|
||||
}
|
||||
|
||||
switch(manualSettingsDataPriv.FlightModeNumber) {
|
||||
case 0:
|
||||
m_config->fmsModePos1->setEnabled(false);
|
||||
// pass through
|
||||
case 1:
|
||||
m_config->fmsModePos2->setEnabled(false);
|
||||
// pass through
|
||||
case 2:
|
||||
m_config->fmsModePos3->setEnabled(false);
|
||||
// pass through
|
||||
case 3:
|
||||
m_config->fmsModePos4->setEnabled(false);
|
||||
// pass through
|
||||
case 4:
|
||||
m_config->fmsModePos5->setEnabled(false);
|
||||
// pass through
|
||||
case 5:
|
||||
m_config->fmsModePos6->setEnabled(false);
|
||||
// pass through
|
||||
case 6:
|
||||
default:
|
||||
break;
|
||||
}
|
||||
}
|
||||
|
||||
void ConfigInputWidget::updateCalibration()
|
||||
{
|
||||
manualCommandData=manualCommandObj->getData();
|
||||
for(uint i=0;i<ManualControlSettings::CHANNELMAX_NUMELEM;++i)
|
||||
{
|
||||
if((!reverse[i] && manualSettingsData.ChannelMin[i]>manualCommandData.Channel[i]) ||
|
||||
(reverse[i] && manualSettingsData.ChannelMin[i]<manualCommandData.Channel[i]))
|
||||
manualSettingsData.ChannelMin[i]=manualCommandData.Channel[i];
|
||||
if((!reverse[i] && manualSettingsData.ChannelMax[i]<manualCommandData.Channel[i]) ||
|
||||
(reverse[i] && manualSettingsData.ChannelMax[i]>manualCommandData.Channel[i]))
|
||||
manualSettingsData.ChannelMax[i]=manualCommandData.Channel[i];
|
||||
manualSettingsData.ChannelNeutral[i] = manualCommandData.Channel[i];
|
||||
}
|
||||
|
||||
manualSettingsObj->setData(manualSettingsData);
|
||||
manualSettingsObj->updated();
|
||||
}
|
||||
|
||||
void ConfigInputWidget::simpleCalibration(bool enable)
|
||||
{
|
||||
if (enable) {
|
||||
m_config->configurationWizard->setEnabled(false);
|
||||
|
||||
QMessageBox msgBox;
|
||||
msgBox.setText(tr("Arming Settings are now set to Always Disarmed for your safety."));
|
||||
msgBox.setDetailedText(tr("You will have to reconfigure the arming settings manually when the wizard is finished."));
|
||||
msgBox.setStandardButtons(QMessageBox::Ok);
|
||||
msgBox.setDefaultButton(QMessageBox::Ok);
|
||||
msgBox.exec();
|
||||
|
||||
manualCommandData = manualCommandObj->getData();
|
||||
|
||||
manualSettingsData=manualSettingsObj->getData();
|
||||
manualSettingsData.Arming=ManualControlSettings::ARMING_ALWAYSDISARMED;
|
||||
manualSettingsObj->setData(manualSettingsData);
|
||||
|
||||
for (unsigned int i = 0; i < ManualControlCommand::CHANNEL_NUMELEM; i++) {
|
||||
reverse[i] = manualSettingsData.ChannelMax[i] < manualSettingsData.ChannelMin[i];
|
||||
manualSettingsData.ChannelMin[i] = manualCommandData.Channel[i];
|
||||
manualSettingsData.ChannelNeutral[i] = manualCommandData.Channel[i];
|
||||
manualSettingsData.ChannelMax[i] = manualCommandData.Channel[i];
|
||||
}
|
||||
|
||||
fastMdata();
|
||||
|
||||
connect(manualCommandObj, SIGNAL(objectUnpacked(UAVObject*)), this, SLOT(updateCalibration()));
|
||||
} else {
|
||||
m_config->configurationWizard->setEnabled(true);
|
||||
|
||||
manualCommandData = manualCommandObj->getData();
|
||||
manualSettingsData = manualSettingsObj->getData();
|
||||
|
||||
restoreMdata();
|
||||
|
||||
for (int i = 0; i < ManualControlCommand::CHANNEL_NUMELEM; i++)
|
||||
manualSettingsData.ChannelNeutral[i] = manualCommandData.Channel[i];
|
||||
|
||||
// Force flight mode neutral to middle
|
||||
manualSettingsData.ChannelNeutral[ManualControlSettings::CHANNELNUMBER_FLIGHTMODE] =
|
||||
(manualSettingsData.ChannelMax[ManualControlSettings::CHANNELNUMBER_FLIGHTMODE] +
|
||||
manualSettingsData.ChannelMin[ManualControlSettings::CHANNELNUMBER_FLIGHTMODE]) / 2;
|
||||
|
||||
// Force throttle to be near min
|
||||
manualSettingsData.ChannelNeutral[ManualControlSettings::CHANNELNEUTRAL_THROTTLE]=
|
||||
manualSettingsData.ChannelMin[ManualControlSettings::CHANNELMIN_THROTTLE]+
|
||||
((manualSettingsData.ChannelMax[ManualControlSettings::CHANNELMAX_THROTTLE]-
|
||||
manualSettingsData.ChannelMin[ManualControlSettings::CHANNELMIN_THROTTLE])*0.02);
|
||||
|
||||
manualSettingsObj->setData(manualSettingsData);
|
||||
|
||||
disconnect(manualCommandObj, SIGNAL(objectUnpacked(UAVObject*)), this, SLOT(updateCalibration()));
|
||||
}
|
||||
}
|
||||
|
@ -60,7 +60,7 @@ public:
|
||||
enum txMovements{moveLeftVerticalStick,moveRightVerticalStick,moveLeftHorizontalStick,moveRightHorizontalStick,moveAccess0,moveAccess1,moveAccess2,moveFlightMode,centerAll,moveAll,nothing};
|
||||
enum txMovementType{vertical,horizontal,jump,mix};
|
||||
enum txType {acro, heli};
|
||||
public slots:
|
||||
void startInputWizard() { goToWizard(); }
|
||||
|
||||
private:
|
||||
bool growing;
|
||||
@ -144,6 +144,7 @@ private:
|
||||
|
||||
void wizardSetUpStep(enum wizardSteps);
|
||||
void wizardTearDownStep(enum wizardSteps);
|
||||
|
||||
private slots:
|
||||
void wzNext();
|
||||
void wzBack();
|
||||
@ -161,11 +162,10 @@ private slots:
|
||||
void invertControls();
|
||||
void simpleCalibration(bool state);
|
||||
void updateCalibration();
|
||||
|
||||
protected:
|
||||
void resizeEvent(QResizeEvent *event);
|
||||
virtual void enableControls(bool enable);
|
||||
|
||||
|
||||
};
|
||||
|
||||
#endif
|
||||
|
@ -99,7 +99,7 @@ void ConfigPlugin::extensionsInitialized()
|
||||
|
||||
void ConfigPlugin::shutdown()
|
||||
{
|
||||
// Do nothing
|
||||
// Do nothing
|
||||
}
|
||||
|
||||
/**
|
||||
|
@ -101,7 +101,7 @@ void ConnectionManager::init()
|
||||
/**
|
||||
* Method called when the user clicks the "Connect" button
|
||||
*/
|
||||
bool ConnectionManager::connectDevice()
|
||||
bool ConnectionManager::connectDevice(DevListItem device)
|
||||
{
|
||||
DevListItem connection_device = findDevice(m_availableDevList->itemData(m_availableDevList->currentIndex(),Qt::ToolTipRole).toString());
|
||||
if (!connection_device.connection)
|
||||
@ -126,7 +126,7 @@ bool ConnectionManager::connectDevice()
|
||||
connect(m_connectionDevice.connection, SIGNAL(destroyed(QObject *)), this, SLOT(onConnectionDestroyed(QObject *)), Qt::QueuedConnection);
|
||||
|
||||
// signal interested plugins that we connected to the device
|
||||
emit deviceConnected(m_ioDev);
|
||||
emit deviceConnected(io_dev);
|
||||
m_connectBtn->setText("Disconnect");
|
||||
m_availableDevList->setEnabled(false);
|
||||
|
||||
@ -174,6 +174,7 @@ bool ConnectionManager::disconnectDevice()
|
||||
m_connectionDevice.connection = NULL;
|
||||
m_ioDev = NULL;
|
||||
|
||||
emit deviceDisconnected();
|
||||
m_connectBtn->setText("Connect");
|
||||
m_availableDevList->setEnabled(true);
|
||||
|
||||
@ -230,8 +231,11 @@ void ConnectionManager::onConnectClicked()
|
||||
{
|
||||
// Check if we have a ioDev already created:
|
||||
if (!m_ioDev)
|
||||
{ // connecting
|
||||
connectDevice();
|
||||
{
|
||||
// connecting to currently selected device
|
||||
DevListItem device = findDevice(m_availableDevList->itemData(m_availableDevList->currentIndex(), Qt::ToolTipRole).toString());
|
||||
if (device.connection)
|
||||
connectDevice(device);
|
||||
}
|
||||
else
|
||||
{ // disconnecting
|
||||
@ -427,6 +431,9 @@ void ConnectionManager::devChanged(IConnection *connection)
|
||||
|
||||
updateConnectionDropdown();
|
||||
|
||||
qDebug() << "# devices " << m_devList.count();
|
||||
emit availableDevicesChanged(m_devList);
|
||||
|
||||
|
||||
//disable connection button if the liNameif (m_availableDevList->count() > 0)
|
||||
if (m_availableDevList->count() > 0)
|
||||
@ -445,11 +452,12 @@ void ConnectionManager::updateConnectionDropdown()
|
||||
if(!m_ioDev && d.getConName().startsWith("USB"))
|
||||
{
|
||||
if(m_mainWindow->generalSettings()->autoConnect() || m_mainWindow->generalSettings()->autoSelect())
|
||||
m_availableDevList->setCurrentIndex(m_availableDevList->count()-1);
|
||||
m_availableDevList->setCurrentIndex(m_availableDevList->count() - 1);
|
||||
|
||||
if(m_mainWindow->generalSettings()->autoConnect() && polling)
|
||||
{
|
||||
qDebug() << "Automatically opening device";
|
||||
connectDevice();
|
||||
connectDevice(d);
|
||||
qDebug()<<"ConnectionManager::devChanged autoconnected USB device";
|
||||
}
|
||||
}
|
||||
|
@ -92,7 +92,14 @@ public:
|
||||
void init();
|
||||
|
||||
QIODevice* getCurrentConnection() { return m_ioDev; }
|
||||
DevListItem getCurrentDevice() { return m_connectionDevice;}
|
||||
DevListItem getCurrentDevice() { return m_connectionDevice; }
|
||||
DevListItem findDevice(const QString &devName);
|
||||
|
||||
QLinkedList<DevListItem> getAvailableDevices() { return m_devList; }
|
||||
|
||||
bool isConnected() { return m_ioDev != 0; }
|
||||
|
||||
bool connectDevice(DevListItem device);
|
||||
bool disconnectDevice();
|
||||
void suspendPolling();
|
||||
void resumePolling();
|
||||
@ -101,11 +108,12 @@ protected:
|
||||
void updateConnectionList(IConnection *connection);
|
||||
void registerDevice(IConnection *conn, IConnection::device device);
|
||||
void updateConnectionDropdown();
|
||||
DevListItem findDevice(const QString &devName);
|
||||
|
||||
signals:
|
||||
void deviceConnected(QIODevice *dev);
|
||||
void deviceConnected(QIODevice *device);
|
||||
void deviceAboutToDisconnect();
|
||||
void deviceDisconnected();
|
||||
void availableDevicesChanged(const QLinkedList<Core::DevListItem> devices);
|
||||
|
||||
public slots:
|
||||
void telemetryConnected();
|
||||
|
@ -326,3 +326,13 @@ void ModeManager::setFocusToCurrentMode()
|
||||
widget->setFocus();
|
||||
}
|
||||
}
|
||||
|
||||
void ModeManager::triggerAction(const QString &actionId)
|
||||
{
|
||||
foreach(Command * command, m_actions.keys()){
|
||||
if(command->action()->objectName() == actionId) {
|
||||
command->action()->trigger();
|
||||
break;
|
||||
}
|
||||
}
|
||||
}
|
||||
|
@ -82,6 +82,7 @@ public slots:
|
||||
void activateMode(const QString &id);
|
||||
void activateModeByWorkspaceName(const QString &id);
|
||||
void setFocusToCurrentMode();
|
||||
void triggerAction(const QString &actionId);
|
||||
|
||||
private slots:
|
||||
void objectAdded(QObject *obj);
|
||||
|
@ -1,45 +1,45 @@
|
||||
/*
|
||||
* 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 PFDQMLGADGET_H_
|
||||
#define PFDQMLQMLGADGET_H_
|
||||
|
||||
#include <coreplugin/iuavgadget.h>
|
||||
#include "pfdqmlgadgetwidget.h"
|
||||
|
||||
class IUAVGadget;
|
||||
class QWidget;
|
||||
class QString;
|
||||
class PfdQmlGadgetWidget;
|
||||
|
||||
using namespace Core;
|
||||
|
||||
class PfdQmlGadget : public Core::IUAVGadget
|
||||
{
|
||||
Q_OBJECT
|
||||
public:
|
||||
PfdQmlGadget(QString classId, PfdQmlGadgetWidget *widget, QWidget *parent = 0);
|
||||
~PfdQmlGadget();
|
||||
|
||||
QWidget *widget() { return m_widget; }
|
||||
void loadConfiguration(IUAVGadgetConfiguration* config);
|
||||
|
||||
private:
|
||||
PfdQmlGadgetWidget *m_widget;
|
||||
};
|
||||
|
||||
|
||||
#endif // PFDQMLQMLGADGET_H_
|
||||
/*
|
||||
* 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 PFDQMLGADGET_H_
|
||||
#define PFDQMLQMLGADGET_H_
|
||||
|
||||
#include <coreplugin/iuavgadget.h>
|
||||
#include "pfdqmlgadgetwidget.h"
|
||||
|
||||
class IUAVGadget;
|
||||
class QWidget;
|
||||
class QString;
|
||||
class PfdQmlGadgetWidget;
|
||||
|
||||
using namespace Core;
|
||||
|
||||
class PfdQmlGadget : public Core::IUAVGadget
|
||||
{
|
||||
Q_OBJECT
|
||||
public:
|
||||
PfdQmlGadget(QString classId, PfdQmlGadgetWidget *widget, QWidget *parent = 0);
|
||||
~PfdQmlGadget();
|
||||
|
||||
QWidget *widget() { return m_widget; }
|
||||
void loadConfiguration(IUAVGadgetConfiguration* config);
|
||||
|
||||
private:
|
||||
PfdQmlGadgetWidget *m_widget;
|
||||
};
|
||||
|
||||
|
||||
#endif // PFDQMLQMLGADGET_H_
|
||||
|
@ -223,6 +223,13 @@ plugin_uavobjectwidgetutils.depends += plugin_uavobjectutil
|
||||
plugin_uavobjectwidgetutils.depends += plugin_uavsettingsimportexport
|
||||
SUBDIRS += plugin_uavobjectwidgetutils
|
||||
|
||||
# Setup Wizard plugin
|
||||
plugin_setupwizard.subdir = setupwizard
|
||||
plugin_setupwizard.depends = plugin_coreplugin
|
||||
plugin_setupwizard.depends += plugin_uavobjects
|
||||
plugin_setupwizard.depends += plugin_config
|
||||
SUBDIRS += plugin_setupwizard
|
||||
|
||||
# Junsi Powerlog plugin
|
||||
#plugin_powerlog.subdir = powerlog
|
||||
#plugin_powerlog.depends = plugin_coreplugin
|
||||
|
@ -0,0 +1,12 @@
|
||||
<plugin name="SetupWizard" version="1.0.0" compatVersion="1.0.0">
|
||||
<vendor>The OpenPilot Project</vendor>
|
||||
<copyright>(C) 2012 OpenPilot Project</copyright>
|
||||
<license>The GNU Public License (GPL) Version 3</license>
|
||||
<description>A plugin that provides a setup wizard for easy initial setup of airframes.</description>
|
||||
<url>http://www.openpilot.org</url>
|
||||
<dependencyList>
|
||||
<dependency name="Core" version="1.0.0"/>
|
||||
<dependency name="Config" version="1.0.0"/>
|
||||
<dependency name="UAVObjects" version="1.0.0"/>
|
||||
</dependencyList>
|
||||
</plugin>
|
@ -0,0 +1,193 @@
|
||||
/**
|
||||
******************************************************************************
|
||||
*
|
||||
* @file connectiondiagram.cpp
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012.
|
||||
* @addtogroup
|
||||
* @{
|
||||
* @addtogroup ConnectionDiagram
|
||||
* @{
|
||||
* @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 <QDebug>
|
||||
#include <QFile>
|
||||
#include <QFileDialog>
|
||||
#include "connectiondiagram.h"
|
||||
#include "ui_connectiondiagram.h"
|
||||
|
||||
ConnectionDiagram::ConnectionDiagram(QWidget *parent, VehicleConfigurationSource* configSource) :
|
||||
QDialog(parent), ui(new Ui::ConnectionDiagram), m_configSource(configSource), m_background(0)
|
||||
{
|
||||
ui->setupUi(this);
|
||||
setWindowTitle(tr("Connection Diagram"));
|
||||
setupGraphicsScene();
|
||||
}
|
||||
|
||||
ConnectionDiagram::~ConnectionDiagram()
|
||||
{
|
||||
delete ui;
|
||||
}
|
||||
|
||||
void ConnectionDiagram::resizeEvent(QResizeEvent *event)
|
||||
{
|
||||
QWidget::resizeEvent(event);
|
||||
ui->connectionDiagram->fitInView(m_background, Qt::KeepAspectRatio);
|
||||
}
|
||||
|
||||
void ConnectionDiagram::showEvent(QShowEvent * event)
|
||||
{
|
||||
QWidget::showEvent(event);
|
||||
ui->connectionDiagram->fitInView(m_background, Qt::KeepAspectRatio);
|
||||
}
|
||||
|
||||
void ConnectionDiagram::setupGraphicsScene()
|
||||
{
|
||||
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())
|
||||
{
|
||||
m_scene = new QGraphicsScene(this);
|
||||
ui->connectionDiagram->setScene(m_scene);
|
||||
//ui->connectionDiagram->setViewportUpdateMode(QGraphicsView::FullViewportUpdate);
|
||||
|
||||
m_background = new QGraphicsSvgItem();
|
||||
m_background->setSharedRenderer(m_renderer);
|
||||
m_background->setElementId("background");
|
||||
m_background->setOpacity(0);
|
||||
//m_background->setFlags(QGraphicsItem::ItemClipsToShape);
|
||||
m_background->setZValue(-1);
|
||||
m_scene->addItem(m_background);
|
||||
|
||||
QList<QString> elementsToShow;
|
||||
|
||||
switch(m_configSource->getControllerType())
|
||||
{
|
||||
case VehicleConfigurationSource::CONTROLLER_CC:
|
||||
case VehicleConfigurationSource::CONTROLLER_CC3D:
|
||||
case VehicleConfigurationSource::CONTROLLER_REVO:
|
||||
case VehicleConfigurationSource::CONTROLLER_PIPX:
|
||||
default:
|
||||
elementsToShow << "controller";
|
||||
break;
|
||||
}
|
||||
|
||||
switch (m_configSource->getVehicleType())
|
||||
{
|
||||
case VehicleConfigurationSource::VEHICLE_MULTI:
|
||||
switch (m_configSource->getVehicleSubType())
|
||||
{
|
||||
case VehicleConfigurationSource::MULTI_ROTOR_TRI_Y:
|
||||
elementsToShow << "tri";
|
||||
break;
|
||||
case VehicleConfigurationSource::MULTI_ROTOR_QUAD_X:
|
||||
elementsToShow << "quad-x";
|
||||
break;
|
||||
case VehicleConfigurationSource::MULTI_ROTOR_QUAD_PLUS:
|
||||
elementsToShow << "quad-p";
|
||||
break;
|
||||
case VehicleConfigurationSource::MULTI_ROTOR_HEXA:
|
||||
elementsToShow << "hexa";
|
||||
break;
|
||||
case VehicleConfigurationSource::MULTI_ROTOR_HEXA_COAX_Y:
|
||||
elementsToShow << "hexa-y";
|
||||
break;
|
||||
case VehicleConfigurationSource::MULTI_ROTOR_HEXA_H:
|
||||
elementsToShow << "hexa-h";
|
||||
break;
|
||||
default:
|
||||
break;
|
||||
}
|
||||
break;
|
||||
case VehicleConfigurationSource::VEHICLE_FIXEDWING:
|
||||
case VehicleConfigurationSource::VEHICLE_HELI:
|
||||
case VehicleConfigurationSource::VEHICLE_SURFACE:
|
||||
default:
|
||||
break;
|
||||
}
|
||||
|
||||
switch (m_configSource->getInputType())
|
||||
{
|
||||
case VehicleConfigurationSource::INPUT_PWM:
|
||||
elementsToShow << "pwm" ;
|
||||
break;
|
||||
case VehicleConfigurationSource::INPUT_PPM:
|
||||
elementsToShow << "ppm";
|
||||
break;
|
||||
case VehicleConfigurationSource::INPUT_SBUS:
|
||||
elementsToShow << "sbus";
|
||||
break;
|
||||
case VehicleConfigurationSource::INPUT_DSMX10:
|
||||
case VehicleConfigurationSource::INPUT_DSMX11:
|
||||
case VehicleConfigurationSource::INPUT_DSM2:
|
||||
elementsToShow << "satellite";
|
||||
break;
|
||||
default:
|
||||
break;
|
||||
}
|
||||
|
||||
setupGraphicsSceneItems(elementsToShow);
|
||||
|
||||
ui->connectionDiagram->setSceneRect(m_background->boundingRect());
|
||||
ui->connectionDiagram->fitInView(m_background, Qt::KeepAspectRatio);
|
||||
|
||||
qDebug() << "Scene complete";
|
||||
}
|
||||
}
|
||||
|
||||
void ConnectionDiagram::setupGraphicsSceneItems(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->setZValue(z++);
|
||||
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());
|
||||
|
||||
m_scene->addItem(element);
|
||||
qDebug() << "Adding " << elementId << " to scene at " << element->pos();
|
||||
}
|
||||
else {
|
||||
qDebug() << "Element with id: " << elementId << " not found.";
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
void ConnectionDiagram::on_saveButton_clicked()
|
||||
{
|
||||
QImage image(2200, 1100, QImage::Format_ARGB32);
|
||||
image.fill(0);
|
||||
QPainter painter(&image);
|
||||
m_scene->render(&painter);
|
||||
QString fileName = QFileDialog::getSaveFileName(this, tr("Save File"), "", tr("Images (*.png *.xpm *.jpg)"));
|
||||
if(!fileName.isEmpty()) {
|
||||
image.save(fileName);
|
||||
}
|
||||
}
|
@ -0,0 +1,70 @@
|
||||
/**
|
||||
******************************************************************************
|
||||
*
|
||||
* @file connectiondiagram.h
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012.
|
||||
* @addtogroup
|
||||
* @{
|
||||
* @addtogroup ConnectionDiagram
|
||||
* @{
|
||||
* @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 CONNECTIONDIAGRAM_H
|
||||
#define CONNECTIONDIAGRAM_H
|
||||
|
||||
#include <QDialog>
|
||||
#include <QHash>
|
||||
#include <QSvgRenderer>
|
||||
|
||||
#include <QGraphicsSvgItem>
|
||||
#include "vehicleconfigurationsource.h"
|
||||
|
||||
|
||||
namespace Ui {
|
||||
class ConnectionDiagram;
|
||||
}
|
||||
|
||||
class ConnectionDiagram : public QDialog
|
||||
{
|
||||
Q_OBJECT
|
||||
|
||||
public:
|
||||
explicit ConnectionDiagram(QWidget *parent, VehicleConfigurationSource *configSource);
|
||||
~ConnectionDiagram();
|
||||
|
||||
private:
|
||||
Ui::ConnectionDiagram *ui;
|
||||
VehicleConfigurationSource *m_configSource;
|
||||
|
||||
QSvgRenderer *m_renderer;
|
||||
QGraphicsSvgItem* m_background;
|
||||
QGraphicsScene *m_scene;
|
||||
|
||||
void setupGraphicsScene();
|
||||
void setupGraphicsSceneItems(QList<QString> elementsToShow);
|
||||
protected:
|
||||
void resizeEvent(QResizeEvent *event);
|
||||
void showEvent(QShowEvent *event);
|
||||
|
||||
private slots:
|
||||
|
||||
void on_saveButton_clicked();
|
||||
};
|
||||
|
||||
#endif // CONNECTIONDIAGRAM_H
|
112
ground/openpilotgcs/src/plugins/setupwizard/connectiondiagram.ui
Normal file
@ -0,0 +1,112 @@
|
||||
<?xml version="1.0" encoding="UTF-8"?>
|
||||
<ui version="4.0">
|
||||
<class>ConnectionDiagram</class>
|
||||
<widget class="QDialog" name="ConnectionDiagram">
|
||||
<property name="geometry">
|
||||
<rect>
|
||||
<x>0</x>
|
||||
<y>0</y>
|
||||
<width>800</width>
|
||||
<height>440</height>
|
||||
</rect>
|
||||
</property>
|
||||
<property name="windowTitle">
|
||||
<string>Dialog</string>
|
||||
</property>
|
||||
<property name="sizeGripEnabled">
|
||||
<bool>true</bool>
|
||||
</property>
|
||||
<property name="modal">
|
||||
<bool>true</bool>
|
||||
</property>
|
||||
<layout class="QVBoxLayout" name="verticalLayout">
|
||||
<item>
|
||||
<widget class="QGraphicsView" name="connectionDiagram">
|
||||
<property name="frameShape">
|
||||
<enum>QFrame::WinPanel</enum>
|
||||
</property>
|
||||
<property name="verticalScrollBarPolicy">
|
||||
<enum>Qt::ScrollBarAlwaysOff</enum>
|
||||
</property>
|
||||
<property name="horizontalScrollBarPolicy">
|
||||
<enum>Qt::ScrollBarAlwaysOff</enum>
|
||||
</property>
|
||||
<property name="backgroundBrush">
|
||||
<brush brushstyle="SolidPattern">
|
||||
<color alpha="255">
|
||||
<red>255</red>
|
||||
<green>255</green>
|
||||
<blue>255</blue>
|
||||
</color>
|
||||
</brush>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item>
|
||||
<layout class="QHBoxLayout" name="horizontalLayout">
|
||||
<item>
|
||||
<spacer name="horizontalSpacer">
|
||||
<property name="orientation">
|
||||
<enum>Qt::Horizontal</enum>
|
||||
</property>
|
||||
<property name="sizeHint" stdset="0">
|
||||
<size>
|
||||
<width>40</width>
|
||||
<height>20</height>
|
||||
</size>
|
||||
</property>
|
||||
</spacer>
|
||||
</item>
|
||||
<item>
|
||||
<widget class="QPushButton" name="saveButton">
|
||||
<property name="sizePolicy">
|
||||
<sizepolicy hsizetype="Fixed" vsizetype="Fixed">
|
||||
<horstretch>0</horstretch>
|
||||
<verstretch>0</verstretch>
|
||||
</sizepolicy>
|
||||
</property>
|
||||
<property name="text">
|
||||
<string>Save</string>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
<item>
|
||||
<widget class="QPushButton" name="closeButton">
|
||||
<property name="sizePolicy">
|
||||
<sizepolicy hsizetype="Fixed" vsizetype="Fixed">
|
||||
<horstretch>0</horstretch>
|
||||
<verstretch>0</verstretch>
|
||||
</sizepolicy>
|
||||
</property>
|
||||
<property name="text">
|
||||
<string>Close</string>
|
||||
</property>
|
||||
<property name="default">
|
||||
<bool>true</bool>
|
||||
</property>
|
||||
</widget>
|
||||
</item>
|
||||
</layout>
|
||||
</item>
|
||||
</layout>
|
||||
</widget>
|
||||
<resources/>
|
||||
<connections>
|
||||
<connection>
|
||||
<sender>closeButton</sender>
|
||||
<signal>clicked()</signal>
|
||||
<receiver>ConnectionDiagram</receiver>
|
||||
<slot>close()</slot>
|
||||
<hints>
|
||||
<hint type="sourcelabel">
|
||||
<x>752</x>
|
||||
<y>418</y>
|
||||
</hint>
|
||||
<hint type="destinationlabel">
|
||||
<x>399</x>
|
||||
<y>219</y>
|
||||
</hint>
|
||||
</hints>
|
||||
</connection>
|
||||
</connections>
|
||||
</ui>
|
217
ground/openpilotgcs/src/plugins/setupwizard/levellingutil.cpp
Normal file
@ -0,0 +1,217 @@
|
||||
/**
|
||||
******************************************************************************
|
||||
*
|
||||
* @file levellingutil.cpp
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012.
|
||||
* @addtogroup
|
||||
* @{
|
||||
* @addtogroup LevellingUtil
|
||||
* @{
|
||||
* @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 "levellingutil.h"
|
||||
#include "extensionsystem/pluginmanager.h"
|
||||
#include "uavobjectmanager.h"
|
||||
#include "attitudesettings.h"
|
||||
#include "accels.h"
|
||||
#include "gyros.h"
|
||||
|
||||
|
||||
LevellingUtil::LevellingUtil(long measurementCount, long measurementRate) : QObject(),
|
||||
m_isMeasuring(false), m_accelMeasurementCount(measurementCount), m_gyroMeasurementCount(measurementCount),
|
||||
m_accelMeasurementRate(measurementRate), m_gyroMeasurementRate(measurementRate)
|
||||
{
|
||||
}
|
||||
|
||||
LevellingUtil::LevellingUtil(long accelMeasurementCount, long accelMeasurementRate,
|
||||
long gyroMeasurementCount, long gyroMeasurementRate) : QObject(),
|
||||
m_isMeasuring(false), m_accelMeasurementCount(accelMeasurementCount), m_gyroMeasurementCount(gyroMeasurementCount),
|
||||
m_accelMeasurementRate(accelMeasurementRate), m_gyroMeasurementRate(gyroMeasurementRate)
|
||||
{
|
||||
}
|
||||
|
||||
void LevellingUtil::start()
|
||||
{
|
||||
if(!m_isMeasuring) {
|
||||
startMeasurement();
|
||||
|
||||
// Set up timeout timer
|
||||
connect(&m_timeoutTimer, SIGNAL(timeout()), this, SLOT(timeout()));
|
||||
//Set timeout to max time of measurement + 10 secs
|
||||
m_timeoutTimer.start(std::max(m_accelMeasurementCount * m_accelMeasurementRate, m_gyroMeasurementCount * m_gyroMeasurementRate) + 10000);
|
||||
}
|
||||
}
|
||||
|
||||
void LevellingUtil::abort()
|
||||
{
|
||||
if(m_isMeasuring) {
|
||||
stopMeasurement();
|
||||
}
|
||||
}
|
||||
|
||||
void LevellingUtil::gyroMeasurementsUpdated(UAVObject *obj)
|
||||
{
|
||||
QMutexLocker locker(&m_measurementMutex);
|
||||
|
||||
if(m_receivedGyroUpdates < m_gyroMeasurementCount) {
|
||||
ExtensionSystem::PluginManager *pm = ExtensionSystem::PluginManager::instance();
|
||||
UAVObjectManager * uavObjectManager = pm->getObject<UAVObjectManager>();
|
||||
Q_ASSERT(uavObjectManager);
|
||||
|
||||
Gyros * gyros = Gyros::GetInstance(uavObjectManager);
|
||||
Gyros::DataFields gyrosData = gyros->getData();
|
||||
|
||||
m_gyroX += gyrosData.x;
|
||||
m_gyroY += gyrosData.y;
|
||||
m_gyroZ += gyrosData.z;
|
||||
|
||||
m_receivedGyroUpdates++;
|
||||
emit progress(m_receivedGyroUpdates + m_receivedAccelUpdates, m_gyroMeasurementCount + m_accelMeasurementCount);
|
||||
}
|
||||
else if (m_receivedAccelUpdates >= m_accelMeasurementCount &&
|
||||
m_receivedGyroUpdates >= m_gyroMeasurementCount && m_isMeasuring) {
|
||||
stopMeasurement();
|
||||
emit done(calculateLevellingData());
|
||||
}
|
||||
}
|
||||
|
||||
void LevellingUtil::accelMeasurementsUpdated(UAVObject *obj)
|
||||
{
|
||||
QMutexLocker locker(&m_measurementMutex);
|
||||
|
||||
if(m_receivedAccelUpdates < m_accelMeasurementCount) {
|
||||
ExtensionSystem::PluginManager *pm = ExtensionSystem::PluginManager::instance();
|
||||
UAVObjectManager * uavObjectManager = pm->getObject<UAVObjectManager>();
|
||||
Q_ASSERT(uavObjectManager);
|
||||
|
||||
Accels * accels = Accels::GetInstance(uavObjectManager);
|
||||
Accels::DataFields accelsData = accels->getData();
|
||||
|
||||
m_accelerometerX += accelsData.x;
|
||||
m_accelerometerY += accelsData.y;
|
||||
m_accelerometerZ += accelsData.z;
|
||||
|
||||
m_receivedAccelUpdates++;
|
||||
emit progress(m_receivedGyroUpdates + m_receivedAccelUpdates, m_gyroMeasurementCount + m_accelMeasurementCount);
|
||||
}
|
||||
else if (m_receivedAccelUpdates >= m_accelMeasurementCount &&
|
||||
m_receivedGyroUpdates >= m_gyroMeasurementCount && m_isMeasuring) {
|
||||
stopMeasurement();
|
||||
emit done(calculateLevellingData());
|
||||
}
|
||||
}
|
||||
|
||||
void LevellingUtil::timeout()
|
||||
{
|
||||
QMutexLocker locker(&m_measurementMutex);
|
||||
|
||||
stopMeasurement();
|
||||
emit timeout(tr("Calibration timed out before receiving required updates."));
|
||||
}
|
||||
|
||||
void LevellingUtil::startMeasurement()
|
||||
{
|
||||
QMutexLocker locker(&m_measurementMutex);
|
||||
|
||||
m_isMeasuring = true;
|
||||
|
||||
// Reset variables
|
||||
m_receivedAccelUpdates = 0;
|
||||
m_accelerometerX = 0;
|
||||
m_accelerometerY = 0;
|
||||
m_accelerometerZ = 0;
|
||||
|
||||
m_receivedGyroUpdates = 0;
|
||||
m_gyroX = 0;
|
||||
m_gyroY = 0;
|
||||
m_gyroZ = 0;
|
||||
|
||||
ExtensionSystem::PluginManager *pm = ExtensionSystem::PluginManager::instance();
|
||||
UAVObjectManager * uavObjectManager = pm->getObject<UAVObjectManager>();
|
||||
Q_ASSERT(uavObjectManager);
|
||||
|
||||
// Disable gyro bias correction to see raw data
|
||||
AttitudeSettings::DataFields attitudeSettingsData = AttitudeSettings::GetInstance(uavObjectManager)->getData();
|
||||
attitudeSettingsData.BiasCorrectGyro = AttitudeSettings::BIASCORRECTGYRO_FALSE;
|
||||
AttitudeSettings::GetInstance(uavObjectManager)->setData(attitudeSettingsData);
|
||||
|
||||
// Set up to receive updates for accels
|
||||
UAVDataObject *uavObject = Accels::GetInstance(uavObjectManager);
|
||||
connect(uavObject, SIGNAL(objectUpdated(UAVObject*)), this, SLOT(accelMeasurementsUpdated(UAVObject*)));
|
||||
|
||||
// Set update period for accels
|
||||
m_previousAccelMetaData = uavObject->getMetadata();
|
||||
UAVObject::Metadata newMetaData = m_previousAccelMetaData;
|
||||
UAVObject::SetFlightTelemetryUpdateMode(newMetaData, UAVObject::UPDATEMODE_PERIODIC);
|
||||
newMetaData.flightTelemetryUpdatePeriod = m_accelMeasurementRate;
|
||||
uavObject->setMetadata(newMetaData);
|
||||
|
||||
// Set up to receive updates from gyros
|
||||
uavObject = Gyros::GetInstance(uavObjectManager);
|
||||
connect(uavObject, SIGNAL(objectUpdated(UAVObject*)), this, SLOT(gyroMeasurementsUpdated(UAVObject*)));
|
||||
|
||||
// Set update period for gyros
|
||||
m_previousGyroMetaData = uavObject->getMetadata();
|
||||
newMetaData = m_previousGyroMetaData;
|
||||
UAVObject::SetFlightTelemetryUpdateMode(newMetaData, UAVObject::UPDATEMODE_PERIODIC);
|
||||
newMetaData.flightTelemetryUpdatePeriod = m_gyroMeasurementRate;
|
||||
uavObject->setMetadata(newMetaData);
|
||||
}
|
||||
|
||||
void LevellingUtil::stopMeasurement()
|
||||
{
|
||||
m_isMeasuring = false;
|
||||
|
||||
//Stop timeout timer
|
||||
m_timeoutTimer.stop();
|
||||
disconnect(&m_timeoutTimer, SIGNAL(timeout()), this, SLOT(timeout()));
|
||||
|
||||
ExtensionSystem::PluginManager *pm = ExtensionSystem::PluginManager::instance();
|
||||
UAVObjectManager * uavObjectManager = pm->getObject<UAVObjectManager>();
|
||||
Q_ASSERT(uavObjectManager);
|
||||
|
||||
// Stop listening for updates from accels
|
||||
UAVDataObject *uavObject = Accels::GetInstance(uavObjectManager);
|
||||
disconnect(uavObject, SIGNAL(objectUpdated(UAVObject*)), this, SLOT(accelMeasurementsUpdated(UAVObject*)));
|
||||
uavObject->setMetadata(m_previousAccelMetaData);
|
||||
|
||||
// Stop listening for updates from gyros
|
||||
uavObject = Gyros::GetInstance(uavObjectManager);
|
||||
disconnect(uavObject, SIGNAL(objectUpdated(UAVObject*)), this, SLOT(gyroMeasurementsUpdated(UAVObject*)));
|
||||
uavObject->setMetadata(m_previousGyroMetaData);
|
||||
|
||||
// Enable gyro bias correction again
|
||||
AttitudeSettings::DataFields attitudeSettingsData = AttitudeSettings::GetInstance(uavObjectManager)->getData();
|
||||
attitudeSettingsData.BiasCorrectGyro = AttitudeSettings::BIASCORRECTGYRO_TRUE;
|
||||
AttitudeSettings::GetInstance(uavObjectManager)->setData(attitudeSettingsData);
|
||||
}
|
||||
|
||||
accelGyroBias LevellingUtil::calculateLevellingData()
|
||||
{
|
||||
accelGyroBias bias;
|
||||
bias.m_accelerometerXBias = m_accelerometerX / (double)m_receivedAccelUpdates / ACCELERATION_SCALE;
|
||||
bias.m_accelerometerYBias = m_accelerometerY / (double)m_receivedAccelUpdates / ACCELERATION_SCALE;
|
||||
bias.m_accelerometerZBias = (m_accelerometerZ / (double)m_receivedAccelUpdates + G) / ACCELERATION_SCALE;
|
||||
|
||||
bias.m_gyroXBias = m_gyroX / (double)m_receivedGyroUpdates * 100.0;
|
||||
bias.m_gyroYBias = m_gyroY / (double)m_receivedGyroUpdates * 100.0;
|
||||
bias.m_gyroZBias = m_gyroZ / (double)m_receivedGyroUpdates * 100.0;
|
||||
return bias;
|
||||
}
|
||||
|
92
ground/openpilotgcs/src/plugins/setupwizard/levellingutil.h
Normal file
@ -0,0 +1,92 @@
|
||||
/**
|
||||
******************************************************************************
|
||||
*
|
||||
* @file levellingutil.h
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012.
|
||||
* @addtogroup
|
||||
* @{
|
||||
* @addtogroup LevellingUtil
|
||||
* @{
|
||||
* @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 LEVELLINGUTIL_H
|
||||
#define LEVELLINGUTIL_H
|
||||
|
||||
#include <QObject>
|
||||
#include <QTimer>
|
||||
#include <QMutex>
|
||||
|
||||
#include "uavobject.h"
|
||||
#include "vehicleconfigurationsource.h"
|
||||
|
||||
class LevellingUtil : public QObject
|
||||
{
|
||||
Q_OBJECT
|
||||
public:
|
||||
explicit LevellingUtil(long measurementCount, long measurementRate);
|
||||
explicit LevellingUtil(long accelMeasurementCount, long accelMeasurementRate,
|
||||
long gyroMeasurementCount, long gyroMeasurementRate);
|
||||
|
||||
signals:
|
||||
void progress(long current, long total);
|
||||
void done(accelGyroBias measuredBias);
|
||||
void timeout(QString message);
|
||||
|
||||
public slots:
|
||||
void start();
|
||||
void abort();
|
||||
|
||||
private slots:
|
||||
void gyroMeasurementsUpdated(UAVObject * obj);
|
||||
void accelMeasurementsUpdated(UAVObject * obj);
|
||||
void timeout();
|
||||
|
||||
private:
|
||||
static const float G = 9.81f;
|
||||
static const float ACCELERATION_SCALE = 0.004f * 9.81f;
|
||||
|
||||
QMutex m_measurementMutex;
|
||||
QTimer m_timeoutTimer;
|
||||
|
||||
bool m_isMeasuring;
|
||||
long m_receivedAccelUpdates;
|
||||
long m_receivedGyroUpdates;
|
||||
|
||||
long m_accelMeasurementCount;
|
||||
long m_gyroMeasurementCount;
|
||||
long m_accelMeasurementRate;
|
||||
long m_gyroMeasurementRate;
|
||||
|
||||
UAVObject::Metadata m_previousGyroMetaData;
|
||||
UAVObject::Metadata m_previousAccelMetaData;
|
||||
|
||||
double m_accelerometerX;
|
||||
double m_accelerometerY;
|
||||
double m_accelerometerZ;
|
||||
double m_gyroX;
|
||||
double m_gyroY;
|
||||
double m_gyroZ;
|
||||
|
||||
void stop();
|
||||
void startMeasurement();
|
||||
void stopMeasurement();
|
||||
accelGyroBias calculateLevellingData();
|
||||
};
|
||||
|
||||
#endif // LEVELLINGUTIL_H
|
@ -0,0 +1,115 @@
|
||||
/**
|
||||
******************************************************************************
|
||||
*
|
||||
* @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"
|
||||
#include "vehicleconfigurationhelper.h"
|
||||
#include "manualcontrolsettings.h"
|
||||
|
||||
OutputCalibrationUtil::OutputCalibrationUtil(QObject *parent) :
|
||||
QObject(parent), m_outputChannel(-1), m_safeValue(1000)
|
||||
{
|
||||
ExtensionSystem::PluginManager *pm = ExtensionSystem::PluginManager::instance();
|
||||
m_uavObjectManager = pm->getObject<UAVObjectManager>();
|
||||
Q_ASSERT(m_uavObjectManager);
|
||||
}
|
||||
|
||||
OutputCalibrationUtil::~OutputCalibrationUtil()
|
||||
{
|
||||
stopChannelOutput();
|
||||
}
|
||||
|
||||
void OutputCalibrationUtil::startChannelOutput(quint16 channel, quint16 safeValue)
|
||||
{
|
||||
if(m_outputChannel < 0 && channel >= 0 && channel < ActuatorCommand::CHANNEL_NUMELEM)
|
||||
{
|
||||
//Start output...
|
||||
m_outputChannel = channel;
|
||||
m_safeValue = safeValue;
|
||||
|
||||
qDebug() << "Starting output for channel " << m_outputChannel << "...";
|
||||
|
||||
ActuatorCommand *actuatorCommand = ActuatorCommand::GetInstance(m_uavObjectManager);
|
||||
Q_ASSERT(actuatorCommand);
|
||||
UAVObject::Metadata metaData = actuatorCommand->getMetadata();
|
||||
m_savedActuatorCommandMetadata = metaData;
|
||||
|
||||
//Store current data for later restore
|
||||
m_savedActuatorCommandData = actuatorCommand->getData();
|
||||
|
||||
//Enable actuator control from GCS...
|
||||
//Store current metadata for later restore
|
||||
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;
|
||||
|
||||
//Apply changes
|
||||
actuatorCommand->setMetadata(metaData);
|
||||
actuatorCommand->updated();
|
||||
|
||||
qDebug() << "Output for channel " << m_outputChannel << " started.";
|
||||
}
|
||||
}
|
||||
|
||||
void OutputCalibrationUtil::stopChannelOutput()
|
||||
{
|
||||
if(m_outputChannel >= 0)
|
||||
{
|
||||
qDebug() << "Stopping output for channel " << m_outputChannel << "...";
|
||||
//Stop output...
|
||||
setChannelOutputValue(m_safeValue);
|
||||
qDebug() << "Settings output for channel " << m_outputChannel << " to " << m_safeValue;
|
||||
|
||||
// Restore metadata to what it was before
|
||||
ActuatorCommand *actuatorCommand = ActuatorCommand::GetInstance(m_uavObjectManager);
|
||||
Q_ASSERT(actuatorCommand);
|
||||
//actuatorCommand->setData(m_savedActuatorCommandData);
|
||||
actuatorCommand->setMetadata(m_savedActuatorCommandMetadata);
|
||||
actuatorCommand->updated();
|
||||
|
||||
qDebug() << "Output for channel " << m_outputChannel << " stopped.";
|
||||
|
||||
m_outputChannel = -1;
|
||||
}
|
||||
}
|
||||
|
||||
void OutputCalibrationUtil::setChannelOutputValue(quint16 value)
|
||||
{
|
||||
if(m_outputChannel >= 0)
|
||||
{
|
||||
//Set output value
|
||||
qDebug() << "Setting output value for channel " << m_outputChannel << " to " << value << ".";
|
||||
ActuatorCommand *actuatorCommand = ActuatorCommand::GetInstance(m_uavObjectManager);
|
||||
Q_ASSERT(actuatorCommand);
|
||||
ActuatorCommand::DataFields data = actuatorCommand->getData();
|
||||
data.Channel[m_outputChannel] = value;
|
||||
actuatorCommand->setData(data);
|
||||
}
|
||||
}
|
@ -0,0 +1,62 @@
|
||||
/**
|
||||
******************************************************************************
|
||||
*
|
||||
* @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 <QList>
|
||||
#include "uavobject.h"
|
||||
#include "uavobjectmanager.h"
|
||||
#include "vehicleconfigurationsource.h"
|
||||
#include "actuatorcommand.h"
|
||||
|
||||
|
||||
class OutputCalibrationUtil : public QObject
|
||||
{
|
||||
Q_OBJECT
|
||||
public:
|
||||
explicit OutputCalibrationUtil(QObject *parent = 0);
|
||||
~OutputCalibrationUtil();
|
||||
|
||||
signals:
|
||||
|
||||
public slots:
|
||||
void startChannelOutput(quint16 channel, quint16 safeValue);
|
||||
void stopChannelOutput();
|
||||
|
||||
void setChannelOutputValue(quint16 value);
|
||||
|
||||
private:
|
||||
qint16 m_outputChannel;
|
||||
quint16 m_safeValue;
|
||||
UAVObject::Metadata m_savedActuatorCommandMetadata;
|
||||
ActuatorCommand::DataFields m_savedActuatorCommandData;
|
||||
UAVObjectManager *m_uavObjectManager;
|
||||
};
|
||||
|
||||
#endif // OUTPUTCALIBRATIONUTIL_H
|
@ -0,0 +1,35 @@
|
||||
/**
|
||||
******************************************************************************
|
||||
*
|
||||
* @file abstractwizardpage.cpp
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012.
|
||||
* @addtogroup
|
||||
* @{
|
||||
* @addtogroup AbstractWizardPage
|
||||
* @{
|
||||
* @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 "abstractwizardpage.h"
|
||||
|
||||
AbstractWizardPage::AbstractWizardPage(SetupWizard* wizard, QWidget *parent) :
|
||||
QWizardPage(parent)
|
||||
{
|
||||
m_wizard = wizard;
|
||||
setFixedSize(600, 400);
|
||||
}
|
@ -0,0 +1,48 @@
|
||||
/**
|
||||
******************************************************************************
|
||||
*
|
||||
* @file abstractwizardpage.h
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012.
|
||||
* @addtogroup
|
||||
* @{
|
||||
* @addtogroup AbstractWizardPage
|
||||
* @{
|
||||
* @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 ABSTRACTWIZARDPAGE_H
|
||||
#define ABSTRACTWIZARDPAGE_H
|
||||
|
||||
#include <QWizardPage>
|
||||
#include "setupwizard.h"
|
||||
|
||||
class AbstractWizardPage : public QWizardPage
|
||||
{
|
||||
Q_OBJECT
|
||||
protected:
|
||||
explicit AbstractWizardPage(SetupWizard *wizard, QWidget *parent = 0);
|
||||
|
||||
private:
|
||||
SetupWizard *m_wizard;
|
||||
|
||||
public:
|
||||
SetupWizard* getWizard() { return m_wizard; }
|
||||
|
||||
};
|
||||
|
||||
#endif // ABSTRACTWIZARDPAGE_H
|
@ -0,0 +1,212 @@
|
||||
/**
|
||||
******************************************************************************
|
||||
*
|
||||
* @file controllerpage.cpp
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012.
|
||||
* @addtogroup
|
||||
* @{
|
||||
* @addtogroup ControllerPage
|
||||
* @{
|
||||
* @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 "controllerpage.h"
|
||||
#include "ui_controllerpage.h"
|
||||
#include "setupwizard.h"
|
||||
|
||||
#include <extensionsystem/pluginmanager.h>
|
||||
#include <uavobjectutil/uavobjectutilmanager.h>
|
||||
|
||||
ControllerPage::ControllerPage(SetupWizard *wizard, QWidget *parent) :
|
||||
AbstractWizardPage(wizard, parent),
|
||||
ui(new Ui::ControllerPage)
|
||||
{
|
||||
ui->setupUi(this);
|
||||
|
||||
m_connectionManager = getWizard()->getConnectionManager();
|
||||
Q_ASSERT(m_connectionManager);
|
||||
connect(m_connectionManager, SIGNAL(availableDevicesChanged(QLinkedList<Core::DevListItem>)), this, SLOT(devicesChanged(QLinkedList<Core::DevListItem>)));
|
||||
|
||||
ExtensionSystem::PluginManager *pluginManager = ExtensionSystem::PluginManager::instance();
|
||||
Q_ASSERT(pluginManager);
|
||||
m_telemtryManager = pluginManager->getObject<TelemetryManager>();
|
||||
Q_ASSERT(m_telemtryManager);
|
||||
connect(m_telemtryManager, SIGNAL(connected()), this, SLOT(connectionStatusChanged()));
|
||||
connect(m_telemtryManager, SIGNAL(disconnected()), this, SLOT(connectionStatusChanged()));
|
||||
|
||||
connect(ui->connectButton, SIGNAL(clicked()), this, SLOT(connectDisconnect()));
|
||||
|
||||
setupBoardTypes();
|
||||
setupDeviceList();
|
||||
}
|
||||
|
||||
ControllerPage::~ControllerPage()
|
||||
{
|
||||
delete ui;
|
||||
}
|
||||
|
||||
void ControllerPage::initializePage()
|
||||
{
|
||||
if(anyControllerConnected()) {
|
||||
SetupWizard::CONTROLLER_TYPE type = getControllerType();
|
||||
setControllerType(type);
|
||||
}
|
||||
else {
|
||||
setControllerType(SetupWizard::CONTROLLER_UNKNOWN);
|
||||
}
|
||||
emit completeChanged();
|
||||
}
|
||||
|
||||
bool ControllerPage::isComplete() const
|
||||
{
|
||||
return m_telemtryManager->isConnected() && ui->boardTypeCombo->currentIndex() > 0 &&
|
||||
m_connectionManager->getCurrentDevice().getConName().startsWith("USB:", Qt::CaseInsensitive);
|
||||
}
|
||||
|
||||
bool ControllerPage::validatePage()
|
||||
{
|
||||
getWizard()->setControllerType((SetupWizard::CONTROLLER_TYPE)ui->boardTypeCombo->itemData(ui->boardTypeCombo->currentIndex()).toInt());
|
||||
return true;
|
||||
}
|
||||
|
||||
bool ControllerPage::anyControllerConnected()
|
||||
{
|
||||
return m_telemtryManager->isConnected();
|
||||
}
|
||||
|
||||
SetupWizard::CONTROLLER_TYPE ControllerPage::getControllerType()
|
||||
{
|
||||
ExtensionSystem::PluginManager *pm = ExtensionSystem::PluginManager::instance();
|
||||
UAVObjectUtilManager* utilMngr = pm->getObject<UAVObjectUtilManager>();
|
||||
int id = utilMngr->getBoardModel();
|
||||
|
||||
switch (id) {
|
||||
case 0x0301:
|
||||
return SetupWizard::CONTROLLER_PIPX;
|
||||
case 0x0401:
|
||||
return SetupWizard::CONTROLLER_CC;
|
||||
case 0x0402:
|
||||
return SetupWizard::CONTROLLER_CC3D;
|
||||
case 0x0901:
|
||||
return SetupWizard::CONTROLLER_REVO;
|
||||
default:
|
||||
return SetupWizard::CONTROLLER_UNKNOWN;
|
||||
}
|
||||
}
|
||||
|
||||
void ControllerPage::setupDeviceList()
|
||||
{
|
||||
devicesChanged(m_connectionManager->getAvailableDevices());
|
||||
connectionStatusChanged();
|
||||
}
|
||||
|
||||
void ControllerPage::setupBoardTypes()
|
||||
{
|
||||
QVariant v(0);
|
||||
ui->boardTypeCombo->addItem(tr("<Unknown>"), SetupWizard::CONTROLLER_UNKNOWN);
|
||||
ui->boardTypeCombo->addItem(tr("OpenPilot CopterControl"), SetupWizard::CONTROLLER_CC);
|
||||
ui->boardTypeCombo->addItem(tr("OpenPilot CopterControl 3D"), SetupWizard::CONTROLLER_CC3D);
|
||||
ui->boardTypeCombo->addItem(tr("OpenPilot Revolution"), SetupWizard::CONTROLLER_REVO);
|
||||
//ui->boardTypeCombo->model()->setData(ui->boardTypeCombo->model()->index(ui->boardTypeCombo->count() - 1, 0), v, Qt::UserRole - 1);
|
||||
ui->boardTypeCombo->addItem(tr("OpenPilot PipX Radio Modem"), SetupWizard::CONTROLLER_PIPX);
|
||||
//ui->boardTypeCombo->model()->setData(ui->boardTypeCombo->model()->index(ui->boardTypeCombo->count() - 1, 0), v, Qt::UserRole - 1);
|
||||
}
|
||||
|
||||
void ControllerPage::setControllerType(SetupWizard::CONTROLLER_TYPE type)
|
||||
{
|
||||
for(int i = 0; i < ui->boardTypeCombo->count(); ++i) {
|
||||
if(ui->boardTypeCombo->itemData(i) == type) {
|
||||
ui->boardTypeCombo->setCurrentIndex(i);
|
||||
break;
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
void ControllerPage::devicesChanged(QLinkedList<Core::DevListItem> devices)
|
||||
{
|
||||
// Get the selected item before the update if any
|
||||
QString currSelectedDeviceName = ui->deviceCombo->currentIndex() != -1 ?
|
||||
ui->deviceCombo->itemData(ui->deviceCombo->currentIndex(), Qt::ToolTipRole).toString() : "";
|
||||
|
||||
// Clear the box
|
||||
ui->deviceCombo->clear();
|
||||
|
||||
int indexOfSelectedItem = -1;
|
||||
int i = 0;
|
||||
|
||||
// Loop and fill the combo with items from connectionmanager
|
||||
foreach (Core::DevListItem deviceItem, devices)
|
||||
{
|
||||
ui->deviceCombo->addItem(deviceItem.getConName());
|
||||
QString deviceName = (const QString)deviceItem.getConName();
|
||||
ui->deviceCombo->setItemData(ui->deviceCombo->count() - 1, deviceName, Qt::ToolTipRole);
|
||||
if(!deviceName.startsWith("USB:", Qt::CaseInsensitive)) {
|
||||
ui->deviceCombo->setItemData(ui->deviceCombo->count() - 1, QVariant(0), Qt::UserRole - 1);
|
||||
}
|
||||
if(currSelectedDeviceName != "" && currSelectedDeviceName == deviceName) {
|
||||
indexOfSelectedItem = i;
|
||||
}
|
||||
i++;
|
||||
}
|
||||
|
||||
// Re select the item that was selected before if any
|
||||
if(indexOfSelectedItem != -1) {
|
||||
ui->deviceCombo->setCurrentIndex(indexOfSelectedItem);
|
||||
}
|
||||
//connectionStatusChanged();
|
||||
}
|
||||
|
||||
void ControllerPage::connectionStatusChanged()
|
||||
{
|
||||
if(m_connectionManager->isConnected()) {
|
||||
ui->deviceCombo->setEnabled(false);
|
||||
ui->connectButton->setText(tr("Disconnect"));
|
||||
ui->boardTypeCombo->setEnabled(false);
|
||||
QString connectedDeviceName = m_connectionManager->getCurrentDevice().getConName();
|
||||
for(int i = 0; i < ui->deviceCombo->count(); ++i) {
|
||||
if(connectedDeviceName == ui->deviceCombo->itemData(i, Qt::ToolTipRole).toString()) {
|
||||
ui->deviceCombo->setCurrentIndex(i);
|
||||
break;
|
||||
}
|
||||
}
|
||||
|
||||
SetupWizard::CONTROLLER_TYPE type = getControllerType();
|
||||
setControllerType(type);
|
||||
qDebug() << "Connection status changed: Connected, controller type: " << getControllerType();
|
||||
}
|
||||
else {
|
||||
ui->deviceCombo->setEnabled(true);
|
||||
ui->connectButton->setText(tr("Connect"));
|
||||
ui->boardTypeCombo->setEnabled(false);
|
||||
ui->boardTypeCombo->model()->setData(ui->boardTypeCombo->model()->index(0, 0), QVariant(0), Qt::UserRole - 1);
|
||||
setControllerType(SetupWizard::CONTROLLER_UNKNOWN);
|
||||
qDebug() << "Connection status changed: Disconnected";
|
||||
}
|
||||
emit completeChanged();
|
||||
}
|
||||
|
||||
void ControllerPage::connectDisconnect()
|
||||
{
|
||||
if(m_connectionManager->isConnected()) {
|
||||
m_connectionManager->disconnectDevice();
|
||||
}
|
||||
else {
|
||||
m_connectionManager->connectDevice(m_connectionManager->findDevice(ui->deviceCombo->itemData(ui->deviceCombo->currentIndex(), Qt::ToolTipRole).toString()));
|
||||
}
|
||||
emit completeChanged();
|
||||
}
|
@ -0,0 +1,68 @@
|
||||
/**
|
||||
******************************************************************************
|
||||
*
|
||||
* @file controllerpage.h
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012.
|
||||
* @addtogroup
|
||||
* @{
|
||||
* @addtogroup ControllerPage
|
||||
* @{
|
||||
* @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 CONTROLLERPAGE_H
|
||||
#define CONTROLLERPAGE_H
|
||||
|
||||
#include <coreplugin/icore.h>
|
||||
#include <coreplugin/connectionmanager.h>
|
||||
#include "setupwizard.h"
|
||||
#include "uavtalk/telemetrymanager.h"
|
||||
#include "abstractwizardpage.h"
|
||||
|
||||
namespace Ui {
|
||||
class ControllerPage;
|
||||
}
|
||||
|
||||
class ControllerPage : public AbstractWizardPage
|
||||
{
|
||||
Q_OBJECT
|
||||
|
||||
public:
|
||||
explicit ControllerPage(SetupWizard *wizard, QWidget *parent = 0);
|
||||
~ControllerPage();
|
||||
void initializePage();
|
||||
bool isComplete() const;
|
||||
bool validatePage();
|
||||
|
||||
private:
|
||||
Ui::ControllerPage *ui;
|
||||
bool anyControllerConnected();
|
||||
SetupWizard::CONTROLLER_TYPE getControllerType();
|
||||
void setupDeviceList();
|
||||
void setupBoardTypes();
|
||||
void setControllerType(SetupWizard::CONTROLLER_TYPE type);
|
||||
Core::ConnectionManager *m_connectionManager;
|
||||
TelemetryManager *m_telemtryManager;
|
||||
|
||||
private slots:
|
||||
void devicesChanged(QLinkedList<Core::DevListItem> devices);
|
||||
void connectionStatusChanged();
|
||||
void connectDisconnect();
|
||||
};
|
||||
|
||||
#endif // CONTROLLERPAGE_H
|
@ -0,0 +1,127 @@
|
||||
<?xml version="1.0" encoding="UTF-8"?>
|
||||
<ui version="4.0">
|
||||
<class>ControllerPage</class>
|
||||
<widget class="QWizardPage" name="ControllerPage">
|
||||
<property name="geometry">
|
||||
<rect>
|
||||
<x>0</x>
|
||||
<y>0</y>
|
||||
<width>600</width>
|
||||
<height>400</height>
|
||||
</rect>
|
||||
</property>
|
||||
<property name="windowTitle">
|
||||
<string>WizardPage</string>
|
||||
</property>
|
||||
<widget class="QLabel" name="label">
|
||||
<property name="geometry">
|
||||
<rect>
|
||||
<x>20</x>
|
||||
<y>20</y>
|
||||
<width>550</width>
|
||||
<height>261</height>
|
||||
</rect>
|
||||
</property>
|
||||
<property name="text">
|
||||
<string><!DOCTYPE HTML PUBLIC "-//W3C//DTD HTML 4.0//EN" "http://www.w3.org/TR/REC-html40/strict.dtd">
|
||||
<html><head><meta name="qrichtext" content="1" /><style type="text/css">
|
||||
p, li { white-space: pre-wrap; }
|
||||
</style></head><body style=" font-family:'MS Shell Dlg 2'; font-size:8pt; font-weight:400; font-style:normal;">
|
||||
<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-size:12pt; font-weight:600;">OpenPilot board identification</span></p>
|
||||
<p style="-qt-paragraph-type:empty; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><br /></p>
|
||||
<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-size:10pt;">To continue, the wizard needs to determine the configuration required for the type of OpenPilot controller you have. When connected, the wizard will attempt to automatically detect the type of board.</span></p>
|
||||
<p style="-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;"><br /></p>
|
||||
<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-size:10pt;">If the board is already connected and successfully detected, the board type will already be displayed. You can </span><span style=" font-size:10pt; font-weight:600;">Disconnect</span><span style=" font-size:10pt;"> and select another device if you need to detect another board.</span></p>
|
||||
<p style="-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;"><br /></p>
|
||||
<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-size:10pt;">If your board is not connected, please connect the board to a USB port on your computer and select the device from the list below. Then press </span><span style=" font-size:10pt; font-weight:600;">Connect</span><span style=" font-size:10pt;">.</span></p></body></html></string>
|
||||
</property>
|
||||
<property name="textFormat">
|
||||
<enum>Qt::AutoText</enum>
|
||||
</property>
|
||||
<property name="alignment">
|
||||
<set>Qt::AlignLeading|Qt::AlignLeft|Qt::AlignTop</set>
|
||||
</property>
|
||||
<property name="wordWrap">
|
||||
<bool>true</bool>
|
||||
</property>
|
||||
</widget>
|
||||
<widget class="QPushButton" name="connectButton">
|
||||
<property name="geometry">
|
||||
<rect>
|
||||
<x>460</x>
|
||||
<y>350</y>
|
||||
<width>100</width>
|
||||
<height>23</height>
|
||||
</rect>
|
||||
</property>
|
||||
<property name="text">
|
||||
<string>Connect</string>
|
||||
</property>
|
||||
</widget>
|
||||
<widget class="QLabel" name="label_3">
|
||||
<property name="geometry">
|
||||
<rect>
|
||||
<x>40</x>
|
||||
<y>350</y>
|
||||
<width>125</width>
|
||||
<height>16</height>
|
||||
</rect>
|
||||
</property>
|
||||
<property name="font">
|
||||
<font>
|
||||
<pointsize>10</pointsize>
|
||||
<weight>50</weight>
|
||||
<bold>false</bold>
|
||||
</font>
|
||||
</property>
|
||||
<property name="text">
|
||||
<string>Detected board type:</string>
|
||||
</property>
|
||||
</widget>
|
||||
<widget class="QComboBox" name="boardTypeCombo">
|
||||
<property name="enabled">
|
||||
<bool>false</bool>
|
||||
</property>
|
||||
<property name="geometry">
|
||||
<rect>
|
||||
<x>170</x>
|
||||
<y>350</y>
|
||||
<width>279</width>
|
||||
<height>22</height>
|
||||
</rect>
|
||||
</property>
|
||||
</widget>
|
||||
<widget class="QComboBox" name="deviceCombo">
|
||||
<property name="geometry">
|
||||
<rect>
|
||||
<x>170</x>
|
||||
<y>310</y>
|
||||
<width>279</width>
|
||||
<height>22</height>
|
||||
</rect>
|
||||
</property>
|
||||
</widget>
|
||||
<widget class="QLabel" name="label_2">
|
||||
<property name="geometry">
|
||||
<rect>
|
||||
<x>40</x>
|
||||
<y>310</y>
|
||||
<width>121</width>
|
||||
<height>16</height>
|
||||
</rect>
|
||||
</property>
|
||||
<property name="font">
|
||||
<font>
|
||||
<pointsize>10</pointsize>
|
||||
<weight>50</weight>
|
||||
<bold>false</bold>
|
||||
</font>
|
||||
</property>
|
||||
<property name="text">
|
||||
<string>Connection device:</string>
|
||||
</property>
|
||||
</widget>
|
||||
</widget>
|
||||
<resources/>
|
||||
<connections/>
|
||||
</ui>
|
@ -0,0 +1,65 @@
|
||||
/**
|
||||
******************************************************************************
|
||||
*
|
||||
* @file endpage.cpp
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012.
|
||||
* @addtogroup GCSPlugins GCS Plugins
|
||||
* @{
|
||||
* @addtogroup Setup Wizard Plugin
|
||||
* @{
|
||||
* @brief A Wizard to make the initial setup easy for everyone.
|
||||
*****************************************************************************/
|
||||
/*
|
||||
* 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 "endpage.h"
|
||||
#include "ui_endpage.h"
|
||||
#include <coreplugin/modemanager.h>
|
||||
#include <extensionsystem/pluginmanager.h>
|
||||
#include <configgadgetfactory.h>
|
||||
#include <QMessageBox>
|
||||
|
||||
EndPage::EndPage(SetupWizard *wizard, QWidget *parent) :
|
||||
AbstractWizardPage(wizard, parent),
|
||||
ui(new Ui::EndPage)
|
||||
{
|
||||
ui->setupUi(this);
|
||||
setFinalPage(true);
|
||||
connect(ui->inputWizardButton, SIGNAL(clicked()), this, SLOT(openInputWizard()));
|
||||
}
|
||||
|
||||
EndPage::~EndPage()
|
||||
{
|
||||
delete ui;
|
||||
}
|
||||
|
||||
void EndPage::openInputWizard()
|
||||
{
|
||||
ExtensionSystem::PluginManager *pm = ExtensionSystem::PluginManager::instance();
|
||||
ConfigGadgetFactory* configGadgetFactory = pm->getObject<ConfigGadgetFactory>();
|
||||
|
||||
if(configGadgetFactory) {
|
||||
//Core::ModeManager::instance()->activateModeByWorkspaceName("Configuration");
|
||||
getWizard()->close();
|
||||
configGadgetFactory->startInputWizard();
|
||||
}
|
||||
else {
|
||||
QMessageBox msgBox;
|
||||
msgBox.setText(tr("Unable to open Input Wizard since the Config Plugin is not\nloaded in the current workspace."));
|
||||
msgBox.setStandardButtons(QMessageBox::Ok);
|
||||
msgBox.setDefaultButton(QMessageBox::Ok);
|
||||
msgBox.exec();
|
||||
}
|
||||
}
|
52
ground/openpilotgcs/src/plugins/setupwizard/pages/endpage.h
Normal file
@ -0,0 +1,52 @@
|
||||
/**
|
||||
******************************************************************************
|
||||
*
|
||||
* @file endpage.h
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012.
|
||||
* @addtogroup
|
||||
* @{
|
||||
* @addtogroup
|
||||
* @{
|
||||
* @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 ENDPAGE_H
|
||||
#define ENDPAGE_H
|
||||
|
||||
#include "abstractwizardpage.h"
|
||||
|
||||
namespace Ui {
|
||||
class EndPage;
|
||||
}
|
||||
|
||||
class EndPage : public AbstractWizardPage
|
||||
{
|
||||
Q_OBJECT
|
||||
|
||||
public:
|
||||
explicit EndPage(SetupWizard *wizard, QWidget *parent = 0);
|
||||
~EndPage();
|
||||
|
||||
private slots:
|
||||
void openInputWizard();
|
||||
|
||||
private:
|
||||
Ui::EndPage *ui;
|
||||
};
|
||||
|
||||
#endif // ENDPAGE_H
|
88
ground/openpilotgcs/src/plugins/setupwizard/pages/endpage.ui
Normal file
@ -0,0 +1,88 @@
|
||||
<?xml version="1.0" encoding="UTF-8"?>
|
||||
<ui version="4.0">
|
||||
<class>EndPage</class>
|
||||
<widget class="QWizardPage" name="EndPage">
|
||||
<property name="geometry">
|
||||
<rect>
|
||||
<x>0</x>
|
||||
<y>0</y>
|
||||
<width>600</width>
|
||||
<height>400</height>
|
||||
</rect>
|
||||
</property>
|
||||
<property name="minimumSize">
|
||||
<size>
|
||||
<width>600</width>
|
||||
<height>400</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="windowTitle">
|
||||
<string>WizardPage</string>
|
||||
</property>
|
||||
<widget class="QLabel" name="label_2">
|
||||
<property name="geometry">
|
||||
<rect>
|
||||
<x>20</x>
|
||||
<y>20</y>
|
||||
<width>550</width>
|
||||
<height>251</height>
|
||||
</rect>
|
||||
</property>
|
||||
<property name="text">
|
||||
<string><!DOCTYPE HTML PUBLIC "-//W3C//DTD HTML 4.0//EN" "http://www.w3.org/TR/REC-html40/strict.dtd">
|
||||
<html><head><meta name="qrichtext" content="1" /><style type="text/css">
|
||||
p, li { white-space: pre-wrap; }
|
||||
</style></head><body style=" font-family:'MS Shell Dlg 2'; font-size:8pt; font-weight:400; font-style:normal;">
|
||||
<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-size:12pt; font-weight:600;">Congratulations!</span></p>
|
||||
<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-size:12pt; font-weight:600;">Setup wizard is completed.</span></p>
|
||||
<p style="-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;"><br /></p>
|
||||
<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-size:10pt;">This part of the setup procedure is now complete and you are one step away from completing the setup of your OpenPilot controller.</span></p>
|
||||
<p style="-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;"><br /></p>
|
||||
<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-size:10pt;">To complete the setup please click the Radio Setup Wizard button below to close this wizard and go directly to the Radio Setup Wizard.</span></p>
|
||||
<p style="-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;"><br /></p></body></html></string>
|
||||
</property>
|
||||
<property name="alignment">
|
||||
<set>Qt::AlignLeading|Qt::AlignLeft|Qt::AlignTop</set>
|
||||
</property>
|
||||
<property name="wordWrap">
|
||||
<bool>true</bool>
|
||||
</property>
|
||||
</widget>
|
||||
<widget class="QToolButton" name="inputWizardButton">
|
||||
<property name="geometry">
|
||||
<rect>
|
||||
<x>200</x>
|
||||
<y>270</y>
|
||||
<width>200</width>
|
||||
<height>100</height>
|
||||
</rect>
|
||||
</property>
|
||||
<property name="styleSheet">
|
||||
<string notr="true">QToolButton { border: none }</string>
|
||||
</property>
|
||||
<property name="text">
|
||||
<string>Go to Input Wizard...</string>
|
||||
</property>
|
||||
<property name="icon">
|
||||
<iconset resource="../wizardResources.qrc">
|
||||
<normaloff>:/setupwizard/resources/bttn-txwizard-off.png</normaloff>
|
||||
<normalon>:/setupwizard/resources/bttn-txwizard-on.png</normalon>
|
||||
<activeoff>:/setupwizard/resources/bttn-txwizard-off.png</activeoff>
|
||||
<activeon>:/setupwizard/resources/bttn-txwizard-off.png</activeon>:/setupwizard/resources/bttn-txwizard-off.png</iconset>
|
||||
</property>
|
||||
<property name="iconSize">
|
||||
<size>
|
||||
<width>200</width>
|
||||
<height>100</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="autoRaise">
|
||||
<bool>true</bool>
|
||||
</property>
|
||||
</widget>
|
||||
</widget>
|
||||
<resources>
|
||||
<include location="../wizardResources.qrc"/>
|
||||
</resources>
|
||||
<connections/>
|
||||
</ui>
|
@ -0,0 +1,42 @@
|
||||
/**
|
||||
******************************************************************************
|
||||
*
|
||||
* @file fixedwingpage.cpp
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012.
|
||||
* @addtogroup
|
||||
* @{
|
||||
* @addtogroup FixedWingPage
|
||||
* @{
|
||||
* @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 "fixedwingpage.h"
|
||||
#include "ui_fixedwingpage.h"
|
||||
|
||||
FixedWingPage::FixedWingPage(SetupWizard *wizard, QWidget *parent) :
|
||||
AbstractWizardPage(wizard, parent),
|
||||
ui(new Ui::FixedWingPage)
|
||||
{
|
||||
ui->setupUi(this);
|
||||
setFinalPage(true);
|
||||
}
|
||||
|
||||
FixedWingPage::~FixedWingPage()
|
||||
{
|
||||
delete ui;
|
||||
}
|
@ -0,0 +1,49 @@
|
||||
/**
|
||||
******************************************************************************
|
||||
*
|
||||
* @file fixedwingpage.h
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012.
|
||||
* @addtogroup
|
||||
* @{
|
||||
* @addtogroup FixedWingPage
|
||||
* @{
|
||||
* @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 FIXEDWINGPAGE_H
|
||||
#define FIXEDWINGPAGE_H
|
||||
|
||||
#include "abstractwizardpage.h"
|
||||
|
||||
namespace Ui {
|
||||
class FixedWingPage;
|
||||
}
|
||||
|
||||
class FixedWingPage : public AbstractWizardPage
|
||||
{
|
||||
Q_OBJECT
|
||||
|
||||
public:
|
||||
explicit FixedWingPage(SetupWizard *wizard, QWidget *parent = 0);
|
||||
~FixedWingPage();
|
||||
|
||||
private:
|
||||
Ui::FixedWingPage *ui;
|
||||
};
|
||||
|
||||
#endif // FIXEDWINGPAGE_H
|
@ -0,0 +1,43 @@
|
||||
<?xml version="1.0" encoding="UTF-8"?>
|
||||
<ui version="4.0">
|
||||
<class>FixedWingPage</class>
|
||||
<widget class="QWizardPage" name="FixedWingPage">
|
||||
<property name="geometry">
|
||||
<rect>
|
||||
<x>0</x>
|
||||
<y>0</y>
|
||||
<width>600</width>
|
||||
<height>400</height>
|
||||
</rect>
|
||||
</property>
|
||||
<property name="windowTitle">
|
||||
<string>WizardPage</string>
|
||||
</property>
|
||||
<widget class="QLabel" name="label_2">
|
||||
<property name="geometry">
|
||||
<rect>
|
||||
<x>50</x>
|
||||
<y>160</y>
|
||||
<width>500</width>
|
||||
<height>41</height>
|
||||
</rect>
|
||||
</property>
|
||||
<property name="text">
|
||||
<string><!DOCTYPE HTML PUBLIC "-//W3C//DTD HTML 4.0//EN" "http://www.w3.org/TR/REC-html40/strict.dtd">
|
||||
<html><head><meta name="qrichtext" content="1" /><style type="text/css">
|
||||
p, li { white-space: pre-wrap; }
|
||||
</style></head><body style=" font-family:'MS Shell Dlg 2'; font-size:8.25pt; font-weight:400; font-style:normal;">
|
||||
<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-size:12pt; font-weight:600;">The Fixed Wing section of the OpenPilot Setup Wizard is not yet implemented</span></p>
|
||||
<p style="-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:8pt;"></p></body></html></string>
|
||||
</property>
|
||||
<property name="alignment">
|
||||
<set>Qt::AlignHCenter|Qt::AlignTop</set>
|
||||
</property>
|
||||
<property name="wordWrap">
|
||||
<bool>true</bool>
|
||||
</property>
|
||||
</widget>
|
||||
</widget>
|
||||
<resources/>
|
||||
<connections/>
|
||||
</ui>
|
@ -0,0 +1,42 @@
|
||||
/**
|
||||
******************************************************************************
|
||||
*
|
||||
* @file helipage.cpp
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012.
|
||||
* @addtogroup
|
||||
* @{
|
||||
* @addtogroup HeliPage
|
||||
* @{
|
||||
* @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 "helipage.h"
|
||||
#include "ui_helipage.h"
|
||||
|
||||
HeliPage::HeliPage(SetupWizard *wizard, QWidget *parent) :
|
||||
AbstractWizardPage(wizard, parent),
|
||||
ui(new Ui::HeliPage)
|
||||
{
|
||||
ui->setupUi(this);
|
||||
setFinalPage(true);
|
||||
}
|
||||
|
||||
HeliPage::~HeliPage()
|
||||
{
|
||||
delete ui;
|
||||
}
|
49
ground/openpilotgcs/src/plugins/setupwizard/pages/helipage.h
Normal file
@ -0,0 +1,49 @@
|
||||
/**
|
||||
******************************************************************************
|
||||
*
|
||||
* @file helipage.h
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012.
|
||||
* @addtogroup
|
||||
* @{
|
||||
* @addtogroup HeliPage
|
||||
* @{
|
||||
* @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 HELIPAGE_H
|
||||
#define HELIPAGE_H
|
||||
|
||||
#include "abstractwizardpage.h"
|
||||
|
||||
namespace Ui {
|
||||
class HeliPage;
|
||||
}
|
||||
|
||||
class HeliPage : public AbstractWizardPage
|
||||
{
|
||||
Q_OBJECT
|
||||
|
||||
public:
|
||||
explicit HeliPage(SetupWizard *wizard, QWidget *parent = 0);
|
||||
~HeliPage();
|
||||
|
||||
private:
|
||||
Ui::HeliPage *ui;
|
||||
};
|
||||
|
||||
#endif // HELIPAGE_H
|
@ -0,0 +1,43 @@
|
||||
<?xml version="1.0" encoding="UTF-8"?>
|
||||
<ui version="4.0">
|
||||
<class>HeliPage</class>
|
||||
<widget class="QWizardPage" name="HeliPage">
|
||||
<property name="geometry">
|
||||
<rect>
|
||||
<x>0</x>
|
||||
<y>0</y>
|
||||
<width>600</width>
|
||||
<height>400</height>
|
||||
</rect>
|
||||
</property>
|
||||
<property name="windowTitle">
|
||||
<string>WizardPage</string>
|
||||
</property>
|
||||
<widget class="QLabel" name="label_2">
|
||||
<property name="geometry">
|
||||
<rect>
|
||||
<x>50</x>
|
||||
<y>160</y>
|
||||
<width>500</width>
|
||||
<height>41</height>
|
||||
</rect>
|
||||
</property>
|
||||
<property name="text">
|
||||
<string><!DOCTYPE HTML PUBLIC "-//W3C//DTD HTML 4.0//EN" "http://www.w3.org/TR/REC-html40/strict.dtd">
|
||||
<html><head><meta name="qrichtext" content="1" /><style type="text/css">
|
||||
p, li { white-space: pre-wrap; }
|
||||
</style></head><body style=" font-family:'MS Shell Dlg 2'; font-size:8.25pt; font-weight:400; font-style:normal;">
|
||||
<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-size:12pt; font-weight:600;">The Helicopter section of the OpenPilot Setup Wizard is not yet implemented</span></p>
|
||||
<p style="-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:8pt;"></p></body></html></string>
|
||||
</property>
|
||||
<property name="alignment">
|
||||
<set>Qt::AlignHCenter|Qt::AlignTop</set>
|
||||
</property>
|
||||
<property name="wordWrap">
|
||||
<bool>true</bool>
|
||||
</property>
|
||||
</widget>
|
||||
</widget>
|
||||
<resources/>
|
||||
<connections/>
|
||||
</ui>
|
@ -0,0 +1,91 @@
|
||||
/**
|
||||
******************************************************************************
|
||||
*
|
||||
* @file inputpage.cpp
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012.
|
||||
* @addtogroup
|
||||
* @{
|
||||
* @addtogroup InputPage
|
||||
* @{
|
||||
* @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 "inputpage.h"
|
||||
#include "ui_inputpage.h"
|
||||
#include "setupwizard.h"
|
||||
#include "extensionsystem/pluginmanager.h"
|
||||
#include "uavobjectmanager.h"
|
||||
#include "hwsettings.h"
|
||||
|
||||
InputPage::InputPage(SetupWizard *wizard, QWidget *parent) :
|
||||
AbstractWizardPage(wizard, parent),
|
||||
|
||||
ui(new Ui::InputPage)
|
||||
{
|
||||
ui->setupUi(this);
|
||||
}
|
||||
|
||||
InputPage::~InputPage()
|
||||
{
|
||||
delete ui;
|
||||
}
|
||||
|
||||
bool InputPage::validatePage()
|
||||
{
|
||||
if(ui->pwmButton->isChecked()) {
|
||||
getWizard()->setInputType(SetupWizard::INPUT_PWM);
|
||||
}
|
||||
else if(ui->ppmButton->isChecked()) {
|
||||
getWizard()->setInputType(SetupWizard::INPUT_PPM);
|
||||
}
|
||||
else if(ui->sbusButton->isChecked()) {
|
||||
getWizard()->setInputType(SetupWizard::INPUT_SBUS);
|
||||
}
|
||||
else if(ui->spectrumButton->isChecked()) {
|
||||
getWizard()->setInputType(SetupWizard::INPUT_DSM2);
|
||||
}
|
||||
else {
|
||||
getWizard()->setInputType(SetupWizard::INPUT_PWM);
|
||||
}
|
||||
getWizard()->setRestartNeeded(getWizard()->isRestartNeeded() || restartNeeded(getWizard()->getInputType()));
|
||||
|
||||
return true;
|
||||
}
|
||||
|
||||
bool InputPage::restartNeeded(VehicleConfigurationSource::INPUT_TYPE selectedType)
|
||||
{
|
||||
ExtensionSystem::PluginManager *pm = ExtensionSystem::PluginManager::instance();
|
||||
UAVObjectManager *uavoManager = pm->getObject<UAVObjectManager>();
|
||||
Q_ASSERT(uavoManager);
|
||||
HwSettings* hwSettings = HwSettings::GetInstance(uavoManager);
|
||||
HwSettings::DataFields data = hwSettings->getData();
|
||||
switch(selectedType)
|
||||
{
|
||||
case VehicleConfigurationSource::INPUT_PWM:
|
||||
return data.CC_RcvrPort != HwSettings::CC_RCVRPORT_PWM;
|
||||
case VehicleConfigurationSource::INPUT_PPM:
|
||||
return data.CC_RcvrPort != HwSettings::CC_RCVRPORT_PPM;
|
||||
case VehicleConfigurationSource::INPUT_SBUS:
|
||||
return data.CC_MainPort != HwSettings::CC_MAINPORT_SBUS;
|
||||
case VehicleConfigurationSource::INPUT_DSM2:
|
||||
// TODO: Handle all of the DSM types ?? Which is most common?
|
||||
return data.CC_MainPort != HwSettings::CC_MAINPORT_DSM2;
|
||||
default:
|
||||
return true;
|
||||
}
|
||||
}
|
@ -0,0 +1,51 @@
|
||||
/**
|
||||
******************************************************************************
|
||||
*
|
||||
* @file inputpage.h
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012.
|
||||
* @addtogroup
|
||||
* @{
|
||||
* @addtogroup InputPage
|
||||
* @{
|
||||
* @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 INPUTPAGE_H
|
||||
#define INPUTPAGE_H
|
||||
|
||||
#include "abstractwizardpage.h"
|
||||
|
||||
namespace Ui {
|
||||
class InputPage;
|
||||
}
|
||||
|
||||
class InputPage : public AbstractWizardPage
|
||||
{
|
||||
Q_OBJECT
|
||||
|
||||
public:
|
||||
explicit InputPage(SetupWizard *wizard, QWidget *parent = 0);
|
||||
~InputPage();
|
||||
bool validatePage();
|
||||
|
||||
private:
|
||||
bool restartNeeded(VehicleConfigurationSource::INPUT_TYPE selectedType);
|
||||
Ui::InputPage *ui;
|
||||
};
|
||||
|
||||
#endif // INPUTPAGE_H
|
239
ground/openpilotgcs/src/plugins/setupwizard/pages/inputpage.ui
Normal file
@ -0,0 +1,239 @@
|
||||
<?xml version="1.0" encoding="UTF-8"?>
|
||||
<ui version="4.0">
|
||||
<class>InputPage</class>
|
||||
<widget class="QWizardPage" name="InputPage">
|
||||
<property name="geometry">
|
||||
<rect>
|
||||
<x>0</x>
|
||||
<y>0</y>
|
||||
<width>600</width>
|
||||
<height>400</height>
|
||||
</rect>
|
||||
</property>
|
||||
<property name="windowTitle">
|
||||
<string>WizardPage</string>
|
||||
</property>
|
||||
<widget class="QLabel" name="label">
|
||||
<property name="geometry">
|
||||
<rect>
|
||||
<x>20</x>
|
||||
<y>20</y>
|
||||
<width>541</width>
|
||||
<height>221</height>
|
||||
</rect>
|
||||
</property>
|
||||
<property name="text">
|
||||
<string><!DOCTYPE HTML PUBLIC "-//W3C//DTD HTML 4.0//EN" "http://www.w3.org/TR/REC-html40/strict.dtd">
|
||||
<html><head><meta name="qrichtext" content="1" /><style type="text/css">
|
||||
p, li { white-space: pre-wrap; }
|
||||
</style></head><body style=" font-family:'MS Shell Dlg 2'; font-size:8pt; font-weight:400; font-style:normal;">
|
||||
<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-size:12pt; font-weight:600;">OpenPilot basic input signal configuration</span></p>
|
||||
<p style="-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;"><br /></p>
|
||||
<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-size:10pt;">The OpenPilot controller supports many different types of input signals. Please select the type of input that matches your receiver configuration. If you are unsure, just leave the default option selected and continue the wizard.</span></p>
|
||||
<p style="-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;"><br /></p>
|
||||
<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-size:10pt;">Some input options require the OpenPilot controller to be rebooted before the changes can take place. If an option that requires a reboot is selected, you will be instructed to do so on the next page of this wizard.</span></p></body></html></string>
|
||||
</property>
|
||||
<property name="alignment">
|
||||
<set>Qt::AlignLeading|Qt::AlignLeft|Qt::AlignTop</set>
|
||||
</property>
|
||||
<property name="wordWrap">
|
||||
<bool>true</bool>
|
||||
</property>
|
||||
</widget>
|
||||
<widget class="QToolButton" name="spectrumButton">
|
||||
<property name="geometry">
|
||||
<rect>
|
||||
<x>430</x>
|
||||
<y>250</y>
|
||||
<width>100</width>
|
||||
<height>120</height>
|
||||
</rect>
|
||||
</property>
|
||||
<property name="font">
|
||||
<font>
|
||||
<pointsize>10</pointsize>
|
||||
</font>
|
||||
</property>
|
||||
<property name="toolTip">
|
||||
<string>Spectrum Satellite</string>
|
||||
</property>
|
||||
<property name="styleSheet">
|
||||
<string notr="true">QToolButton { border: none }</string>
|
||||
</property>
|
||||
<property name="text">
|
||||
<string>Spectrum</string>
|
||||
</property>
|
||||
<property name="icon">
|
||||
<iconset resource="../wizardResources.qrc">
|
||||
<normaloff>:/setupwizard/resources/bttn-sat-up.png</normaloff>
|
||||
<normalon>:/setupwizard/resources/bttn-sat-down.png</normalon>:/setupwizard/resources/bttn-sat-up.png</iconset>
|
||||
</property>
|
||||
<property name="iconSize">
|
||||
<size>
|
||||
<width>100</width>
|
||||
<height>100</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="checkable">
|
||||
<bool>true</bool>
|
||||
</property>
|
||||
<property name="autoExclusive">
|
||||
<bool>true</bool>
|
||||
</property>
|
||||
<property name="toolButtonStyle">
|
||||
<enum>Qt::ToolButtonTextUnderIcon</enum>
|
||||
</property>
|
||||
<property name="autoRaise">
|
||||
<bool>true</bool>
|
||||
</property>
|
||||
</widget>
|
||||
<widget class="QToolButton" name="pwmButton">
|
||||
<property name="geometry">
|
||||
<rect>
|
||||
<x>70</x>
|
||||
<y>250</y>
|
||||
<width>100</width>
|
||||
<height>120</height>
|
||||
</rect>
|
||||
</property>
|
||||
<property name="font">
|
||||
<font>
|
||||
<pointsize>10</pointsize>
|
||||
</font>
|
||||
</property>
|
||||
<property name="toolTip">
|
||||
<string>PWM - One cable per channel</string>
|
||||
</property>
|
||||
<property name="styleSheet">
|
||||
<string notr="true">QToolButton { border: none }</string>
|
||||
</property>
|
||||
<property name="text">
|
||||
<string>PWM</string>
|
||||
</property>
|
||||
<property name="icon">
|
||||
<iconset resource="../wizardResources.qrc">
|
||||
<normaloff>:/setupwizard/resources/bttn-pwm-up.png</normaloff>
|
||||
<normalon>:/setupwizard/resources/bttn-pwm-down.png</normalon>:/setupwizard/resources/bttn-pwm-up.png</iconset>
|
||||
</property>
|
||||
<property name="iconSize">
|
||||
<size>
|
||||
<width>100</width>
|
||||
<height>100</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="checkable">
|
||||
<bool>true</bool>
|
||||
</property>
|
||||
<property name="checked">
|
||||
<bool>true</bool>
|
||||
</property>
|
||||
<property name="autoExclusive">
|
||||
<bool>true</bool>
|
||||
</property>
|
||||
<property name="toolButtonStyle">
|
||||
<enum>Qt::ToolButtonTextUnderIcon</enum>
|
||||
</property>
|
||||
<property name="autoRaise">
|
||||
<bool>true</bool>
|
||||
</property>
|
||||
</widget>
|
||||
<widget class="QToolButton" name="ppmButton">
|
||||
<property name="geometry">
|
||||
<rect>
|
||||
<x>190</x>
|
||||
<y>250</y>
|
||||
<width>100</width>
|
||||
<height>120</height>
|
||||
</rect>
|
||||
</property>
|
||||
<property name="font">
|
||||
<font>
|
||||
<pointsize>10</pointsize>
|
||||
</font>
|
||||
</property>
|
||||
<property name="toolTip">
|
||||
<string>PPM - One cable for all channels</string>
|
||||
</property>
|
||||
<property name="styleSheet">
|
||||
<string notr="true">QToolButton { border: none }</string>
|
||||
</property>
|
||||
<property name="text">
|
||||
<string>PPM</string>
|
||||
</property>
|
||||
<property name="icon">
|
||||
<iconset resource="../wizardResources.qrc">
|
||||
<normaloff>:/setupwizard/resources/bttn-ppm-up.png</normaloff>
|
||||
<normalon>:/setupwizard/resources/bttn-ppm-down.png</normalon>:/setupwizard/resources/bttn-ppm-up.png</iconset>
|
||||
</property>
|
||||
<property name="iconSize">
|
||||
<size>
|
||||
<width>100</width>
|
||||
<height>100</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="checkable">
|
||||
<bool>true</bool>
|
||||
</property>
|
||||
<property name="autoExclusive">
|
||||
<bool>true</bool>
|
||||
</property>
|
||||
<property name="toolButtonStyle">
|
||||
<enum>Qt::ToolButtonTextUnderIcon</enum>
|
||||
</property>
|
||||
<property name="autoRaise">
|
||||
<bool>true</bool>
|
||||
</property>
|
||||
</widget>
|
||||
<widget class="QToolButton" name="sbusButton">
|
||||
<property name="geometry">
|
||||
<rect>
|
||||
<x>310</x>
|
||||
<y>250</y>
|
||||
<width>100</width>
|
||||
<height>120</height>
|
||||
</rect>
|
||||
</property>
|
||||
<property name="font">
|
||||
<font>
|
||||
<pointsize>10</pointsize>
|
||||
</font>
|
||||
</property>
|
||||
<property name="toolTip">
|
||||
<string>Futaba S-BUS</string>
|
||||
</property>
|
||||
<property name="styleSheet">
|
||||
<string notr="true">QToolButton { border: none }</string>
|
||||
</property>
|
||||
<property name="text">
|
||||
<string>Futaba</string>
|
||||
</property>
|
||||
<property name="icon">
|
||||
<iconset resource="../wizardResources.qrc">
|
||||
<normaloff>:/setupwizard/resources/bttn-sbus-up.png</normaloff>
|
||||
<normalon>:/setupwizard/resources/bttn-sbus-down.png</normalon>:/setupwizard/resources/bttn-sbus-up.png</iconset>
|
||||
</property>
|
||||
<property name="iconSize">
|
||||
<size>
|
||||
<width>100</width>
|
||||
<height>100</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="checkable">
|
||||
<bool>true</bool>
|
||||
</property>
|
||||
<property name="autoExclusive">
|
||||
<bool>true</bool>
|
||||
</property>
|
||||
<property name="toolButtonStyle">
|
||||
<enum>Qt::ToolButtonTextUnderIcon</enum>
|
||||
</property>
|
||||
<property name="autoRaise">
|
||||
<bool>true</bool>
|
||||
</property>
|
||||
</widget>
|
||||
</widget>
|
||||
<resources>
|
||||
<include location="../wizardResources.qrc"/>
|
||||
</resources>
|
||||
<connections/>
|
||||
</ui>
|
@ -0,0 +1,136 @@
|
||||
/**
|
||||
******************************************************************************
|
||||
*
|
||||
* @file levellingpage.cpp
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012.
|
||||
* @addtogroup
|
||||
* @{
|
||||
* @addtogroup LevellingPage
|
||||
* @{
|
||||
* @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 <QMessageBox>
|
||||
#include <QDebug>
|
||||
#include "levellingpage.h"
|
||||
#include "ui_levellingpage.h"
|
||||
#include "setupwizard.h"
|
||||
|
||||
LevellingPage::LevellingPage(SetupWizard *wizard, QWidget *parent) :
|
||||
AbstractWizardPage(wizard, parent),
|
||||
ui(new Ui::LevellingPage), m_levellingUtil(0)
|
||||
{
|
||||
ui->setupUi(this);
|
||||
connect(ui->levelButton, SIGNAL(clicked()), this, SLOT(performLevelling()));
|
||||
}
|
||||
|
||||
LevellingPage::~LevellingPage()
|
||||
{
|
||||
if(m_levellingUtil) {
|
||||
delete m_levellingUtil;
|
||||
}
|
||||
delete ui;
|
||||
}
|
||||
|
||||
bool LevellingPage::validatePage()
|
||||
{
|
||||
return true;
|
||||
}
|
||||
|
||||
bool LevellingPage::isComplete() const
|
||||
{
|
||||
//const_cast<LevellingPage *>(this)->getWizard()->isLevellingPerformed() &&
|
||||
return ui->levelButton->isEnabled();
|
||||
}
|
||||
|
||||
void LevellingPage::enableButtons(bool enable)
|
||||
{
|
||||
ui->levelButton->setEnabled(enable);
|
||||
getWizard()->button(QWizard::NextButton)->setEnabled(enable);
|
||||
getWizard()->button(QWizard::CancelButton)->setEnabled(enable);
|
||||
getWizard()->button(QWizard::BackButton)->setEnabled(enable);
|
||||
QApplication::processEvents();
|
||||
}
|
||||
|
||||
void LevellingPage::performLevelling()
|
||||
{
|
||||
if(!getWizard()->getConnectionManager()->isConnected()) {
|
||||
QMessageBox msgBox;
|
||||
msgBox.setText(tr("An OpenPilot controller must be connected to your computer to perform bias "
|
||||
"calculations.\nPlease connect your OpenPilot controller to your computer and try again."));
|
||||
msgBox.setStandardButtons(QMessageBox::Ok);
|
||||
msgBox.setDefaultButton(QMessageBox::Ok);
|
||||
msgBox.exec();
|
||||
return;
|
||||
}
|
||||
|
||||
enableButtons(false);
|
||||
ui->progressLabel->setText(QString(tr("Retrieving data...")));
|
||||
|
||||
|
||||
if(!m_levellingUtil)
|
||||
{
|
||||
m_levellingUtil = new LevellingUtil(BIAS_CYCLES, BIAS_RATE);
|
||||
}
|
||||
|
||||
connect(m_levellingUtil, SIGNAL(progress(long,long)), this, SLOT(levellingProgress(long,long)));
|
||||
connect(m_levellingUtil, SIGNAL(done(accelGyroBias)), this, SLOT(levellingDone(accelGyroBias)));
|
||||
connect(m_levellingUtil, SIGNAL(timeout(QString)), this, SLOT(levellingTimeout(QString)));
|
||||
|
||||
m_levellingUtil->start();
|
||||
}
|
||||
|
||||
void LevellingPage::levellingProgress(long current, long total)
|
||||
{
|
||||
if(ui->levellinProgressBar->maximum() != (int)total) {
|
||||
ui->levellinProgressBar->setMaximum((int)total);
|
||||
}
|
||||
if(ui->levellinProgressBar->value() != (int)current) {
|
||||
ui->levellinProgressBar->setValue((int)current);
|
||||
}
|
||||
}
|
||||
|
||||
void LevellingPage::levellingDone(accelGyroBias bias)
|
||||
{
|
||||
stopLevelling();
|
||||
getWizard()->setLevellingBias(bias);
|
||||
emit completeChanged();
|
||||
}
|
||||
|
||||
void LevellingPage::levellingTimeout(QString message)
|
||||
{
|
||||
stopLevelling();
|
||||
|
||||
QMessageBox msgBox;
|
||||
msgBox.setText(message);
|
||||
msgBox.setStandardButtons(QMessageBox::Ok);
|
||||
msgBox.setDefaultButton(QMessageBox::Ok);
|
||||
msgBox.exec();
|
||||
}
|
||||
|
||||
void LevellingPage::stopLevelling()
|
||||
{
|
||||
if(m_levellingUtil)
|
||||
{
|
||||
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->progressLabel->setText(QString(tr("<font color='green'>Done!</font>")));
|
||||
enableButtons(true);
|
||||
}
|
||||
}
|
@ -0,0 +1,65 @@
|
||||
/**
|
||||
******************************************************************************
|
||||
*
|
||||
* @file levellingpage.h
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012.
|
||||
* @addtogroup
|
||||
* @{
|
||||
* @addtogroup LevellingPage
|
||||
* @{
|
||||
* @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 LEVELLINGPAGE_H
|
||||
#define LEVELLINGPAGE_H
|
||||
|
||||
#include "abstractwizardpage.h"
|
||||
#include "levellingutil.h"
|
||||
|
||||
namespace Ui {
|
||||
class LevellingPage;
|
||||
}
|
||||
|
||||
class LevellingPage : public AbstractWizardPage
|
||||
{
|
||||
Q_OBJECT
|
||||
|
||||
public:
|
||||
explicit LevellingPage(SetupWizard *wizard, QWidget *parent = 0);
|
||||
~LevellingPage();
|
||||
bool validatePage();
|
||||
bool isComplete() const;
|
||||
|
||||
private slots:
|
||||
void performLevelling();
|
||||
void levellingProgress(long current, long total);
|
||||
void levellingDone(accelGyroBias bias);
|
||||
void levellingTimeout(QString message);
|
||||
|
||||
private:
|
||||
static const int BIAS_CYCLES = 200;
|
||||
static const int BIAS_RATE = 30;
|
||||
|
||||
Ui::LevellingPage *ui;
|
||||
LevellingUtil *m_levellingUtil;
|
||||
|
||||
void stopLevelling();
|
||||
void enableButtons(bool enable);
|
||||
};
|
||||
|
||||
#endif // LEVELLINGPAGE_H
|
@ -0,0 +1,124 @@
|
||||
<?xml version="1.0" encoding="UTF-8"?>
|
||||
<ui version="4.0">
|
||||
<class>LevellingPage</class>
|
||||
<widget class="QWizardPage" name="LevellingPage">
|
||||
<property name="geometry">
|
||||
<rect>
|
||||
<x>0</x>
|
||||
<y>0</y>
|
||||
<width>600</width>
|
||||
<height>400</height>
|
||||
</rect>
|
||||
</property>
|
||||
<property name="windowTitle">
|
||||
<string>WizardPage</string>
|
||||
</property>
|
||||
<widget class="QLabel" name="label">
|
||||
<property name="geometry">
|
||||
<rect>
|
||||
<x>20</x>
|
||||
<y>20</y>
|
||||
<width>541</width>
|
||||
<height>241</height>
|
||||
</rect>
|
||||
</property>
|
||||
<property name="text">
|
||||
<string><!DOCTYPE HTML PUBLIC "-//W3C//DTD HTML 4.0//EN" "http://www.w3.org/TR/REC-html40/strict.dtd">
|
||||
<html><head><meta name="qrichtext" content="1" /><style type="text/css">
|
||||
p, li { white-space: pre-wrap; }
|
||||
</style></head><body style=" font-family:'Lucida Grande'; font-size:13pt; font-weight:400; font-style:normal;">
|
||||
<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-family:'MS Shell Dlg 2'; font-size:12pt; font-weight:600;">OpenPilot controller leveling calibration procedure</span></p>
|
||||
<p style="-qt-paragraph-type:empty; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px; font-family:'MS Shell Dlg 2'; font-size:12pt; font-weight:600;"></p>
|
||||
<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-family:'MS Shell Dlg 2'; font-size:10pt;">The wizard needs to get information from the controller to determine in which position the vehicle is normally considered to be level. To be able to successfully perform these measurements, you need to place the vehicle on a surface that is as flat and level as possible. Examples of such surfaces could be a table top or the floor. Be careful to ensure that the vehicle really is level, since this step will affect the accelerometer and gyro bias in the controller software.</span></p>
|
||||
<p style="-qt-paragraph-type:empty; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px; font-family:'MS Shell Dlg 2'; font-size:10pt;"></p>
|
||||
<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-family:'MS Shell Dlg 2'; font-size:10pt;">To perform the leveling, please push the Calculate button and wait for the process to finish. </span></p></body></html></string>
|
||||
</property>
|
||||
<property name="alignment">
|
||||
<set>Qt::AlignLeading|Qt::AlignLeft|Qt::AlignTop</set>
|
||||
</property>
|
||||
<property name="wordWrap">
|
||||
<bool>true</bool>
|
||||
</property>
|
||||
</widget>
|
||||
<widget class="QToolButton" name="levelButton">
|
||||
<property name="geometry">
|
||||
<rect>
|
||||
<x>200</x>
|
||||
<y>260</y>
|
||||
<width>200</width>
|
||||
<height>70</height>
|
||||
</rect>
|
||||
</property>
|
||||
<property name="toolTip">
|
||||
<string>Calculate gyro and accelerometer bias</string>
|
||||
</property>
|
||||
<property name="styleSheet">
|
||||
<string notr="true">QToolButton { border: none }</string>
|
||||
</property>
|
||||
<property name="text">
|
||||
<string>Calculate</string>
|
||||
</property>
|
||||
<property name="icon">
|
||||
<iconset resource="../wizardResources.qrc">
|
||||
<normaloff>:/setupwizard/resources/bttn-calculate-up.png</normaloff>
|
||||
<normalon>:/setupwizard/resources/bttn-calculate-down.png</normalon>:/setupwizard/resources/bttn-calculate-up.png</iconset>
|
||||
</property>
|
||||
<property name="iconSize">
|
||||
<size>
|
||||
<width>200</width>
|
||||
<height>70</height>
|
||||
</size>
|
||||
</property>
|
||||
</widget>
|
||||
<widget class="QProgressBar" name="levellinProgressBar">
|
||||
<property name="geometry">
|
||||
<rect>
|
||||
<x>40</x>
|
||||
<y>350</y>
|
||||
<width>520</width>
|
||||
<height>23</height>
|
||||
</rect>
|
||||
</property>
|
||||
<property name="styleSheet">
|
||||
<string notr="true">QProgressBar {
|
||||
border: 2px solid grey;
|
||||
border-radius: 5px;
|
||||
text-align: center;
|
||||
}
|
||||
QProgressBar::chunk {
|
||||
background-color: #3D6699;
|
||||
width: 10px;
|
||||
margin: 0.5px;
|
||||
}</string>
|
||||
</property>
|
||||
<property name="value">
|
||||
<number>0</number>
|
||||
</property>
|
||||
<property name="format">
|
||||
<string/>
|
||||
</property>
|
||||
</widget>
|
||||
<widget class="QLabel" name="progressLabel">
|
||||
<property name="geometry">
|
||||
<rect>
|
||||
<x>42</x>
|
||||
<y>330</y>
|
||||
<width>511</width>
|
||||
<height>16</height>
|
||||
</rect>
|
||||
</property>
|
||||
<property name="font">
|
||||
<font>
|
||||
<pointsize>10</pointsize>
|
||||
</font>
|
||||
</property>
|
||||
<property name="text">
|
||||
<string/>
|
||||
</property>
|
||||
</widget>
|
||||
</widget>
|
||||
<resources>
|
||||
<include location="../wizardResources.qrc"/>
|
||||
</resources>
|
||||
<connections/>
|
||||
</ui>
|
171
ground/openpilotgcs/src/plugins/setupwizard/pages/multipage.cpp
Normal file
@ -0,0 +1,171 @@
|
||||
/**
|
||||
******************************************************************************
|
||||
*
|
||||
* @file multipage.cpp
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012.
|
||||
* @addtogroup
|
||||
* @{
|
||||
* @addtogroup MultiPage
|
||||
* @{
|
||||
* @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 "multipage.h"
|
||||
#include "ui_multipage.h"
|
||||
#include "setupwizard.h"
|
||||
|
||||
MultiPage::MultiPage(SetupWizard *wizard, QWidget *parent) :
|
||||
AbstractWizardPage(wizard, parent),
|
||||
ui(new Ui::MultiPage)
|
||||
{
|
||||
ui->setupUi(this);
|
||||
|
||||
QSvgRenderer *renderer = new QSvgRenderer();
|
||||
renderer->load(QString(":/configgadget/images/multirotor-shapes.svg"));
|
||||
multiPic = new QGraphicsSvgItem();
|
||||
multiPic->setSharedRenderer(renderer);
|
||||
QGraphicsScene *scene = new QGraphicsScene(this);
|
||||
scene->addItem(multiPic);
|
||||
ui->typeGraphicsView->setScene(scene);
|
||||
|
||||
setupMultiTypesCombo();
|
||||
|
||||
// Default to Quad X since it is the most common setup
|
||||
ui->typeCombo->setCurrentIndex(1);
|
||||
connect(ui->typeCombo, SIGNAL(currentIndexChanged(int)), this, SLOT(updateImageAndDescription()));
|
||||
}
|
||||
|
||||
MultiPage::~MultiPage()
|
||||
{
|
||||
delete ui;
|
||||
}
|
||||
|
||||
void MultiPage::initializePage()
|
||||
{
|
||||
updateAvailableTypes();
|
||||
updateImageAndDescription();
|
||||
}
|
||||
|
||||
bool MultiPage::validatePage()
|
||||
{
|
||||
SetupWizard::VEHICLE_SUB_TYPE type = (SetupWizard::VEHICLE_SUB_TYPE) ui->typeCombo->itemData(ui->typeCombo->currentIndex()).toInt();
|
||||
getWizard()->setVehicleSubType(type);
|
||||
return true;
|
||||
}
|
||||
|
||||
void MultiPage::setupMultiTypesCombo()
|
||||
{
|
||||
ui->typeCombo->addItem(tr("Tricopter"), SetupWizard::MULTI_ROTOR_TRI_Y);
|
||||
m_descriptions << tr("The Tricopter uses three motors and one servo. The servo is used to give yaw authority to the rear motor. "
|
||||
"The front motors are rotating in opposite directions. The Tricopter is known for its sweeping yaw movement and "
|
||||
"it is very well suited for FPV since the front rotors are spread wide apart.");
|
||||
|
||||
ui->typeCombo->addItem(tr("Quadcopter X"), SetupWizard::MULTI_ROTOR_QUAD_X);
|
||||
m_descriptions << tr("The X Quadcopter uses four motors and is the most common multi rotor configuration. Two of the motors rotate clockwise "
|
||||
"and two counter clockwise. The motors positioned diagonal to each other rotate in the same direction. "
|
||||
"This setup is perfect for sport flying and is also commonly used for FPV platforms.");
|
||||
|
||||
ui->typeCombo->addItem(tr("Quadcopter +"), SetupWizard::MULTI_ROTOR_QUAD_PLUS);
|
||||
m_descriptions << tr("The Plus(+) Quadcopter uses four motors and is similar to the X Quadcopter but the forward direction is offset by 45 degrees. "
|
||||
"The motors front and rear rotate in clockwise and the motors right and left rotate counter-clockwise. "
|
||||
"This setup was one of the first to be used and is still used for sport flying. This configuration is not that well suited "
|
||||
"for FPV since the fore rotor tend to be in the way of the camera.");
|
||||
|
||||
ui->typeCombo->addItem(tr("Hexacopter"), SetupWizard::MULTI_ROTOR_HEXA);
|
||||
m_descriptions << tr("Hexacopter");
|
||||
|
||||
ui->typeCombo->addItem(tr("Hexacopter Coax (Y6)"), SetupWizard::MULTI_ROTOR_HEXA_COAX_Y);
|
||||
m_descriptions << tr("Hexacopter Coax (Y6)");
|
||||
|
||||
ui->typeCombo->addItem(tr("Hexacopter X"), SetupWizard::MULTI_ROTOR_HEXA_H);
|
||||
m_descriptions << tr("Hexacopter H");
|
||||
|
||||
// Fredrik Arvidsson(m_thread) 2012-08-26 Disable Octos until further notice
|
||||
/*
|
||||
ui->typeCombo->addItem(tr("Octocopter"), SetupWizard::MULTI_ROTOR_OCTO);
|
||||
m_descriptions << tr("Octocopter");
|
||||
|
||||
ui->typeCombo->addItem(tr("Octocopter Coax X"), SetupWizard::MULTI_ROTOR_OCTO_COAX_X);
|
||||
m_descriptions << tr("Octocopter Coax X");
|
||||
|
||||
ui->typeCombo->addItem(tr("Octocopter Coax +"), SetupWizard::MULTI_ROTOR_OCTO_COAX_PLUS);
|
||||
m_descriptions << tr("Octocopter Coax +");
|
||||
|
||||
ui->typeCombo->addItem(tr("Octocopter V"), SetupWizard::MULTI_ROTOR_OCTO_V);
|
||||
m_descriptions << tr("Octocopter V");
|
||||
*/
|
||||
}
|
||||
|
||||
void MultiPage::updateAvailableTypes()
|
||||
{
|
||||
/*
|
||||
QVariant enable = (getWizard()->getInputType() == SetupWizard::INPUT_PWM) ? QVariant(0) : QVariant(1 | 32);
|
||||
ui->typeCombo->model()->setData(ui->typeCombo->model()->index(6, 0), enable, Qt::UserRole - 1);
|
||||
ui->typeCombo->model()->setData(ui->typeCombo->model()->index(7, 0), enable, Qt::UserRole - 1);
|
||||
ui->typeCombo->model()->setData(ui->typeCombo->model()->index(8, 0), enable, Qt::UserRole - 1);
|
||||
ui->typeCombo->model()->setData(ui->typeCombo->model()->index(9, 0), enable, Qt::UserRole - 1);
|
||||
*/
|
||||
}
|
||||
|
||||
void MultiPage::updateImageAndDescription()
|
||||
{
|
||||
SetupWizard::VEHICLE_SUB_TYPE type = (SetupWizard::VEHICLE_SUB_TYPE) ui->typeCombo->itemData(ui->typeCombo->currentIndex()).toInt();
|
||||
QString elementId = "";
|
||||
QString description = m_descriptions.at(ui->typeCombo->currentIndex());
|
||||
switch(type)
|
||||
{
|
||||
case SetupWizard::MULTI_ROTOR_TRI_Y:
|
||||
elementId = "tri";
|
||||
break;
|
||||
case SetupWizard::MULTI_ROTOR_QUAD_X:
|
||||
elementId = "quad-x";
|
||||
break;
|
||||
case SetupWizard::MULTI_ROTOR_QUAD_PLUS:
|
||||
elementId = "quad-plus";
|
||||
break;
|
||||
case SetupWizard::MULTI_ROTOR_HEXA:
|
||||
elementId = "quad-hexa";
|
||||
break;
|
||||
case SetupWizard::MULTI_ROTOR_HEXA_COAX_Y:
|
||||
elementId = "hexa-coax";
|
||||
break;
|
||||
case SetupWizard::MULTI_ROTOR_HEXA_H:
|
||||
elementId = "quad-hexa-H";
|
||||
break;
|
||||
case SetupWizard::MULTI_ROTOR_OCTO:
|
||||
elementId = "quad-octo";
|
||||
break;
|
||||
case SetupWizard::MULTI_ROTOR_OCTO_COAX_X:
|
||||
elementId = "octo-coax-X";
|
||||
break;
|
||||
case SetupWizard::MULTI_ROTOR_OCTO_COAX_PLUS:
|
||||
elementId = "octo-coax-P";
|
||||
break;
|
||||
case SetupWizard::MULTI_ROTOR_OCTO_V:
|
||||
elementId = "quad-octo-v";
|
||||
break;
|
||||
default:
|
||||
elementId = "";
|
||||
break;
|
||||
}
|
||||
multiPic->setElementId(elementId);
|
||||
ui->typeGraphicsView->setSceneRect(multiPic->boundingRect());
|
||||
ui->typeGraphicsView->fitInView(multiPic, Qt::KeepAspectRatio);
|
||||
|
||||
ui->typeDescription->setText(description);
|
||||
}
|
@ -0,0 +1,64 @@
|
||||
/**
|
||||
******************************************************************************
|
||||
*
|
||||
* @file multipage.h
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012.
|
||||
* @addtogroup
|
||||
* @{
|
||||
* @addtogroup MultiPage
|
||||
* @{
|
||||
* @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 MULTIPAGE_H
|
||||
#define MULTIPAGE_H
|
||||
|
||||
#include <QtSvg/QGraphicsSvgItem>
|
||||
#include <QtSvg/QSvgRenderer>
|
||||
#include <QList>
|
||||
|
||||
#include "abstractwizardpage.h"
|
||||
|
||||
namespace Ui {
|
||||
class MultiPage;
|
||||
}
|
||||
|
||||
class MultiPage : public AbstractWizardPage
|
||||
{
|
||||
Q_OBJECT
|
||||
|
||||
public:
|
||||
explicit MultiPage(SetupWizard *wizard, QWidget *parent = 0);
|
||||
~MultiPage();
|
||||
|
||||
void initializePage();
|
||||
bool validatePage();
|
||||
|
||||
|
||||
private:
|
||||
Ui::MultiPage *ui;
|
||||
void setupMultiTypesCombo();
|
||||
QGraphicsSvgItem *multiPic;
|
||||
void updateAvailableTypes();
|
||||
QList<QString> m_descriptions;
|
||||
|
||||
private slots:
|
||||
void updateImageAndDescription();
|
||||
};
|
||||
|
||||
#endif // MULTIPAGE_H
|
150
ground/openpilotgcs/src/plugins/setupwizard/pages/multipage.ui
Normal file
@ -0,0 +1,150 @@
|
||||
<?xml version="1.0" encoding="UTF-8"?>
|
||||
<ui version="4.0">
|
||||
<class>MultiPage</class>
|
||||
<widget class="QWizardPage" name="MultiPage">
|
||||
<property name="geometry">
|
||||
<rect>
|
||||
<x>0</x>
|
||||
<y>0</y>
|
||||
<width>600</width>
|
||||
<height>400</height>
|
||||
</rect>
|
||||
</property>
|
||||
<property name="windowTitle">
|
||||
<string>WizardPage</string>
|
||||
</property>
|
||||
<widget class="QLabel" name="label">
|
||||
<property name="geometry">
|
||||
<rect>
|
||||
<x>20</x>
|
||||
<y>20</y>
|
||||
<width>541</width>
|
||||
<height>151</height>
|
||||
</rect>
|
||||
</property>
|
||||
<property name="text">
|
||||
<string><!DOCTYPE HTML PUBLIC "-//W3C//DTD HTML 4.0//EN" "http://www.w3.org/TR/REC-html40/strict.dtd">
|
||||
<html><head><meta name="qrichtext" content="1" /><style type="text/css">
|
||||
p, li { white-space: pre-wrap; }
|
||||
</style></head><body style=" font-family:'MS Shell Dlg 2'; font-size:8pt; font-weight:400; font-style:normal;">
|
||||
<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-size:12pt; font-weight:600;">OpenPilot multirotor configuration</span></p>
|
||||
<p style="-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;"><br /></p>
|
||||
<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-size:10pt;">This part of the wizard will set up the OpenPilot controller for use with a flying platform utilizing multiple rotors. The wizard supports the most common types of multirotors. Other variants of multirotors can be configured by using custom configuration options in the Configuration plugin in the GCS.</span></p>
|
||||
<p style="-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;"><br /></p>
|
||||
<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-size:10pt;">Please select the type of multirotor you want to create a configuration for below:</span></p></body></html></string>
|
||||
</property>
|
||||
<property name="alignment">
|
||||
<set>Qt::AlignLeading|Qt::AlignLeft|Qt::AlignTop</set>
|
||||
</property>
|
||||
<property name="wordWrap">
|
||||
<bool>true</bool>
|
||||
</property>
|
||||
</widget>
|
||||
<widget class="QGraphicsView" name="typeGraphicsView">
|
||||
<property name="geometry">
|
||||
<rect>
|
||||
<x>390</x>
|
||||
<y>200</y>
|
||||
<width>170</width>
|
||||
<height>170</height>
|
||||
</rect>
|
||||
</property>
|
||||
<property name="sizePolicy">
|
||||
<sizepolicy hsizetype="Maximum" vsizetype="Maximum">
|
||||
<horstretch>0</horstretch>
|
||||
<verstretch>0</verstretch>
|
||||
</sizepolicy>
|
||||
</property>
|
||||
<property name="autoFillBackground">
|
||||
<bool>false</bool>
|
||||
</property>
|
||||
<property name="frameShape">
|
||||
<enum>QFrame::NoFrame</enum>
|
||||
</property>
|
||||
<property name="lineWidth">
|
||||
<number>0</number>
|
||||
</property>
|
||||
<property name="midLineWidth">
|
||||
<number>0</number>
|
||||
</property>
|
||||
<property name="verticalScrollBarPolicy">
|
||||
<enum>Qt::ScrollBarAlwaysOff</enum>
|
||||
</property>
|
||||
<property name="horizontalScrollBarPolicy">
|
||||
<enum>Qt::ScrollBarAlwaysOff</enum>
|
||||
</property>
|
||||
<property name="backgroundBrush">
|
||||
<brush brushstyle="NoBrush">
|
||||
<color alpha="0">
|
||||
<red>0</red>
|
||||
<green>0</green>
|
||||
<blue>0</blue>
|
||||
</color>
|
||||
</brush>
|
||||
</property>
|
||||
<property name="foregroundBrush">
|
||||
<brush brushstyle="NoBrush">
|
||||
<color alpha="0">
|
||||
<red>0</red>
|
||||
<green>0</green>
|
||||
<blue>0</blue>
|
||||
</color>
|
||||
</brush>
|
||||
</property>
|
||||
<property name="interactive">
|
||||
<bool>false</bool>
|
||||
</property>
|
||||
</widget>
|
||||
<widget class="QLabel" name="label_2">
|
||||
<property name="geometry">
|
||||
<rect>
|
||||
<x>40</x>
|
||||
<y>200</y>
|
||||
<width>90</width>
|
||||
<height>16</height>
|
||||
</rect>
|
||||
</property>
|
||||
<property name="font">
|
||||
<font>
|
||||
<pointsize>10</pointsize>
|
||||
<weight>50</weight>
|
||||
<bold>false</bold>
|
||||
</font>
|
||||
</property>
|
||||
<property name="text">
|
||||
<string>Multirotor type:</string>
|
||||
</property>
|
||||
</widget>
|
||||
<widget class="QComboBox" name="typeCombo">
|
||||
<property name="geometry">
|
||||
<rect>
|
||||
<x>140</x>
|
||||
<y>198</y>
|
||||
<width>230</width>
|
||||
<height>22</height>
|
||||
</rect>
|
||||
</property>
|
||||
</widget>
|
||||
<widget class="QTextEdit" name="typeDescription">
|
||||
<property name="geometry">
|
||||
<rect>
|
||||
<x>40</x>
|
||||
<y>240</y>
|
||||
<width>330</width>
|
||||
<height>130</height>
|
||||
</rect>
|
||||
</property>
|
||||
<property name="verticalScrollBarPolicy">
|
||||
<enum>Qt::ScrollBarAlwaysOn</enum>
|
||||
</property>
|
||||
<property name="horizontalScrollBarPolicy">
|
||||
<enum>Qt::ScrollBarAlwaysOff</enum>
|
||||
</property>
|
||||
<property name="textInteractionFlags">
|
||||
<set>Qt::TextSelectableByKeyboard|Qt::TextSelectableByMouse</set>
|
||||
</property>
|
||||
</widget>
|
||||
</widget>
|
||||
<resources/>
|
||||
<connections/>
|
||||
</ui>
|
@ -0,0 +1,42 @@
|
||||
/**
|
||||
******************************************************************************
|
||||
*
|
||||
* @file notyetimplementedpage.cpp
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012.
|
||||
* @addtogroup
|
||||
* @{
|
||||
* @addtogroup NotYetImplementedPage
|
||||
* @{
|
||||
* @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 "notyetimplementedpage.h"
|
||||
#include "ui_notyetimplementedpage.h"
|
||||
|
||||
NotYetImplementedPage::NotYetImplementedPage(SetupWizard *wizard, QWidget *parent) :
|
||||
AbstractWizardPage(wizard, parent),
|
||||
ui(new Ui::NotYetImplementedPage)
|
||||
{
|
||||
ui->setupUi(this);
|
||||
setFinalPage(true);
|
||||
}
|
||||
|
||||
NotYetImplementedPage::~NotYetImplementedPage()
|
||||
{
|
||||
delete ui;
|
||||
}
|
@ -0,0 +1,49 @@
|
||||
/**
|
||||
******************************************************************************
|
||||
*
|
||||
* @file notyetimplementedpage.h
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012.
|
||||
* @addtogroup
|
||||
* @{
|
||||
* @addtogroup NotYetImplementedPage
|
||||
* @{
|
||||
* @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 NOTYETIMPLEMENTEDPAGE_H
|
||||
#define NOTYETIMPLEMENTEDPAGE_H
|
||||
|
||||
#include "abstractwizardpage.h"
|
||||
|
||||
namespace Ui {
|
||||
class NotYetImplementedPage;
|
||||
}
|
||||
|
||||
class NotYetImplementedPage : public AbstractWizardPage
|
||||
{
|
||||
Q_OBJECT
|
||||
|
||||
public:
|
||||
explicit NotYetImplementedPage(SetupWizard *wizard, QWidget *parent = 0);
|
||||
~NotYetImplementedPage();
|
||||
|
||||
private:
|
||||
Ui::NotYetImplementedPage *ui;
|
||||
};
|
||||
|
||||
#endif // NOTYETIMPLEMENTEDPAGE_H
|
@ -0,0 +1,43 @@
|
||||
<?xml version="1.0" encoding="UTF-8"?>
|
||||
<ui version="4.0">
|
||||
<class>NotYetImplementedPage</class>
|
||||
<widget class="QWizardPage" name="NotYetImplementedPage">
|
||||
<property name="geometry">
|
||||
<rect>
|
||||
<x>0</x>
|
||||
<y>0</y>
|
||||
<width>600</width>
|
||||
<height>400</height>
|
||||
</rect>
|
||||
</property>
|
||||
<property name="windowTitle">
|
||||
<string>WizardPage</string>
|
||||
</property>
|
||||
<widget class="QLabel" name="label_2">
|
||||
<property name="geometry">
|
||||
<rect>
|
||||
<x>50</x>
|
||||
<y>190</y>
|
||||
<width>501</width>
|
||||
<height>31</height>
|
||||
</rect>
|
||||
</property>
|
||||
<property name="text">
|
||||
<string><!DOCTYPE HTML PUBLIC "-//W3C//DTD HTML 4.0//EN" "http://www.w3.org/TR/REC-html40/strict.dtd">
|
||||
<html><head><meta name="qrichtext" content="1" /><style type="text/css">
|
||||
p, li { white-space: pre-wrap; }
|
||||
</style></head><body style=" font-family:'MS Shell Dlg 2'; font-size:8.25pt; font-weight:400; font-style:normal;">
|
||||
<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-size:12pt; font-weight:600;">This section of the OpenPilot Setup Wizard is not yet implemented</span></p>
|
||||
<p style="-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:8pt;"></p></body></html></string>
|
||||
</property>
|
||||
<property name="alignment">
|
||||
<set>Qt::AlignLeading|Qt::AlignLeft|Qt::AlignTop</set>
|
||||
</property>
|
||||
<property name="wordWrap">
|
||||
<bool>true</bool>
|
||||
</property>
|
||||
</widget>
|
||||
</widget>
|
||||
<resources/>
|
||||
<connections/>
|
||||
</ui>
|
@ -0,0 +1,388 @@
|
||||
/**
|
||||
******************************************************************************
|
||||
*
|
||||
* @file outputcalibrationpage.cpp
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012.
|
||||
* @addtogroup
|
||||
* @{
|
||||
* @addtogroup OutputCalibrationPage
|
||||
* @{
|
||||
* @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 "outputcalibrationpage.h"
|
||||
#include "ui_outputcalibrationpage.h"
|
||||
#include "systemalarms.h"
|
||||
#include "uavobjectmanager.h"
|
||||
|
||||
OutputCalibrationPage::OutputCalibrationPage(SetupWizard *wizard, QWidget *parent) :
|
||||
AbstractWizardPage(wizard, parent), ui(new Ui::OutputCalibrationPage), m_vehicleBoundsItem(0),
|
||||
m_currentWizardIndex(-1), m_calibrationUtil(0)
|
||||
{
|
||||
ui->setupUi(this);
|
||||
|
||||
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;
|
||||
m_calibrationUtil = 0;
|
||||
}
|
||||
delete ui;
|
||||
}
|
||||
|
||||
void OutputCalibrationPage::setupVehicle()
|
||||
{
|
||||
m_actuatorSettings = getWizard()->getActuatorSettings();
|
||||
m_wizardIndexes.clear();
|
||||
m_vehicleElementIds.clear();
|
||||
m_vehicleHighlightElementIndexes.clear();
|
||||
m_channelIndex.clear();
|
||||
m_currentWizardIndex = 0;
|
||||
m_vehicleScene->clear();
|
||||
switch(getWizard()->getVehicleSubType())
|
||||
{
|
||||
case SetupWizard::MULTI_ROTOR_TRI_Y:
|
||||
m_wizardIndexes << 0 << 1 << 1 << 1 << 2 << 3 << 4;
|
||||
m_vehicleElementIds << "tri" << "tri-frame" << "tri-m1" << "tri-m2" << "tri-m3" << "tri-s1";
|
||||
m_vehicleHighlightElementIndexes << 0 << 1 << 2 << 3 << 4 << 4 << 4;
|
||||
m_channelIndex << 0 << 0 << 1 << 2 << 3 << 3 << 3;
|
||||
m_actuatorSettings[3].channelMin = 1500;
|
||||
m_actuatorSettings[3].channelNeutral = 1500;
|
||||
m_actuatorSettings[3].channelMax = 1500;
|
||||
getWizard()->setActuatorSettings(m_actuatorSettings);
|
||||
break;
|
||||
case SetupWizard::MULTI_ROTOR_QUAD_X:
|
||||
m_wizardIndexes << 0 << 1 << 1 << 1 << 1;
|
||||
m_vehicleElementIds << "quad-x" << "quad-x-frame" << "quad-x-m1" << "quad-x-m2" << "quad-x-m3" << "quad-x-m4";
|
||||
m_vehicleHighlightElementIndexes << 0 << 1 << 2 << 3 << 4;
|
||||
m_channelIndex << 0 << 0 << 1 << 2 << 3;
|
||||
break;
|
||||
case SetupWizard::MULTI_ROTOR_QUAD_PLUS:
|
||||
m_wizardIndexes << 0 << 1 << 1 << 1 << 1;
|
||||
m_vehicleElementIds << "quad-p" << "quad-p-frame" << "quad-p-m1" << "quad-p-m2" << "quad-p-m3" << "quad-p-m4";
|
||||
m_vehicleHighlightElementIndexes << 0 << 1 << 2 << 3 << 4;
|
||||
m_channelIndex << 0 << 0 << 1 << 2 << 3;
|
||||
break;
|
||||
case SetupWizard::MULTI_ROTOR_HEXA:
|
||||
m_wizardIndexes << 0 << 1 << 1 << 1 << 1 << 1 << 1;
|
||||
m_vehicleElementIds << "hexa" << "hexa-frame" << "hexa-m1" << "hexa-m2" << "hexa-m3" << "hexa-m4" << "hexa-m5" << "hexa-m6";
|
||||
m_vehicleHighlightElementIndexes << 0 << 1 << 2 << 3 << 4 << 5 << 6;
|
||||
m_channelIndex << 0 << 0 << 1 << 2 << 3 << 4 << 5;
|
||||
break;
|
||||
case SetupWizard::MULTI_ROTOR_HEXA_COAX_Y:
|
||||
m_wizardIndexes << 0 << 1 << 1 << 1 << 1 << 1 << 1;
|
||||
m_vehicleElementIds << "hexa-y6" << "hexa-y6-frame" << "hexa-y6-m2" << "hexa-y6-m1" << "hexa-y6-m4" << "hexa-y6-m3" << "hexa-y6-m6" << "hexa-y6-m5";
|
||||
m_vehicleHighlightElementIndexes << 0 << 2 << 1 << 4 << 3 << 6 << 5;
|
||||
m_channelIndex << 0 << 0 << 1 << 2 << 3 << 4 << 5;
|
||||
break;
|
||||
case SetupWizard::MULTI_ROTOR_HEXA_H:
|
||||
m_wizardIndexes << 0 << 1 << 1 << 1 << 1 << 1 << 1;
|
||||
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 << 2 << 3 << 4 << 5 << 6;
|
||||
m_channelIndex << 0 << 0 << 1 << 2 << 3 << 4 << 5;
|
||||
break;
|
||||
default:
|
||||
break;
|
||||
}
|
||||
|
||||
VehicleConfigurationHelper helper(getWizard());
|
||||
helper.setupVehicle(false);
|
||||
|
||||
if(m_calibrationUtil) {
|
||||
delete m_calibrationUtil;
|
||||
m_calibrationUtil = 0;
|
||||
}
|
||||
m_calibrationUtil = new OutputCalibrationUtil();
|
||||
|
||||
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()
|
||||
{
|
||||
qDebug() << "Wizard index: " << m_currentWizardIndex;
|
||||
m_calibrationUtil->stopChannelOutput();
|
||||
|
||||
QApplication::processEvents();
|
||||
|
||||
int currentPageIndex = m_wizardIndexes[m_currentWizardIndex];
|
||||
qDebug() << "Current page: " << currentPageIndex;
|
||||
ui->calibrationStack->setCurrentIndex(currentPageIndex);
|
||||
|
||||
int currentChannel = getCurrentChannel();
|
||||
qDebug() << "Current channel: " << currentChannel;
|
||||
if(currentChannel >= 0) {
|
||||
if(currentPageIndex == 1) {
|
||||
ui->motorNeutralSlider->setValue(m_actuatorSettings[currentChannel].channelNeutral);
|
||||
}
|
||||
else if(currentPageIndex == 2) {
|
||||
ui->servoCenterSlider->setValue(m_actuatorSettings[currentChannel].channelNeutral);
|
||||
}
|
||||
else if(currentPageIndex == 3) {
|
||||
ui->servoMinAngleSlider->setMaximum(m_actuatorSettings[currentChannel].channelNeutral);
|
||||
ui->servoMinAngleSlider->setValue(m_actuatorSettings[currentChannel].channelMin);
|
||||
}
|
||||
else if(currentPageIndex == 4) {
|
||||
ui->servoMaxAngleSlider->setMinimum(m_actuatorSettings[currentChannel].channelNeutral);
|
||||
ui->servoMaxAngleSlider->setValue(m_actuatorSettings[currentChannel].channelMax);
|
||||
}
|
||||
}
|
||||
setupVehicleHighlightedPart();
|
||||
}
|
||||
|
||||
void OutputCalibrationPage::initializePage()
|
||||
{
|
||||
if(m_vehicleScene) {
|
||||
setupVehicle();
|
||||
startWizard();
|
||||
}
|
||||
}
|
||||
|
||||
bool OutputCalibrationPage::validatePage()
|
||||
{
|
||||
if(isFinished()) {
|
||||
getWizard()->setActuatorSettings(m_actuatorSettings);
|
||||
return true;
|
||||
} else {
|
||||
m_currentWizardIndex++;
|
||||
setWizardPage();
|
||||
return false;
|
||||
}
|
||||
}
|
||||
|
||||
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::customBackClicked()
|
||||
{
|
||||
if(m_currentWizardIndex > 0)
|
||||
{
|
||||
m_currentWizardIndex--;
|
||||
setWizardPage();
|
||||
}
|
||||
else
|
||||
{
|
||||
getWizard()->back();
|
||||
}
|
||||
}
|
||||
|
||||
quint16 OutputCalibrationPage::getCurrentChannel()
|
||||
{
|
||||
return m_channelIndex[m_currentWizardIndex];
|
||||
}
|
||||
|
||||
void OutputCalibrationPage::enableButtons(bool enable)
|
||||
{
|
||||
getWizard()->button(QWizard::NextButton)->setEnabled(enable);
|
||||
getWizard()->button(QWizard::CustomButton1)->setEnabled(enable);
|
||||
getWizard()->button(QWizard::CancelButton)->setEnabled(enable);
|
||||
getWizard()->button(QWizard::BackButton)->setEnabled(enable);
|
||||
QApplication::processEvents();
|
||||
}
|
||||
|
||||
void OutputCalibrationPage::on_motorNeutralButton_toggled(bool checked)
|
||||
{
|
||||
ui->motorNeutralButton->setText(checked ? tr("Stop") : tr("Start"));
|
||||
quint16 channel = getCurrentChannel();
|
||||
onStartButtonToggle(ui->motorNeutralButton, channel, m_actuatorSettings[channel].channelNeutral, 1000, ui->motorNeutralSlider);
|
||||
}
|
||||
|
||||
void OutputCalibrationPage::onStartButtonToggle(QAbstractButton *button, quint16 channel, quint16 value, quint16 safeValue, QSlider *slider) {
|
||||
if(button->isChecked()) {
|
||||
if(checkAlarms()) {
|
||||
enableButtons(false);
|
||||
m_calibrationUtil->startChannelOutput(channel, safeValue);
|
||||
slider->setValue(value);
|
||||
m_calibrationUtil->setChannelOutputValue(value);
|
||||
}
|
||||
else {
|
||||
button->setChecked(false);
|
||||
}
|
||||
}
|
||||
else {
|
||||
m_calibrationUtil->stopChannelOutput();
|
||||
enableButtons(true);
|
||||
}
|
||||
debugLogChannelValues();
|
||||
}
|
||||
|
||||
bool OutputCalibrationPage::checkAlarms()
|
||||
{
|
||||
ExtensionSystem::PluginManager *pm = ExtensionSystem::PluginManager::instance();
|
||||
UAVObjectManager *uavObjectManager = pm->getObject<UAVObjectManager>();
|
||||
Q_ASSERT(uavObjectManager);
|
||||
SystemAlarms * systemAlarms = SystemAlarms::GetInstance(uavObjectManager);
|
||||
Q_ASSERT(systemAlarms);
|
||||
SystemAlarms::DataFields data = systemAlarms->getData();
|
||||
|
||||
if(data.Alarm[SystemAlarms::ALARM_ACTUATOR] != SystemAlarms::ALARM_OK) {
|
||||
QMessageBox mbox;
|
||||
mbox.setText(QString(tr("The actuator module is in an error state.\n\n"
|
||||
"This error can be caused by not having the board correctly connected or\n"
|
||||
"if the board is not sufficiently powered by an external power source like\n"
|
||||
"a battery. To use only USB as power source is not enough when the USB can't\n"
|
||||
"power external components like ESCs and servos.\n\n"
|
||||
"Please fix the error before continuing calibration.")));
|
||||
mbox.setStandardButtons(QMessageBox::Ok);
|
||||
mbox.setIcon(QMessageBox::Critical);
|
||||
mbox.exec();
|
||||
return false;
|
||||
}
|
||||
return true;
|
||||
}
|
||||
|
||||
void OutputCalibrationPage::debugLogChannelValues()
|
||||
{
|
||||
quint16 channel = getCurrentChannel();
|
||||
qDebug() << "ChannelMin : " << m_actuatorSettings[channel].channelMin;
|
||||
qDebug() << "ChannelNeutral: " << m_actuatorSettings[channel].channelNeutral;
|
||||
qDebug() << "ChannelMax : " << m_actuatorSettings[channel].channelMax;
|
||||
}
|
||||
|
||||
void OutputCalibrationPage::on_motorNeutralSlider_valueChanged(int value)
|
||||
{
|
||||
if(ui->motorNeutralButton->isChecked()) {
|
||||
quint16 value = ui->motorNeutralSlider->value();
|
||||
m_calibrationUtil->setChannelOutputValue(value);
|
||||
m_actuatorSettings[getCurrentChannel()].channelNeutral = value;
|
||||
debugLogChannelValues();
|
||||
}
|
||||
}
|
||||
|
||||
void OutputCalibrationPage::on_servoCenterButton_toggled(bool checked)
|
||||
{
|
||||
ui->servoCenterButton->setText(checked ? tr("Stop") : tr("Start"));
|
||||
quint16 channel = getCurrentChannel();
|
||||
quint16 safeValue = m_actuatorSettings[channel].channelNeutral;
|
||||
onStartButtonToggle(ui->servoCenterButton, channel, safeValue, safeValue, ui->servoCenterSlider);
|
||||
}
|
||||
|
||||
void OutputCalibrationPage::on_servoCenterSlider_valueChanged(int position)
|
||||
{
|
||||
if(ui->servoCenterButton->isChecked()) {
|
||||
quint16 value = ui->servoCenterSlider->value();
|
||||
m_calibrationUtil->setChannelOutputValue(value);
|
||||
quint16 channel = getCurrentChannel();
|
||||
m_actuatorSettings[channel].channelNeutral = value;
|
||||
|
||||
//Adjust min and max
|
||||
if(value < m_actuatorSettings[channel].channelMin) {
|
||||
m_actuatorSettings[channel].channelMin = value;
|
||||
}
|
||||
if(value > m_actuatorSettings[channel].channelMax) {
|
||||
m_actuatorSettings[channel].channelMax = value;
|
||||
}
|
||||
debugLogChannelValues();
|
||||
}
|
||||
}
|
||||
|
||||
void OutputCalibrationPage::on_servoMinAngleButton_toggled(bool checked)
|
||||
{
|
||||
ui->servoMinAngleButton->setText(checked ? tr("Stop") : tr("Start"));
|
||||
quint16 channel = getCurrentChannel();
|
||||
quint16 safeValue = m_actuatorSettings[channel].channelNeutral;
|
||||
onStartButtonToggle(ui->servoMinAngleButton, channel, m_actuatorSettings[channel].channelMin, safeValue, ui->servoMinAngleSlider);
|
||||
}
|
||||
|
||||
void OutputCalibrationPage::on_servoMinAngleSlider_valueChanged(int position)
|
||||
{
|
||||
if(ui->servoMinAngleButton->isChecked()) {
|
||||
quint16 value = ui->servoMinAngleSlider->value();
|
||||
m_calibrationUtil->setChannelOutputValue(value);
|
||||
m_actuatorSettings[getCurrentChannel()].channelMin = value;
|
||||
debugLogChannelValues();
|
||||
}
|
||||
}
|
||||
|
||||
void OutputCalibrationPage::on_servoMaxAngleButton_toggled(bool checked)
|
||||
{
|
||||
ui->servoMaxAngleButton->setText(checked ? tr("Stop") : tr("Start"));
|
||||
quint16 channel = getCurrentChannel();
|
||||
quint16 safeValue = m_actuatorSettings[channel].channelNeutral;
|
||||
onStartButtonToggle(ui->servoMaxAngleButton, channel, m_actuatorSettings[channel].channelMax, safeValue, ui->servoMaxAngleSlider);
|
||||
}
|
||||
|
||||
void OutputCalibrationPage::on_servoMaxAngleSlider_valueChanged(int position)
|
||||
{
|
||||
if(ui->servoMaxAngleButton->isChecked()) {
|
||||
quint16 value = ui->servoMaxAngleSlider->value();
|
||||
m_calibrationUtil->setChannelOutputValue(value);
|
||||
m_actuatorSettings[getCurrentChannel()].channelMax = value;
|
||||
debugLogChannelValues();
|
||||
}
|
||||
}
|
@ -0,0 +1,103 @@
|
||||
/**
|
||||
******************************************************************************
|
||||
*
|
||||
* @file outputcalibrationpage.h
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012.
|
||||
* @addtogroup
|
||||
* @{
|
||||
* @addtogroup OutputCalibrationPage
|
||||
* @{
|
||||
* @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 OUTPUTCALIBRATIONPAGE_H
|
||||
#define OUTPUTCALIBRATIONPAGE_H
|
||||
|
||||
#include <QtSvg>
|
||||
#include "abstractwizardpage.h"
|
||||
#include "setupwizard.h"
|
||||
#include "outputcalibrationutil.h"
|
||||
#include "vehicleconfigurationhelper.h"
|
||||
|
||||
namespace Ui {
|
||||
class OutputCalibrationPage;
|
||||
}
|
||||
|
||||
class OutputCalibrationPage : public AbstractWizardPage
|
||||
{
|
||||
Q_OBJECT
|
||||
|
||||
public:
|
||||
explicit OutputCalibrationPage(SetupWizard *wizard, QWidget *parent = 0);
|
||||
~OutputCalibrationPage();
|
||||
void initializePage();
|
||||
bool validatePage();
|
||||
|
||||
bool isFinished() { return m_currentWizardIndex >= m_wizardIndexes.size() - 1; }
|
||||
|
||||
protected:
|
||||
void showEvent(QShowEvent *event);
|
||||
|
||||
public slots:
|
||||
void customBackClicked();
|
||||
|
||||
private slots:
|
||||
void on_motorNeutralButton_toggled(bool checked);
|
||||
void on_motorNeutralSlider_valueChanged(int value);
|
||||
|
||||
void on_servoCenterButton_toggled(bool checked);
|
||||
void on_servoCenterSlider_valueChanged(int position);
|
||||
|
||||
void on_servoMinAngleButton_toggled(bool checked);
|
||||
void on_servoMinAngleSlider_valueChanged(int position);
|
||||
|
||||
void on_servoMaxAngleButton_toggled(bool checked);
|
||||
void on_servoMaxAngleSlider_valueChanged(int position);
|
||||
|
||||
private:
|
||||
void setupVehicle();
|
||||
void startWizard();
|
||||
void setupVehicleItems();
|
||||
void setupVehicleHighlightedPart();
|
||||
void setWizardPage();
|
||||
void enableButtons(bool enable);
|
||||
void onStartButtonToggle(QAbstractButton *button, quint16 channel, quint16 value, quint16 safeValue, QSlider *slider);
|
||||
bool checkAlarms();
|
||||
void debugLogChannelValues();
|
||||
quint16 getCurrentChannel();
|
||||
|
||||
Ui::OutputCalibrationPage *ui;
|
||||
QSvgRenderer *m_vehicleRenderer;
|
||||
QGraphicsScene *m_vehicleScene;
|
||||
QGraphicsSvgItem *m_vehicleBoundsItem;
|
||||
|
||||
qint16 m_currentWizardIndex;
|
||||
|
||||
QList<QString> m_vehicleElementIds;
|
||||
QList<QGraphicsSvgItem*> m_vehicleItems;
|
||||
QList<quint16> m_vehicleHighlightElementIndexes;
|
||||
QList<quint16> m_channelIndex;
|
||||
QList<quint16> m_wizardIndexes;
|
||||
|
||||
QList<actuatorChannelSettings> m_actuatorSettings;
|
||||
|
||||
OutputCalibrationUtil *m_calibrationUtil;
|
||||
|
||||
};
|
||||
|
||||
#endif // OUTPUTCALIBRATIONPAGE_H
|
@ -0,0 +1,497 @@
|
||||
<?xml version="1.0" encoding="UTF-8"?>
|
||||
<ui version="4.0">
|
||||
<class>OutputCalibrationPage</class>
|
||||
<widget class="QWizardPage" name="OutputCalibrationPage">
|
||||
<property name="geometry">
|
||||
<rect>
|
||||
<x>0</x>
|
||||
<y>0</y>
|
||||
<width>600</width>
|
||||
<height>400</height>
|
||||
</rect>
|
||||
</property>
|
||||
<property name="windowTitle">
|
||||
<string>WizardPage</string>
|
||||
</property>
|
||||
<widget class="QGraphicsView" name="vehicleView">
|
||||
<property name="geometry">
|
||||
<rect>
|
||||
<x>310</x>
|
||||
<y>40</y>
|
||||
<width>270</width>
|
||||
<height>341</height>
|
||||
</rect>
|
||||
</property>
|
||||
<property name="frameShape">
|
||||
<enum>QFrame::NoFrame</enum>
|
||||
</property>
|
||||
</widget>
|
||||
<widget class="QStackedWidget" name="calibrationStack">
|
||||
<property name="geometry">
|
||||
<rect>
|
||||
<x>20</x>
|
||||
<y>40</y>
|
||||
<width>290</width>
|
||||
<height>341</height>
|
||||
</rect>
|
||||
</property>
|
||||
<property name="currentIndex">
|
||||
<number>0</number>
|
||||
</property>
|
||||
<widget class="QWidget" name="intro">
|
||||
<widget class="QLabel" name="label_3">
|
||||
<property name="geometry">
|
||||
<rect>
|
||||
<x>0</x>
|
||||
<y>10</y>
|
||||
<width>270</width>
|
||||
<height>321</height>
|
||||
</rect>
|
||||
</property>
|
||||
<property name="text">
|
||||
<string><!DOCTYPE HTML PUBLIC "-//W3C//DTD HTML 4.0//EN" "http://www.w3.org/TR/REC-html40/strict.dtd">
|
||||
<html><head><meta name="qrichtext" content="1" /><style type="text/css">
|
||||
p, li { white-space: pre-wrap; }
|
||||
</style></head><body style=" font-family:'MS Shell Dlg 2'; font-size:8pt; font-weight:400; font-style:normal;">
|
||||
<p style=" margin-top:12px; margin-bottom:12px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-family:'Lucida Grande'; font-size:10pt;">It is now time to calibrate the output levels for the signals controlling your vehicle. </span></p>
|
||||
<p align="center" style=" margin-top:12px; margin-bottom:12px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-family:'Lucida Grande'; font-size:10pt; font-weight:600; color:#ff0000;">VERY IMPORTANT!</span><span style=" font-family:'Lucida Grande'; font-size:10pt;"><br /></span><span style=" font-family:'Lucida Grande'; font-size:10pt; font-weight:600; color:#ff0000;">REMOVE ALL PROPELLERS FROM THE VEHICLE BEFORE PROCEEDING!</span></p>
|
||||
<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-family:'Lucida Grande'; font-size:10pt;">Connect all components according to the illustration on the summary page, and provide power using an external power supply such as a battery before continuing.</span></p>
|
||||
<p style="-qt-paragraph-type:empty; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px; font-family:'Lucida Grande'; font-size:10pt;"><br /></p>
|
||||
<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-family:'Lucida Grande'; font-size:10pt;">Depending on what vehicle you have selected, both the motors controlled by ESCs and/or servos controlled directly by the OpenPilot controller may have to be calibrated. The following steps will guide you safely through this process. </span></p></body></html></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>221</height>
|
||||
</rect>
|
||||
</property>
|
||||
<property name="text">
|
||||
<string><html><head/><body><p>In this step we will set the neutral rate for the motor highlighted in the illustration to the right. <br/>Plase pay attention to the details and in particular the motors position and its rotation direction.</p><p>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. <br/><br/>When done press button again to stop.</p></body></html></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>250</y>
|
||||
<width>241</width>
|
||||
<height>19</height>
|
||||
</rect>
|
||||
</property>
|
||||
<property name="minimum">
|
||||
<number>1000</number>
|
||||
</property>
|
||||
<property name="maximum">
|
||||
<number>1300</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>290</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="servoNeutral">
|
||||
<widget class="QLabel" name="label_6">
|
||||
<property name="geometry">
|
||||
<rect>
|
||||
<x>0</x>
|
||||
<y>10</y>
|
||||
<width>261</width>
|
||||
<height>201</height>
|
||||
</rect>
|
||||
</property>
|
||||
<property name="text">
|
||||
<string><html><head/><body><p>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. </p><p>When done press button again to stop.</p></body></html></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>250</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>true</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>290</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="servoMinAngleButton">
|
||||
<property name="geometry">
|
||||
<rect>
|
||||
<x>90</x>
|
||||
<y>290</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>211</height>
|
||||
</rect>
|
||||
</property>
|
||||
<property name="text">
|
||||
<string><html><head/><body><p>To save the servo and other hardware from damage we have to set the max and min angles for the servo. </p><p>To set the minimum angle for the servo, press the Start button below and select the top slider and slide it to the left until min angle is reached.</p><p>When done press button again to stop.</p></body></html></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="servoMinAngleSlider">
|
||||
<property name="enabled">
|
||||
<bool>false</bool>
|
||||
</property>
|
||||
<property name="geometry">
|
||||
<rect>
|
||||
<x>10</x>
|
||||
<y>250</y>
|
||||
<width>241</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>true</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 class="QWidget" name="page">
|
||||
<widget class="QPushButton" name="servoMaxAngleButton">
|
||||
<property name="geometry">
|
||||
<rect>
|
||||
<x>90</x>
|
||||
<y>290</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="QSlider" name="servoMaxAngleSlider">
|
||||
<property name="enabled">
|
||||
<bool>false</bool>
|
||||
</property>
|
||||
<property name="geometry">
|
||||
<rect>
|
||||
<x>10</x>
|
||||
<y>250</y>
|
||||
<width>241</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>true</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="QLabel" name="label_8">
|
||||
<property name="geometry">
|
||||
<rect>
|
||||
<x>0</x>
|
||||
<y>10</y>
|
||||
<width>261</width>
|
||||
<height>211</height>
|
||||
</rect>
|
||||
</property>
|
||||
<property name="text">
|
||||
<string><html><head/><body><p>To set the maximum angle for the servo, press the Start button below and select the top slider and slide it to the right until max angle is reached.</p><p>When done press button again to stop.</p></body></html></string>
|
||||
</property>
|
||||
<property name="alignment">
|
||||
<set>Qt::AlignLeading|Qt::AlignLeft|Qt::AlignTop</set>
|
||||
</property>
|
||||
<property name="wordWrap">
|
||||
<bool>true</bool>
|
||||
</property>
|
||||
</widget>
|
||||
</widget>
|
||||
</widget>
|
||||
<widget class="QLabel" name="label_2">
|
||||
<property name="geometry">
|
||||
<rect>
|
||||
<x>20</x>
|
||||
<y>20</y>
|
||||
<width>531</width>
|
||||
<height>16</height>
|
||||
</rect>
|
||||
</property>
|
||||
<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::AlignLeading|Qt::AlignLeft|Qt::AlignVCenter</set>
|
||||
</property>
|
||||
</widget>
|
||||
</widget>
|
||||
<resources/>
|
||||
<connections>
|
||||
<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>servoMinAngleButton</sender>
|
||||
<signal>toggled(bool)</signal>
|
||||
<receiver>servoMinAngleSlider</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>servoMaxAngleButton</sender>
|
||||
<signal>toggled(bool)</signal>
|
||||
<receiver>servoMaxAngleSlider</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>
|
||||
</connections>
|
||||
</ui>
|
@ -0,0 +1,55 @@
|
||||
/**
|
||||
******************************************************************************
|
||||
*
|
||||
* @file outputpage.cpp
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012.
|
||||
* @addtogroup
|
||||
* @{
|
||||
* @addtogroup OutputPage
|
||||
* @{
|
||||
* @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 "outputpage.h"
|
||||
#include "ui_outputpage.h"
|
||||
#include "setupwizard.h"
|
||||
|
||||
OutputPage::OutputPage(SetupWizard *wizard, QWidget *parent) :
|
||||
AbstractWizardPage(wizard, parent),
|
||||
|
||||
ui(new Ui::OutputPage)
|
||||
{
|
||||
ui->setupUi(this);
|
||||
}
|
||||
|
||||
OutputPage::~OutputPage()
|
||||
{
|
||||
delete ui;
|
||||
}
|
||||
|
||||
bool OutputPage::validatePage()
|
||||
{
|
||||
if(ui->rapidESCButton->isChecked()) {
|
||||
getWizard()->setESCType(SetupWizard::ESC_RAPID);
|
||||
}
|
||||
else {
|
||||
getWizard()->setESCType(SetupWizard::ESC_LEGACY);
|
||||
}
|
||||
|
||||
return true;
|
||||
}
|
@ -0,0 +1,50 @@
|
||||
/**
|
||||
******************************************************************************
|
||||
*
|
||||
* @file outputpage.h
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012.
|
||||
* @addtogroup
|
||||
* @{
|
||||
* @addtogroup OutputPage
|
||||
* @{
|
||||
* @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 OUTPUTPAGE_H
|
||||
#define OUTPUTPAGE_H
|
||||
|
||||
#include "abstractwizardpage.h"
|
||||
|
||||
namespace Ui {
|
||||
class OutputPage;
|
||||
}
|
||||
|
||||
class OutputPage : public AbstractWizardPage
|
||||
{
|
||||
Q_OBJECT
|
||||
|
||||
public:
|
||||
explicit OutputPage(SetupWizard *wizard, QWidget *parent = 0);
|
||||
~OutputPage();
|
||||
bool validatePage();
|
||||
|
||||
private:
|
||||
Ui::OutputPage *ui;
|
||||
};
|
||||
|
||||
#endif // OUTPUTPAGE_H
|
150
ground/openpilotgcs/src/plugins/setupwizard/pages/outputpage.ui
Normal file
@ -0,0 +1,150 @@
|
||||
<?xml version="1.0" encoding="UTF-8"?>
|
||||
<ui version="4.0">
|
||||
<class>OutputPage</class>
|
||||
<widget class="QWizardPage" name="OutputPage">
|
||||
<property name="geometry">
|
||||
<rect>
|
||||
<x>0</x>
|
||||
<y>0</y>
|
||||
<width>600</width>
|
||||
<height>400</height>
|
||||
</rect>
|
||||
</property>
|
||||
<property name="windowTitle">
|
||||
<string>WizardPage</string>
|
||||
</property>
|
||||
<widget class="QLabel" name="label">
|
||||
<property name="geometry">
|
||||
<rect>
|
||||
<x>20</x>
|
||||
<y>20</y>
|
||||
<width>541</width>
|
||||
<height>151</height>
|
||||
</rect>
|
||||
</property>
|
||||
<property name="text">
|
||||
<string><!DOCTYPE HTML PUBLIC "-//W3C//DTD HTML 4.0//EN" "http://www.w3.org/TR/REC-html40/strict.dtd">
|
||||
<html><head><meta name="qrichtext" content="1" /><style type="text/css">
|
||||
p, li { white-space: pre-wrap; }
|
||||
</style></head><body style=" font-family:'Lucida Grande'; font-size:13pt; font-weight:400; font-style:normal;">
|
||||
<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-family:'MS Shell Dlg 2'; font-size:12pt; font-weight:600;">OpenPilot basic output signal configuration</span></p>
|
||||
<p style="-qt-paragraph-type:empty; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px; font-family:'MS Shell Dlg 2'; font-size:12pt; font-weight:600;"></p>
|
||||
<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-family:'MS Shell Dlg 2'; font-size:10pt;">To set an optimal configuration of the output signals powering your motors, the wizard needs to know what type of Electronic Speed Controllers (ESCs) you will use and what their capabilities are.</span></p>
|
||||
<p style="-qt-paragraph-type:empty; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px; font-family:'MS Shell Dlg 2'; font-size:10pt;"></p>
|
||||
<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-family:'MS Shell Dlg 2'; font-size:10pt;">Please select one of the options below. If you are unsure about the capabilities of your ESCs, just leave the default option selected and continue the wizard.</span></p>
|
||||
<p style="-qt-paragraph-type:empty; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px; font-family:'MS Shell Dlg 2'; font-size:10pt;"></p>
|
||||
<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-family:'MS Shell Dlg 2'; font-size:10pt;">To read more regarding ESC refresh rates, please see </span><a href="http://wiki.openpilot.org/display/Doc/TurboPWM+ESC%27s"><span style=" text-decoration: underline; color:#0000ff;">this article</span></a><span style=" font-family:'MS Shell Dlg 2'; font-size:10pt;"> in the OpenPilot Wiki</span></p></body></html></string>
|
||||
</property>
|
||||
<property name="alignment">
|
||||
<set>Qt::AlignLeading|Qt::AlignLeft|Qt::AlignTop</set>
|
||||
</property>
|
||||
<property name="wordWrap">
|
||||
<bool>true</bool>
|
||||
</property>
|
||||
</widget>
|
||||
<widget class="QToolButton" name="rapidESCButton">
|
||||
<property name="geometry">
|
||||
<rect>
|
||||
<x>320</x>
|
||||
<y>250</y>
|
||||
<width>200</width>
|
||||
<height>120</height>
|
||||
</rect>
|
||||
</property>
|
||||
<property name="font">
|
||||
<font>
|
||||
<pointsize>10</pointsize>
|
||||
</font>
|
||||
</property>
|
||||
<property name="toolTip">
|
||||
<string>Turbo PWM ESC 400Hz</string>
|
||||
</property>
|
||||
<property name="styleSheet">
|
||||
<string notr="true">QToolButton { border: none }</string>
|
||||
</property>
|
||||
<property name="text">
|
||||
<string>Turbo PWM</string>
|
||||
</property>
|
||||
<property name="icon">
|
||||
<iconset resource="../wizardResources.qrc">
|
||||
<normaloff>:/setupwizard/resources/bttn-turbo-up.png</normaloff>
|
||||
<normalon>:/setupwizard/resources/bttn-turbo-down.png</normalon>:/setupwizard/resources/bttn-turbo-up.png</iconset>
|
||||
</property>
|
||||
<property name="iconSize">
|
||||
<size>
|
||||
<width>200</width>
|
||||
<height>100</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="checkable">
|
||||
<bool>true</bool>
|
||||
</property>
|
||||
<property name="checked">
|
||||
<bool>true</bool>
|
||||
</property>
|
||||
<property name="autoExclusive">
|
||||
<bool>true</bool>
|
||||
</property>
|
||||
<property name="toolButtonStyle">
|
||||
<enum>Qt::ToolButtonTextUnderIcon</enum>
|
||||
</property>
|
||||
<property name="autoRaise">
|
||||
<bool>true</bool>
|
||||
</property>
|
||||
</widget>
|
||||
<widget class="QToolButton" name="defaultESCButton">
|
||||
<property name="geometry">
|
||||
<rect>
|
||||
<x>80</x>
|
||||
<y>250</y>
|
||||
<width>200</width>
|
||||
<height>120</height>
|
||||
</rect>
|
||||
</property>
|
||||
<property name="font">
|
||||
<font>
|
||||
<pointsize>10</pointsize>
|
||||
</font>
|
||||
</property>
|
||||
<property name="toolTip">
|
||||
<string>Standard ESC 50Hz</string>
|
||||
</property>
|
||||
<property name="styleSheet">
|
||||
<string notr="true">QToolButton { border: none }</string>
|
||||
</property>
|
||||
<property name="text">
|
||||
<string>Standard ESC</string>
|
||||
</property>
|
||||
<property name="icon">
|
||||
<iconset resource="../wizardResources.qrc">
|
||||
<normaloff>:/setupwizard/resources/bttn-ESC-up.png</normaloff>
|
||||
<normalon>:/setupwizard/resources/bttn-ESC-down.png</normalon>:/setupwizard/resources/bttn-ESC-up.png</iconset>
|
||||
</property>
|
||||
<property name="iconSize">
|
||||
<size>
|
||||
<width>200</width>
|
||||
<height>100</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="checkable">
|
||||
<bool>true</bool>
|
||||
</property>
|
||||
<property name="checked">
|
||||
<bool>false</bool>
|
||||
</property>
|
||||
<property name="autoExclusive">
|
||||
<bool>true</bool>
|
||||
</property>
|
||||
<property name="toolButtonStyle">
|
||||
<enum>Qt::ToolButtonTextUnderIcon</enum>
|
||||
</property>
|
||||
<property name="autoRaise">
|
||||
<bool>true</bool>
|
||||
</property>
|
||||
</widget>
|
||||
</widget>
|
||||
<resources>
|
||||
<include location="../wizardResources.qrc"/>
|
||||
</resources>
|
||||
<connections/>
|
||||
</ui>
|
@ -0,0 +1,67 @@
|
||||
/**
|
||||
******************************************************************************
|
||||
*
|
||||
* @file rebootpage.cpp
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012.
|
||||
* @addtogroup
|
||||
* @{
|
||||
* @addtogroup RebootPage
|
||||
* @{
|
||||
* @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 "rebootpage.h"
|
||||
#include "ui_rebootpage.h"
|
||||
|
||||
RebootPage::RebootPage(SetupWizard *wizard, QWidget *parent) :
|
||||
AbstractWizardPage(wizard, parent),
|
||||
ui(new Ui::RebootPage), m_toggl(false)
|
||||
{
|
||||
ui->setupUi(this);
|
||||
ui->yellowLabel->setVisible(false);
|
||||
ui->redLabel->setVisible(true);
|
||||
}
|
||||
|
||||
RebootPage::~RebootPage()
|
||||
{
|
||||
disconnect(&m_timer, SIGNAL(timeout()), this, SLOT(toggleLabel()));
|
||||
m_timer.stop();
|
||||
delete ui;
|
||||
}
|
||||
|
||||
void RebootPage::initializePage()
|
||||
{
|
||||
if(!m_timer.isActive()) {
|
||||
connect(&m_timer, SIGNAL(timeout()), this, SLOT(toggleLabel()));
|
||||
m_timer.setInterval(500);
|
||||
m_timer.setSingleShot(false);
|
||||
m_timer.start();
|
||||
}
|
||||
}
|
||||
|
||||
bool RebootPage::validatePage()
|
||||
{
|
||||
return true;
|
||||
}
|
||||
|
||||
void RebootPage::toggleLabel()
|
||||
{
|
||||
m_toggl = !m_toggl;
|
||||
ui->yellowLabel->setVisible(m_toggl);
|
||||
ui->redLabel->setVisible(!m_toggl);
|
||||
}
|
@ -0,0 +1,57 @@
|
||||
/**
|
||||
******************************************************************************
|
||||
*
|
||||
* @file rebootpage.h
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012.
|
||||
* @addtogroup
|
||||
* @{
|
||||
* @addtogroup RebootPage
|
||||
* @{
|
||||
* @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 REBOOTPAGE_H
|
||||
#define REBOOTPAGE_H
|
||||
|
||||
#include "abstractwizardpage.h"
|
||||
|
||||
namespace Ui {
|
||||
class RebootPage;
|
||||
}
|
||||
|
||||
class RebootPage : public AbstractWizardPage
|
||||
{
|
||||
Q_OBJECT
|
||||
|
||||
public:
|
||||
explicit RebootPage(SetupWizard *wizard, QWidget *parent = 0);
|
||||
~RebootPage();
|
||||
|
||||
void initializePage();
|
||||
bool validatePage();
|
||||
|
||||
private:
|
||||
Ui::RebootPage *ui;
|
||||
QTimer m_timer;
|
||||
bool m_toggl;
|
||||
|
||||
private slots:
|
||||
void toggleLabel();
|
||||
};
|
||||
|
||||
#endif // REBOOTPAGE_H
|
@ -0,0 +1,91 @@
|
||||
<?xml version="1.0" encoding="UTF-8"?>
|
||||
<ui version="4.0">
|
||||
<class>RebootPage</class>
|
||||
<widget class="QWizardPage" name="RebootPage">
|
||||
<property name="geometry">
|
||||
<rect>
|
||||
<x>0</x>
|
||||
<y>0</y>
|
||||
<width>600</width>
|
||||
<height>400</height>
|
||||
</rect>
|
||||
</property>
|
||||
<property name="windowTitle">
|
||||
<string>WizardPage</string>
|
||||
</property>
|
||||
<widget class="QLabel" name="redLabel">
|
||||
<property name="geometry">
|
||||
<rect>
|
||||
<x>50</x>
|
||||
<y>130</y>
|
||||
<width>501</width>
|
||||
<height>41</height>
|
||||
</rect>
|
||||
</property>
|
||||
<property name="text">
|
||||
<string><!DOCTYPE HTML PUBLIC "-//W3C//DTD HTML 4.0//EN" "http://www.w3.org/TR/REC-html40/strict.dtd">
|
||||
<html><head><meta name="qrichtext" content="1" /><style type="text/css">
|
||||
p, li { white-space: pre-wrap; }
|
||||
</style></head><body style=" font-family:'MS Shell Dlg 2'; font-size:8pt; font-weight:400; font-style:normal;">
|
||||
<p align="center" style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-size:18pt; color:#ff0000;">PLEASE REBOOT YOUR CONTROLLER</span></p></body></html></string>
|
||||
</property>
|
||||
<property name="alignment">
|
||||
<set>Qt::AlignLeading|Qt::AlignLeft|Qt::AlignTop</set>
|
||||
</property>
|
||||
<property name="wordWrap">
|
||||
<bool>true</bool>
|
||||
</property>
|
||||
</widget>
|
||||
<widget class="QLabel" name="label_3">
|
||||
<property name="geometry">
|
||||
<rect>
|
||||
<x>50</x>
|
||||
<y>180</y>
|
||||
<width>501</width>
|
||||
<height>151</height>
|
||||
</rect>
|
||||
</property>
|
||||
<property name="text">
|
||||
<string><!DOCTYPE HTML PUBLIC "-//W3C//DTD HTML 4.0//EN" "http://www.w3.org/TR/REC-html40/strict.dtd">
|
||||
<html><head><meta name="qrichtext" content="1" /><style type="text/css">
|
||||
p, li { white-space: pre-wrap; }
|
||||
</style></head><body style=" font-family:'MS Shell Dlg 2'; font-size:8pt; font-weight:400; font-style:normal;">
|
||||
<p align="center" style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-size:10pt; color:#000000;">The configuration created by the wizard contains settings that require a reboot of your controller. Please power cycle the controller before continuing. To power cycle the controller remove all batteries and the USB cable for at least 30 seconds. </span></p></body></html></string>
|
||||
</property>
|
||||
<property name="alignment">
|
||||
<set>Qt::AlignLeading|Qt::AlignLeft|Qt::AlignTop</set>
|
||||
</property>
|
||||
<property name="wordWrap">
|
||||
<bool>true</bool>
|
||||
</property>
|
||||
</widget>
|
||||
<widget class="QLabel" name="yellowLabel">
|
||||
<property name="geometry">
|
||||
<rect>
|
||||
<x>50</x>
|
||||
<y>130</y>
|
||||
<width>501</width>
|
||||
<height>41</height>
|
||||
</rect>
|
||||
</property>
|
||||
<property name="text">
|
||||
<string><!DOCTYPE HTML PUBLIC "-//W3C//DTD HTML 4.0//EN" "http://www.w3.org/TR/REC-html40/strict.dtd">
|
||||
<html><head><meta name="qrichtext" content="1" /><style type="text/css">
|
||||
p, li { white-space: pre-wrap; }
|
||||
</style></head><body style=" font-family:'MS Shell Dlg 2'; font-size:8pt; font-weight:400; font-style:normal;">
|
||||
<p align="center" style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-size:18pt; color:#ffd500;">PLEASE REBOOT YOUR CONTROLLER</span></p></body></html></string>
|
||||
</property>
|
||||
<property name="alignment">
|
||||
<set>Qt::AlignLeading|Qt::AlignLeft|Qt::AlignTop</set>
|
||||
</property>
|
||||
<property name="wordWrap">
|
||||
<bool>true</bool>
|
||||
</property>
|
||||
</widget>
|
||||
<zorder>yellowLabel</zorder>
|
||||
<zorder>redLabel</zorder>
|
||||
<zorder>label_3</zorder>
|
||||
</widget>
|
||||
<resources/>
|
||||
<connections/>
|
||||
</ui>
|
103
ground/openpilotgcs/src/plugins/setupwizard/pages/savepage.cpp
Normal file
@ -0,0 +1,103 @@
|
||||
/**
|
||||
******************************************************************************
|
||||
*
|
||||
* @file savepage.cpp
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012.
|
||||
* @addtogroup
|
||||
* @{
|
||||
* @addtogroup SavePage
|
||||
* @{
|
||||
* @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 <QMessageBox>
|
||||
#include "savepage.h"
|
||||
#include "ui_savepage.h"
|
||||
#include "setupwizard.h"
|
||||
#include "vehicleconfigurationhelper.h"
|
||||
|
||||
SavePage::SavePage(SetupWizard *wizard, QWidget *parent) :
|
||||
AbstractWizardPage(wizard, parent),
|
||||
ui(new Ui::SavePage), m_successfulWrite(false)
|
||||
{
|
||||
ui->setupUi(this);
|
||||
connect(ui->saveButton, SIGNAL(clicked()), this, SLOT(writeToController()));
|
||||
}
|
||||
|
||||
SavePage::~SavePage()
|
||||
{
|
||||
delete ui;
|
||||
}
|
||||
|
||||
bool SavePage::validatePage()
|
||||
{
|
||||
return true;
|
||||
}
|
||||
|
||||
bool SavePage::isComplete() const
|
||||
{
|
||||
return m_successfulWrite;
|
||||
}
|
||||
|
||||
void SavePage::writeToController()
|
||||
{
|
||||
if(!getWizard()->getConnectionManager()->isConnected()) {
|
||||
QMessageBox msgBox;
|
||||
msgBox.setText(tr("An OpenPilot controller must be connected to your computer to save the "
|
||||
"configuration.\nPlease connect your OpenPilot controller to your computer and try again."));
|
||||
msgBox.setStandardButtons(QMessageBox::Ok);
|
||||
msgBox.setDefaultButton(QMessageBox::Ok);
|
||||
msgBox.exec();
|
||||
return;
|
||||
}
|
||||
|
||||
enableButtons(false);
|
||||
VehicleConfigurationHelper helper(getWizard());
|
||||
connect(&helper, SIGNAL(saveProgress(int, int, QString)),this, SLOT(saveProgress(int, int, QString)));
|
||||
|
||||
m_successfulWrite = helper.setupVehicle();
|
||||
|
||||
disconnect(&helper, SIGNAL(saveProgress(int, int, QString)),this, SLOT(saveProgress(int, int, QString)));
|
||||
ui->saveProgressLabel->setText(QString("<font color='%1'>%2</font>").arg(m_successfulWrite ? "green" : "red", ui->saveProgressLabel->text()));
|
||||
enableButtons(true);
|
||||
|
||||
emit completeChanged();
|
||||
}
|
||||
|
||||
void SavePage::enableButtons(bool enable)
|
||||
{
|
||||
ui->saveButton->setEnabled(enable);
|
||||
getWizard()->button(QWizard::NextButton)->setEnabled(enable);
|
||||
getWizard()->button(QWizard::CancelButton)->setEnabled(enable);
|
||||
getWizard()->button(QWizard::BackButton)->setEnabled(enable);
|
||||
QApplication::processEvents();
|
||||
}
|
||||
|
||||
void SavePage::saveProgress(int total, int current, QString description)
|
||||
{
|
||||
qDebug() << "Progress " << current << "(" << total << ")";
|
||||
if(ui->saveProgressBar->maximum() != total) {
|
||||
ui->saveProgressBar->setMaximum(total);
|
||||
}
|
||||
if(ui->saveProgressBar->value() != current) {
|
||||
ui->saveProgressBar->setValue(current);
|
||||
}
|
||||
if(ui->saveProgressLabel->text() != description) {
|
||||
ui->saveProgressLabel->setText(description);
|
||||
}
|
||||
}
|
57
ground/openpilotgcs/src/plugins/setupwizard/pages/savepage.h
Normal file
@ -0,0 +1,57 @@
|
||||
/**
|
||||
******************************************************************************
|
||||
*
|
||||
* @file savepage.h
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012.
|
||||
* @addtogroup
|
||||
* @{
|
||||
* @addtogroup SavePage
|
||||
* @{
|
||||
* @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 SAVEPAGE_H
|
||||
#define SAVEPAGE_H
|
||||
|
||||
#include "abstractwizardpage.h"
|
||||
|
||||
namespace Ui {
|
||||
class SavePage;
|
||||
}
|
||||
|
||||
class SavePage : public AbstractWizardPage
|
||||
{
|
||||
Q_OBJECT
|
||||
|
||||
public:
|
||||
explicit SavePage(SetupWizard *wizard, QWidget *parent = 0);
|
||||
~SavePage();
|
||||
bool validatePage();
|
||||
bool isComplete() const;
|
||||
|
||||
private:
|
||||
Ui::SavePage *ui;
|
||||
bool m_successfulWrite;
|
||||
void enableButtons(bool enable);
|
||||
|
||||
private slots:
|
||||
void writeToController();
|
||||
void saveProgress(int total, int current, QString description);
|
||||
};
|
||||
|
||||
#endif // SAVEPAGE_H
|
132
ground/openpilotgcs/src/plugins/setupwizard/pages/savepage.ui
Normal file
@ -0,0 +1,132 @@
|
||||
<?xml version="1.0" encoding="UTF-8"?>
|
||||
<ui version="4.0">
|
||||
<class>SavePage</class>
|
||||
<widget class="QWizardPage" name="SavePage">
|
||||
<property name="geometry">
|
||||
<rect>
|
||||
<x>0</x>
|
||||
<y>0</y>
|
||||
<width>600</width>
|
||||
<height>400</height>
|
||||
</rect>
|
||||
</property>
|
||||
<property name="windowTitle">
|
||||
<string>WizardPage</string>
|
||||
</property>
|
||||
<widget class="QLabel" name="label">
|
||||
<property name="geometry">
|
||||
<rect>
|
||||
<x>20</x>
|
||||
<y>20</y>
|
||||
<width>541</width>
|
||||
<height>231</height>
|
||||
</rect>
|
||||
</property>
|
||||
<property name="text">
|
||||
<string><!DOCTYPE HTML PUBLIC "-//W3C//DTD HTML 4.0//EN" "http://www.w3.org/TR/REC-html40/strict.dtd">
|
||||
<html><head><meta name="qrichtext" content="1" /><style type="text/css">
|
||||
p, li { white-space: pre-wrap; }
|
||||
</style></head><body style=" font-family:'MS Shell Dlg 2'; font-size:8pt; font-weight:400; font-style:normal;">
|
||||
<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-size:12pt; font-weight:600;">OpenPilot configuration ready to save</span></p>
|
||||
<p style="-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;"><br /></p>
|
||||
<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-size:10pt;">The wizard is now ready to save the configuration directly to your OpenPilot controller. </span></p>
|
||||
<p style="-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;"><br /></p>
|
||||
<p style="-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;"><br /></p>
|
||||
<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-size:10pt;">If any of the selections made in this wizard require a reboot of the controller, then power cycling the OpenPilot controller board will have to be performed after you save in this step.</span></p>
|
||||
<p style="-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;"><br /></p>
|
||||
<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-size:10pt;">Press the Save button to save the configuration.</span></p>
|
||||
<p style="-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;"><br /></p>
|
||||
<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-size:10pt;"><br /></span></p></body></html></string>
|
||||
</property>
|
||||
<property name="alignment">
|
||||
<set>Qt::AlignLeading|Qt::AlignLeft|Qt::AlignTop</set>
|
||||
</property>
|
||||
<property name="wordWrap">
|
||||
<bool>true</bool>
|
||||
</property>
|
||||
</widget>
|
||||
<widget class="QToolButton" name="saveButton">
|
||||
<property name="geometry">
|
||||
<rect>
|
||||
<x>225</x>
|
||||
<y>260</y>
|
||||
<width>150</width>
|
||||
<height>70</height>
|
||||
</rect>
|
||||
</property>
|
||||
<property name="toolTip">
|
||||
<string>Write configuration to controller</string>
|
||||
</property>
|
||||
<property name="styleSheet">
|
||||
<string notr="true">QToolButton { border: none }</string>
|
||||
</property>
|
||||
<property name="text">
|
||||
<string>Save</string>
|
||||
</property>
|
||||
<property name="icon">
|
||||
<iconset resource="../wizardResources.qrc">
|
||||
<normaloff>:/setupwizard/resources/bttn-save-up.png</normaloff>
|
||||
<normalon>:/setupwizard/resources/bttn-save-down.png</normalon>:/setupwizard/resources/bttn-save-up.png</iconset>
|
||||
</property>
|
||||
<property name="iconSize">
|
||||
<size>
|
||||
<width>200</width>
|
||||
<height>70</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="toolButtonStyle">
|
||||
<enum>Qt::ToolButtonIconOnly</enum>
|
||||
</property>
|
||||
</widget>
|
||||
<widget class="QLabel" name="saveProgressLabel">
|
||||
<property name="geometry">
|
||||
<rect>
|
||||
<x>42</x>
|
||||
<y>330</y>
|
||||
<width>441</width>
|
||||
<height>16</height>
|
||||
</rect>
|
||||
</property>
|
||||
<property name="font">
|
||||
<font>
|
||||
<pointsize>10</pointsize>
|
||||
</font>
|
||||
</property>
|
||||
<property name="text">
|
||||
<string>Ready...</string>
|
||||
</property>
|
||||
</widget>
|
||||
<widget class="QProgressBar" name="saveProgressBar">
|
||||
<property name="geometry">
|
||||
<rect>
|
||||
<x>40</x>
|
||||
<y>350</y>
|
||||
<width>520</width>
|
||||
<height>23</height>
|
||||
</rect>
|
||||
</property>
|
||||
<property name="styleSheet">
|
||||
<string notr="true">QProgressBar {
|
||||
border: 2px solid grey;
|
||||
border-radius: 5px;
|
||||
text-align: center;
|
||||
}
|
||||
QProgressBar::chunk {
|
||||
background-color: #3D6699;
|
||||
width: 10px;
|
||||
margin: 0.5px;
|
||||
}</string>
|
||||
</property>
|
||||
<property name="value">
|
||||
<number>0</number>
|
||||
</property>
|
||||
<property name="format">
|
||||
<string/>
|
||||
</property>
|
||||
</widget>
|
||||
</widget>
|
||||
<resources>
|
||||
<include location="../wizardResources.qrc"/>
|
||||
</resources>
|
||||
<connections/>
|
||||
</ui>
|
@ -0,0 +1,40 @@
|
||||
/**
|
||||
******************************************************************************
|
||||
*
|
||||
* @file startpage.cpp
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012.
|
||||
* @addtogroup GCSPlugins GCS Plugins
|
||||
* @{
|
||||
* @addtogroup Setup Wizard Plugin
|
||||
* @{
|
||||
* @brief A Wizard to make the initial setup easy for everyone.
|
||||
*****************************************************************************/
|
||||
/*
|
||||
* 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 "startpage.h"
|
||||
#include "ui_startpage.h"
|
||||
|
||||
StartPage::StartPage(SetupWizard *wizard, QWidget *parent) :
|
||||
AbstractWizardPage(wizard, parent),
|
||||
ui(new Ui::StartPage)
|
||||
{
|
||||
ui->setupUi(this);
|
||||
}
|
||||
|
||||
StartPage::~StartPage()
|
||||
{
|
||||
delete ui;
|
||||
}
|
@ -0,0 +1,48 @@
|
||||
/**
|
||||
******************************************************************************
|
||||
*
|
||||
* @file startpage.cpp
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012.
|
||||
* @addtogroup GCSPlugins GCS Plugins
|
||||
* @{
|
||||
* @addtogroup Setup Wizard Plugin
|
||||
* @{
|
||||
* @brief A Wizard to make the initial setup easy for everyone.
|
||||
*****************************************************************************/
|
||||
/*
|
||||
* 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 STARTPAGE_H
|
||||
#define STARTPAGE_H
|
||||
|
||||
#include "abstractwizardpage.h"
|
||||
|
||||
namespace Ui {
|
||||
class StartPage;
|
||||
}
|
||||
|
||||
class StartPage : public AbstractWizardPage
|
||||
{
|
||||
Q_OBJECT
|
||||
|
||||
public:
|
||||
explicit StartPage(SetupWizard *wizard, QWidget *parent = 0);
|
||||
~StartPage();
|
||||
|
||||
private:
|
||||
Ui::StartPage *ui;
|
||||
};
|
||||
|
||||
#endif // STARTPAGE_H
|
@ -0,0 +1,59 @@
|
||||
<?xml version="1.0" encoding="UTF-8"?>
|
||||
<ui version="4.0">
|
||||
<class>StartPage</class>
|
||||
<widget class="QWizardPage" name="StartPage">
|
||||
<property name="geometry">
|
||||
<rect>
|
||||
<x>0</x>
|
||||
<y>0</y>
|
||||
<width>640</width>
|
||||
<height>400</height>
|
||||
</rect>
|
||||
</property>
|
||||
<property name="minimumSize">
|
||||
<size>
|
||||
<width>640</width>
|
||||
<height>400</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="windowTitle">
|
||||
<string>WizardPage</string>
|
||||
</property>
|
||||
<widget class="QLabel" name="label_2">
|
||||
<property name="geometry">
|
||||
<rect>
|
||||
<x>20</x>
|
||||
<y>20</y>
|
||||
<width>581</width>
|
||||
<height>350</height>
|
||||
</rect>
|
||||
</property>
|
||||
<property name="text">
|
||||
<string><!DOCTYPE HTML PUBLIC "-//W3C//DTD HTML 4.0//EN" "http://www.w3.org/TR/REC-html40/strict.dtd">
|
||||
<html><head><meta name="qrichtext" content="1" /><style type="text/css">
|
||||
p, li { white-space: pre-wrap; }
|
||||
</style></head><body style=" font-family:'MS Shell Dlg 2'; font-size:8pt; font-weight:400; font-style:normal;">
|
||||
<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-size:12pt; font-weight:600;">Welcome to the OpenPilot Setup Wizard</span></p>
|
||||
<p style="-qt-paragraph-type:empty; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><br /></p>
|
||||
<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-size:10pt;">This wizard will guide you through the basic steps required to setup your OpenPilot controller for the first time. You will be asked questions about your platform (multirotor/heli/fixed-wing) which this wizard will use to configure your aircraft for your maiden flight. </span></p>
|
||||
<p style="-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;"><br /></p>
|
||||
<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-size:10pt;">This wizard does not configure all of the advanced settings available in the GCS Configuration. All basic and advanced configuration parameters can be modified later by using the GCS Configuration plugin.</span></p>
|
||||
<p style="-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;"><br /></p>
|
||||
<p align="center" style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-size:12pt; font-weight:600; color:#ff0000;">WARNING: YOU MUST REMOVE ALL PROPELLERS </span></p>
|
||||
<p align="center" style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-size:12pt; font-weight:600; color:#ff0000;">FROM THE VEHICLE BEFORE PROCEEDING!</span></p>
|
||||
<p style="-qt-paragraph-type:empty; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px; font-family:'Lucida Grande'; font-size:13pt;"><br /></p>
|
||||
<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-size:10pt;">Disregarding this warning puts you at</span><span style=" font-size:10pt; font-weight:600; color:#000000;"> risk of very serious injury</span><span style=" font-size:10pt;">!</span></p>
|
||||
<p style="-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;"><br /></p>
|
||||
<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-size:10pt;">Now that your props are removed we can get started. Ready?</span></p></body></html></string>
|
||||
</property>
|
||||
<property name="alignment">
|
||||
<set>Qt::AlignLeading|Qt::AlignLeft|Qt::AlignTop</set>
|
||||
</property>
|
||||
<property name="wordWrap">
|
||||
<bool>true</bool>
|
||||
</property>
|
||||
</widget>
|
||||
</widget>
|
||||
<resources/>
|
||||
<connections/>
|
||||
</ui>
|
@ -0,0 +1,60 @@
|
||||
/**
|
||||
******************************************************************************
|
||||
*
|
||||
* @file summarypage.cpp
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012.
|
||||
* @addtogroup
|
||||
* @{
|
||||
* @addtogroup SummaryPage
|
||||
* @{
|
||||
* @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 "summarypage.h"
|
||||
#include "ui_summarypage.h"
|
||||
#include "setupwizard.h"
|
||||
#include "connectiondiagram.h"
|
||||
|
||||
SummaryPage::SummaryPage(SetupWizard *wizard, QWidget *parent) :
|
||||
AbstractWizardPage(wizard, parent),
|
||||
ui(new Ui::SummaryPage)
|
||||
{
|
||||
ui->setupUi(this);
|
||||
connect(ui->illustrationButton, SIGNAL(clicked()), this, SLOT(showDiagram()));
|
||||
}
|
||||
|
||||
SummaryPage::~SummaryPage()
|
||||
{
|
||||
delete ui;
|
||||
}
|
||||
|
||||
bool SummaryPage::validatePage()
|
||||
{
|
||||
return true;
|
||||
}
|
||||
|
||||
void SummaryPage::initializePage()
|
||||
{
|
||||
ui->configurationSummary->setText(getWizard()->getSummaryText());
|
||||
}
|
||||
|
||||
void SummaryPage::showDiagram()
|
||||
{
|
||||
ConnectionDiagram diagram(this, getWizard());
|
||||
diagram.exec();
|
||||
}
|
@ -0,0 +1,54 @@
|
||||
/**
|
||||
******************************************************************************
|
||||
*
|
||||
* @file summarypage.h
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012.
|
||||
* @addtogroup
|
||||
* @{
|
||||
* @addtogroup SummaryPage
|
||||
* @{
|
||||
* @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 SUMMARYPAGE_H
|
||||
#define SUMMARYPAGE_H
|
||||
|
||||
#include "abstractwizardpage.h"
|
||||
|
||||
namespace Ui {
|
||||
class SummaryPage;
|
||||
}
|
||||
|
||||
class SummaryPage : public AbstractWizardPage
|
||||
{
|
||||
Q_OBJECT
|
||||
|
||||
public:
|
||||
explicit SummaryPage(SetupWizard *wizard, QWidget *parent = 0);
|
||||
~SummaryPage();
|
||||
bool validatePage();
|
||||
void initializePage();
|
||||
|
||||
private:
|
||||
Ui::SummaryPage *ui;
|
||||
|
||||
private slots:
|
||||
void showDiagram();
|
||||
};
|
||||
|
||||
#endif // SUMMARYPAGE_H
|
117
ground/openpilotgcs/src/plugins/setupwizard/pages/summarypage.ui
Normal file
@ -0,0 +1,117 @@
|
||||
<?xml version="1.0" encoding="UTF-8"?>
|
||||
<ui version="4.0">
|
||||
<class>SummaryPage</class>
|
||||
<widget class="QWizardPage" name="SummaryPage">
|
||||
<property name="geometry">
|
||||
<rect>
|
||||
<x>0</x>
|
||||
<y>0</y>
|
||||
<width>600</width>
|
||||
<height>400</height>
|
||||
</rect>
|
||||
</property>
|
||||
<property name="windowTitle">
|
||||
<string>WizardPage</string>
|
||||
</property>
|
||||
<widget class="QLabel" name="label">
|
||||
<property name="geometry">
|
||||
<rect>
|
||||
<x>20</x>
|
||||
<y>20</y>
|
||||
<width>541</width>
|
||||
<height>241</height>
|
||||
</rect>
|
||||
</property>
|
||||
<property name="text">
|
||||
<string><!DOCTYPE HTML PUBLIC "-//W3C//DTD HTML 4.0//EN" "http://www.w3.org/TR/REC-html40/strict.dtd">
|
||||
<html><head><meta name="qrichtext" content="1" /><style type="text/css">
|
||||
p, li { white-space: pre-wrap; }
|
||||
</style></head><body style=" font-family:'MS Shell Dlg 2'; font-size:8pt; font-weight:400; font-style:normal;">
|
||||
<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-size:12pt; font-weight:600;">OpenPilot configuration summary</span></p>
|
||||
<p style="-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;"><br /></p>
|
||||
<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-size:10pt;">The first part of this wizard is now complete. All information required to create a basic OpenPilot controller configuration for a specific vehicle has been collected.</span></p>
|
||||
<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-size:10pt;">Below is a summary of the configuration and a button that links to a diagram illustrating how to connect required hardware and the OpenPilot Controller with the current configuration.</span></p>
|
||||
<p style="-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;"><br /></p>
|
||||
<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-size:10pt;">To continue the wizard and go through some basic configuration steps, please continue to the next step of this wizard.</span></p>
|
||||
<p style="-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;"><br /></p>
|
||||
<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-size:10pt;">The following steps require that your OpenPilot controller is set up according to the diagram, it is </span><span style=" font-size:10pt; font-weight:600;">connected to the computer</span><span style=" font-size:10pt;"> by USB, and that the vehicle is</span><span style=" font-size:10pt; font-weight:600;"> powered by a battery</span><span style=" font-size:10pt;">.</span></p></body></html></string>
|
||||
</property>
|
||||
<property name="alignment">
|
||||
<set>Qt::AlignLeading|Qt::AlignLeft|Qt::AlignTop</set>
|
||||
</property>
|
||||
<property name="wordWrap">
|
||||
<bool>true</bool>
|
||||
</property>
|
||||
</widget>
|
||||
<widget class="QToolButton" name="illustrationButton">
|
||||
<property name="geometry">
|
||||
<rect>
|
||||
<x>460</x>
|
||||
<y>271</y>
|
||||
<width>100</width>
|
||||
<height>100</height>
|
||||
</rect>
|
||||
</property>
|
||||
<property name="toolTip">
|
||||
<string>Show connection diagram for configuration</string>
|
||||
</property>
|
||||
<property name="styleSheet">
|
||||
<string notr="true">QToolButton { border: none }</string>
|
||||
</property>
|
||||
<property name="text">
|
||||
<string/>
|
||||
</property>
|
||||
<property name="icon">
|
||||
<iconset resource="../wizardResources.qrc">
|
||||
<normaloff>:/setupwizard/resources/bttn-illustration-up.png</normaloff>
|
||||
<normalon>:/setupwizard/resources/bttn-illustration-down.png</normalon>:/setupwizard/resources/bttn-illustration-up.png</iconset>
|
||||
</property>
|
||||
<property name="iconSize">
|
||||
<size>
|
||||
<width>100</width>
|
||||
<height>100</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="checkable">
|
||||
<bool>false</bool>
|
||||
</property>
|
||||
<property name="checked">
|
||||
<bool>false</bool>
|
||||
</property>
|
||||
<property name="autoExclusive">
|
||||
<bool>true</bool>
|
||||
</property>
|
||||
<property name="toolButtonStyle">
|
||||
<enum>Qt::ToolButtonIconOnly</enum>
|
||||
</property>
|
||||
</widget>
|
||||
<widget class="QTextEdit" name="configurationSummary">
|
||||
<property name="geometry">
|
||||
<rect>
|
||||
<x>20</x>
|
||||
<y>270</y>
|
||||
<width>400</width>
|
||||
<height>100</height>
|
||||
</rect>
|
||||
</property>
|
||||
<property name="font">
|
||||
<font>
|
||||
<pointsize>10</pointsize>
|
||||
</font>
|
||||
</property>
|
||||
<property name="verticalScrollBarPolicy">
|
||||
<enum>Qt::ScrollBarAlwaysOn</enum>
|
||||
</property>
|
||||
<property name="horizontalScrollBarPolicy">
|
||||
<enum>Qt::ScrollBarAlwaysOff</enum>
|
||||
</property>
|
||||
<property name="textInteractionFlags">
|
||||
<set>Qt::TextSelectableByKeyboard|Qt::TextSelectableByMouse</set>
|
||||
</property>
|
||||
</widget>
|
||||
</widget>
|
||||
<resources>
|
||||
<include location="../wizardResources.qrc"/>
|
||||
</resources>
|
||||
<connections/>
|
||||
</ui>
|
@ -0,0 +1,42 @@
|
||||
/**
|
||||
******************************************************************************
|
||||
*
|
||||
* @file surfacepage.cpp
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012.
|
||||
* @addtogroup
|
||||
* @{
|
||||
* @addtogroup SurfacePage
|
||||
* @{
|
||||
* @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 "surfacepage.h"
|
||||
#include "ui_surfacepage.h"
|
||||
|
||||
SurfacePage::SurfacePage(SetupWizard *wizard, QWidget *parent) :
|
||||
AbstractWizardPage(wizard, parent),
|
||||
ui(new Ui::SurfacePage)
|
||||
{
|
||||
ui->setupUi(this);
|
||||
setFinalPage(true);
|
||||
}
|
||||
|
||||
SurfacePage::~SurfacePage()
|
||||
{
|
||||
delete ui;
|
||||
}
|
@ -0,0 +1,49 @@
|
||||
/**
|
||||
******************************************************************************
|
||||
*
|
||||
* @file surfacepage.h
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012.
|
||||
* @addtogroup
|
||||
* @{
|
||||
* @addtogroup SurfacePage
|
||||
* @{
|
||||
* @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 SURFACEPAGE_H
|
||||
#define SURFACEPAGE_H
|
||||
|
||||
#include "abstractwizardpage.h"
|
||||
|
||||
namespace Ui {
|
||||
class SurfacePage;
|
||||
}
|
||||
|
||||
class SurfacePage : public AbstractWizardPage
|
||||
{
|
||||
Q_OBJECT
|
||||
|
||||
public:
|
||||
explicit SurfacePage(SetupWizard *wizard, QWidget *parent = 0);
|
||||
~SurfacePage();
|
||||
|
||||
private:
|
||||
Ui::SurfacePage *ui;
|
||||
};
|
||||
|
||||
#endif // SURFACEPAGE_H
|
@ -0,0 +1,43 @@
|
||||
<?xml version="1.0" encoding="UTF-8"?>
|
||||
<ui version="4.0">
|
||||
<class>SurfacePage</class>
|
||||
<widget class="QWizardPage" name="SurfacePage">
|
||||
<property name="geometry">
|
||||
<rect>
|
||||
<x>0</x>
|
||||
<y>0</y>
|
||||
<width>600</width>
|
||||
<height>400</height>
|
||||
</rect>
|
||||
</property>
|
||||
<property name="windowTitle">
|
||||
<string>WizardPage</string>
|
||||
</property>
|
||||
<widget class="QLabel" name="label_2">
|
||||
<property name="geometry">
|
||||
<rect>
|
||||
<x>50</x>
|
||||
<y>160</y>
|
||||
<width>500</width>
|
||||
<height>41</height>
|
||||
</rect>
|
||||
</property>
|
||||
<property name="text">
|
||||
<string><!DOCTYPE HTML PUBLIC "-//W3C//DTD HTML 4.0//EN" "http://www.w3.org/TR/REC-html40/strict.dtd">
|
||||
<html><head><meta name="qrichtext" content="1" /><style type="text/css">
|
||||
p, li { white-space: pre-wrap; }
|
||||
</style></head><body style=" font-family:'MS Shell Dlg 2'; font-size:8.25pt; font-weight:400; font-style:normal;">
|
||||
<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-size:12pt; font-weight:600;">The Surface Vehicle section of the OpenPilot Setup Wizard is not yet implemented</span></p>
|
||||
<p style="-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:8pt;"></p></body></html></string>
|
||||
</property>
|
||||
<property name="alignment">
|
||||
<set>Qt::AlignHCenter|Qt::AlignTop</set>
|
||||
</property>
|
||||
<property name="wordWrap">
|
||||
<bool>true</bool>
|
||||
</property>
|
||||
</widget>
|
||||
</widget>
|
||||
<resources/>
|
||||
<connections/>
|
||||
</ui>
|
@ -0,0 +1,61 @@
|
||||
/**
|
||||
******************************************************************************
|
||||
*
|
||||
* @file vehiclepage.cpp
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012.
|
||||
* @addtogroup
|
||||
* @{
|
||||
* @addtogroup VehiclePage
|
||||
* @{
|
||||
* @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 "vehiclepage.h"
|
||||
#include "ui_vehiclepage.h"
|
||||
|
||||
VehiclePage::VehiclePage(SetupWizard *wizard, QWidget *parent) :
|
||||
AbstractWizardPage(wizard, parent),
|
||||
ui(new Ui::VehiclePage)
|
||||
{
|
||||
ui->setupUi(this);
|
||||
}
|
||||
|
||||
VehiclePage::~VehiclePage()
|
||||
{
|
||||
delete ui;
|
||||
}
|
||||
|
||||
bool VehiclePage::validatePage()
|
||||
{
|
||||
if(ui->multirotorButton->isChecked()) {
|
||||
getWizard()->setVehicleType(SetupWizard::VEHICLE_MULTI);
|
||||
}
|
||||
else if(ui->fixedwingButton->isChecked()) {
|
||||
getWizard()->setVehicleType(SetupWizard::VEHICLE_FIXEDWING);
|
||||
}
|
||||
else if(ui->heliButton->isChecked()) {
|
||||
getWizard()->setVehicleType(SetupWizard::VEHICLE_HELI);
|
||||
}
|
||||
else if(ui->surfaceButton->isChecked()) {
|
||||
getWizard()->setVehicleType(SetupWizard::VEHICLE_SURFACE);
|
||||
}
|
||||
else {
|
||||
getWizard()->setVehicleType(SetupWizard::VEHICLE_UNKNOWN);
|
||||
}
|
||||
return true;
|
||||
}
|
@ -0,0 +1,50 @@
|
||||
/**
|
||||
******************************************************************************
|
||||
*
|
||||
* @file vehiclepage.h
|
||||
* @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012.
|
||||
* @addtogroup
|
||||
* @{
|
||||
* @addtogroup VehiclePage
|
||||
* @{
|
||||
* @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 VEHICLEPAGE_H
|
||||
#define VEHICLEPAGE_H
|
||||
|
||||
#include "abstractwizardpage.h"
|
||||
|
||||
namespace Ui {
|
||||
class VehiclePage;
|
||||
}
|
||||
|
||||
class VehiclePage : public AbstractWizardPage
|
||||
{
|
||||
Q_OBJECT
|
||||
|
||||
public:
|
||||
explicit VehiclePage(SetupWizard *wizard, QWidget *parent = 0);
|
||||
~VehiclePage();
|
||||
bool validatePage();
|
||||
|
||||
private:
|
||||
Ui::VehiclePage *ui;
|
||||
};
|
||||
|
||||
#endif // VEHICLEPAGE_H
|
256
ground/openpilotgcs/src/plugins/setupwizard/pages/vehiclepage.ui
Normal file
@ -0,0 +1,256 @@
|
||||
<?xml version="1.0" encoding="UTF-8"?>
|
||||
<ui version="4.0">
|
||||
<class>VehiclePage</class>
|
||||
<widget class="QWizardPage" name="VehiclePage">
|
||||
<property name="geometry">
|
||||
<rect>
|
||||
<x>0</x>
|
||||
<y>0</y>
|
||||
<width>600</width>
|
||||
<height>400</height>
|
||||
</rect>
|
||||
</property>
|
||||
<property name="windowTitle">
|
||||
<string>WizardPage</string>
|
||||
</property>
|
||||
<widget class="QLabel" name="label_2">
|
||||
<property name="geometry">
|
||||
<rect>
|
||||
<x>20</x>
|
||||
<y>20</y>
|
||||
<width>550</width>
|
||||
<height>221</height>
|
||||
</rect>
|
||||
</property>
|
||||
<property name="text">
|
||||
<string><!DOCTYPE HTML PUBLIC "-//W3C//DTD HTML 4.0//EN" "http://www.w3.org/TR/REC-html40/strict.dtd">
|
||||
<html><head><meta name="qrichtext" content="1" /><style type="text/css">
|
||||
p, li { white-space: pre-wrap; }
|
||||
</style></head><body style=" font-family:'MS Shell Dlg 2'; font-size:8pt; font-weight:400; font-style:normal;">
|
||||
<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-size:12pt; font-weight:600;">Vehicle type selection</span></p>
|
||||
<p style="-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;"><br /></p>
|
||||
<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-size:10pt;">To continue, the wizard needs to know what type of vehicle the OpenPilot controller board is going to be used with. This step is crucial since much of the following configuration is unique per vehicle type.</span></p>
|
||||
<p style="-qt-paragraph-type:empty; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><br /></p>
|
||||
<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-size:10pt;">Go ahead and select the type of vehicle for which you want to create a configuration.</span></p>
|
||||
<p style="-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;"><br /></p>
|
||||
<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-size:10pt;">(The current version only provides functionality for multirotors.)</span></p></body></html></string>
|
||||
</property>
|
||||
<property name="alignment">
|
||||
<set>Qt::AlignLeading|Qt::AlignLeft|Qt::AlignTop</set>
|
||||
</property>
|
||||
<property name="wordWrap">
|
||||
<bool>true</bool>
|
||||
</property>
|
||||
</widget>
|
||||
<widget class="QToolButton" name="surfaceButton">
|
||||
<property name="enabled">
|
||||
<bool>false</bool>
|
||||
</property>
|
||||
<property name="geometry">
|
||||
<rect>
|
||||
<x>430</x>
|
||||
<y>250</y>
|
||||
<width>100</width>
|
||||
<height>120</height>
|
||||
</rect>
|
||||
</property>
|
||||
<property name="font">
|
||||
<font>
|
||||
<pointsize>10</pointsize>
|
||||
</font>
|
||||
</property>
|
||||
<property name="toolTip">
|
||||
<string>Car, Boat, U-Boat</string>
|
||||
</property>
|
||||
<property name="styleSheet">
|
||||
<string notr="true">QToolButton { border: none }</string>
|
||||
</property>
|
||||
<property name="text">
|
||||
<string>Surface</string>
|
||||
</property>
|
||||
<property name="icon">
|
||||
<iconset resource="../wizardResources.qrc">
|
||||
<normaloff>:/setupwizard/resources/bttn-land-up.png</normaloff>
|
||||
<normalon>:/setupwizard/resources/bttn-land-down.png</normalon>:/setupwizard/resources/bttn-land-up.png</iconset>
|
||||
</property>
|
||||
<property name="iconSize">
|
||||
<size>
|
||||
<width>100</width>
|
||||
<height>100</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="checkable">
|
||||
<bool>true</bool>
|
||||
</property>
|
||||
<property name="autoExclusive">
|
||||
<bool>true</bool>
|
||||
</property>
|
||||
<property name="toolButtonStyle">
|
||||
<enum>Qt::ToolButtonTextUnderIcon</enum>
|
||||
</property>
|
||||
<property name="autoRaise">
|
||||
<bool>true</bool>
|
||||
</property>
|
||||
</widget>
|
||||
<widget class="QToolButton" name="multirotorButton">
|
||||
<property name="geometry">
|
||||
<rect>
|
||||
<x>70</x>
|
||||
<y>250</y>
|
||||
<width>100</width>
|
||||
<height>120</height>
|
||||
</rect>
|
||||
</property>
|
||||
<property name="font">
|
||||
<font>
|
||||
<pointsize>10</pointsize>
|
||||
</font>
|
||||
</property>
|
||||
<property name="toolTip">
|
||||
<string>Tricopter, Quadcopter, Hexacopter</string>
|
||||
</property>
|
||||
<property name="autoFillBackground">
|
||||
<bool>false</bool>
|
||||
</property>
|
||||
<property name="styleSheet">
|
||||
<string notr="true">QToolButton { border: none }</string>
|
||||
</property>
|
||||
<property name="text">
|
||||
<string>Multirotor</string>
|
||||
</property>
|
||||
<property name="icon">
|
||||
<iconset resource="../wizardResources.qrc">
|
||||
<normaloff>:/setupwizard/resources/bttn-multi-up.png</normaloff>
|
||||
<normalon>:/setupwizard/resources/bttn-multi-down.png</normalon>:/setupwizard/resources/bttn-multi-up.png</iconset>
|
||||
</property>
|
||||
<property name="iconSize">
|
||||
<size>
|
||||
<width>100</width>
|
||||
<height>100</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="checkable">
|
||||
<bool>true</bool>
|
||||
</property>
|
||||
<property name="checked">
|
||||
<bool>true</bool>
|
||||
</property>
|
||||
<property name="autoExclusive">
|
||||
<bool>true</bool>
|
||||
</property>
|
||||
<property name="toolButtonStyle">
|
||||
<enum>Qt::ToolButtonTextUnderIcon</enum>
|
||||
</property>
|
||||
<property name="autoRaise">
|
||||
<bool>true</bool>
|
||||
</property>
|
||||
</widget>
|
||||
<widget class="QToolButton" name="fixedwingButton">
|
||||
<property name="enabled">
|
||||
<bool>false</bool>
|
||||
</property>
|
||||
<property name="geometry">
|
||||
<rect>
|
||||
<x>190</x>
|
||||
<y>250</y>
|
||||
<width>100</width>
|
||||
<height>120</height>
|
||||
</rect>
|
||||
</property>
|
||||
<property name="font">
|
||||
<font>
|
||||
<pointsize>10</pointsize>
|
||||
</font>
|
||||
</property>
|
||||
<property name="toolTip">
|
||||
<string>Airplane, Sloper, Jet</string>
|
||||
</property>
|
||||
<property name="styleSheet">
|
||||
<string notr="true">QToolButton { border: none }</string>
|
||||
</property>
|
||||
<property name="text">
|
||||
<string>Fixed wing</string>
|
||||
</property>
|
||||
<property name="icon">
|
||||
<iconset resource="../wizardResources.qrc">
|
||||
<normaloff>:/setupwizard/resources/bttn-plane-up.png</normaloff>
|
||||
<normalon>:/setupwizard/resources/bttn-plane-down.png</normalon>:/setupwizard/resources/bttn-plane-up.png</iconset>
|
||||
</property>
|
||||
<property name="iconSize">
|
||||
<size>
|
||||
<width>100</width>
|
||||
<height>100</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="checkable">
|
||||
<bool>true</bool>
|
||||
</property>
|
||||
<property name="checked">
|
||||
<bool>false</bool>
|
||||
</property>
|
||||
<property name="autoExclusive">
|
||||
<bool>true</bool>
|
||||
</property>
|
||||
<property name="toolButtonStyle">
|
||||
<enum>Qt::ToolButtonTextUnderIcon</enum>
|
||||
</property>
|
||||
<property name="autoRaise">
|
||||
<bool>true</bool>
|
||||
</property>
|
||||
</widget>
|
||||
<widget class="QToolButton" name="heliButton">
|
||||
<property name="enabled">
|
||||
<bool>false</bool>
|
||||
</property>
|
||||
<property name="geometry">
|
||||
<rect>
|
||||
<x>310</x>
|
||||
<y>250</y>
|
||||
<width>100</width>
|
||||
<height>120</height>
|
||||
</rect>
|
||||
</property>
|
||||
<property name="font">
|
||||
<font>
|
||||
<pointsize>10</pointsize>
|
||||
</font>
|
||||
</property>
|
||||
<property name="toolTip">
|
||||
<string>CCPM Helicopters</string>
|
||||
</property>
|
||||
<property name="styleSheet">
|
||||
<string notr="true">QToolButton { border: none }</string>
|
||||
</property>
|
||||
<property name="text">
|
||||
<string>Helicopter</string>
|
||||
</property>
|
||||
<property name="icon">
|
||||
<iconset resource="../wizardResources.qrc">
|
||||
<normaloff>:/setupwizard/resources/bttn-heli-up.png</normaloff>
|
||||
<normalon>:/setupwizard/resources/bttn-heli-down.png</normalon>:/setupwizard/resources/bttn-heli-up.png</iconset>
|
||||
</property>
|
||||
<property name="iconSize">
|
||||
<size>
|
||||
<width>100</width>
|
||||
<height>100</height>
|
||||
</size>
|
||||
</property>
|
||||
<property name="checkable">
|
||||
<bool>true</bool>
|
||||
</property>
|
||||
<property name="autoExclusive">
|
||||
<bool>true</bool>
|
||||
</property>
|
||||
<property name="toolButtonStyle">
|
||||
<enum>Qt::ToolButtonTextUnderIcon</enum>
|
||||
</property>
|
||||
<property name="autoRaise">
|
||||
<bool>true</bool>
|
||||
</property>
|
||||
</widget>
|
||||
</widget>
|
||||
<resources>
|
||||
<include location="../wizardResources.qrc"/>
|
||||
</resources>
|
||||
<connections/>
|
||||
</ui>
|
After Width: | Height: | Size: 5.1 KiB |
After Width: | Height: | Size: 5.9 KiB |
After Width: | Height: | Size: 5.6 KiB |
After Width: | Height: | Size: 8.0 KiB |
After Width: | Height: | Size: 3.4 KiB |
After Width: | Height: | Size: 3.4 KiB |
After Width: | Height: | Size: 4.1 KiB |
After Width: | Height: | Size: 6.5 KiB |
After Width: | Height: | Size: 8.2 KiB |
After Width: | Height: | Size: 3.9 KiB |
After Width: | Height: | Size: 3.7 KiB |
After Width: | Height: | Size: 4.7 KiB |
After Width: | Height: | Size: 6.5 KiB |
After Width: | Height: | Size: 5.8 KiB |
After Width: | Height: | Size: 7.7 KiB |
After Width: | Height: | Size: 3.8 KiB |
After Width: | Height: | Size: 3.8 KiB |
After Width: | Height: | Size: 4.7 KiB |
After Width: | Height: | Size: 4.4 KiB |
After Width: | Height: | Size: 5.1 KiB |
After Width: | Height: | Size: 4.6 KiB |
After Width: | Height: | Size: 5.2 KiB |
After Width: | Height: | Size: 3.7 KiB |
After Width: | Height: | Size: 4.4 KiB |
After Width: | Height: | Size: 4.3 KiB |