mirror of
https://bitbucket.org/librepilot/librepilot.git
synced 2025-01-29 14:52:12 +01:00
OP-39 Fiddling around with connection diagram.
Updated some GUI. Started on motor calibration function.
This commit is contained in:
parent
4d701a2f7a
commit
66534ae91c
@ -31,31 +31,142 @@
|
||||
#include "ui_connectiondiagram.h"
|
||||
|
||||
ConnectionDiagram::ConnectionDiagram(QWidget *parent, VehicleConfigurationSource* configSource) :
|
||||
QDialog(parent), m_configSource(configSource),
|
||||
ui(new Ui::ConnectionDiagram)
|
||||
QDialog(parent), ui(new Ui::ConnectionDiagram), m_configSource(configSource), m_background(0)
|
||||
{
|
||||
setWindowTitle(tr("Connection Diagram"));
|
||||
ui->setupUi(this);
|
||||
|
||||
QGraphicsScene *scene = new QGraphicsScene(this);
|
||||
ui->connectionDiagram->setScene(scene);
|
||||
ui->connectionDiagram->setViewportUpdateMode(QGraphicsView::FullViewportUpdate);
|
||||
m_renderer = new QSvgRenderer();
|
||||
if (m_renderer->load(QString(":/setupwizard/resources/connection-diagrams.svg")) && m_renderer->isValid())
|
||||
{
|
||||
scene->clear();
|
||||
QGraphicsSvgItem* ccPic = new QGraphicsSvgItem();
|
||||
ccPic->setSharedRenderer(m_renderer);
|
||||
ccPic->setElementId("cc");
|
||||
scene->addItem(ccPic);
|
||||
qDebug() << "Scene complete";
|
||||
|
||||
//ui->connectionDiagram->setSceneRect(ccPic->boundingRect());
|
||||
//ui->connectionDiagram->fitInView(ccPic, Qt::KeepAspectRatio);
|
||||
}
|
||||
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()
|
||||
{
|
||||
QGraphicsScene *scene = new QGraphicsScene(this);
|
||||
ui->connectionDiagram->setScene(scene);
|
||||
ui->connectionDiagram->setViewportUpdateMode(QGraphicsView::FullViewportUpdate);
|
||||
m_renderer = new QSvgRenderer();
|
||||
if (QFile::exists(QString(":/setupwizard/resources/connection-diagrams.svg")) &&
|
||||
m_renderer->load(QString(":/setupwizard/resources/connection-diagrams.svg")) &&
|
||||
m_renderer->isValid())
|
||||
{
|
||||
scene->clear();
|
||||
m_background = new QGraphicsSvgItem();
|
||||
m_background->setSharedRenderer(m_renderer);
|
||||
m_background->setElementId("background");
|
||||
m_background->setVisible(true);
|
||||
m_background->setFlags(QGraphicsItem::ItemClipsChildrenToShape | QGraphicsItem::ItemClipsToShape);
|
||||
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" << "receiver" ;
|
||||
break;
|
||||
case VehicleConfigurationSource::INPUT_PPM:
|
||||
elementsToShow << "receiver" << "ppm";
|
||||
break;
|
||||
case VehicleConfigurationSource::INPUT_SBUS:
|
||||
elementsToShow << "sbus";
|
||||
break;
|
||||
case VehicleConfigurationSource::INPUT_DSM:
|
||||
elementsToShow << "satellite";
|
||||
break;
|
||||
default:
|
||||
break;
|
||||
}
|
||||
|
||||
setupGraphicsSceneItems(scene, elementsToShow);
|
||||
|
||||
ui->connectionDiagram->setSceneRect(m_background->boundingRect());
|
||||
ui->connectionDiagram->fitInView(m_background, Qt::KeepAspectRatio);
|
||||
|
||||
qDebug() << "Scene complete";
|
||||
}
|
||||
}
|
||||
|
||||
void ConnectionDiagram::setupGraphicsSceneItems(QGraphicsScene *scene, QList<QString> elementsToShow)
|
||||
{
|
||||
foreach(QString elementId, elementsToShow) {
|
||||
if(m_renderer->elementExists(elementId)) {
|
||||
QGraphicsSvgItem* element = new QGraphicsSvgItem();
|
||||
element->setSharedRenderer(m_renderer);
|
||||
element->setElementId(elementId);
|
||||
element->setVisible(true);
|
||||
scene->addItem(element);
|
||||
|
||||
QMatrix matrix = m_renderer->matrixForElement(elementId);
|
||||
QRectF orig = matrix.mapRect(m_renderer->boundsOnElement(elementId));
|
||||
element->setPos(orig.x(),orig.y());
|
||||
qDebug() << "Adding " << elementId << " to scene at " << element->pos();
|
||||
}
|
||||
else
|
||||
{
|
||||
qDebug() << "Element " << elementId << " not found in renderer!";
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
|
@ -53,8 +53,14 @@ private:
|
||||
VehicleConfigurationSource *m_configSource;
|
||||
|
||||
QSvgRenderer *m_renderer;
|
||||
QHash<QString, QGraphicsSvgItem> m_vehicleImageMap;
|
||||
QHash<QString, QGraphicsSvgItem> m_receiverImageMap;
|
||||
QGraphicsSvgItem* m_background;
|
||||
|
||||
void setupGraphicsScene();
|
||||
void setupGraphicsSceneItems(QGraphicsScene *scene, QList<QString> elementsToShow);
|
||||
protected:
|
||||
void resizeEvent(QResizeEvent *event);
|
||||
void showEvent(QShowEvent *event);
|
||||
|
||||
};
|
||||
|
||||
#endif // CONNECTIONDIAGRAM_H
|
||||
|
@ -31,6 +31,15 @@
|
||||
<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>
|
||||
|
@ -52,6 +52,9 @@ p, li { white-space: pre-wrap; }
|
||||
<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>
|
||||
|
@ -55,7 +55,7 @@ p, li { white-space: pre-wrap; }
|
||||
</font>
|
||||
</property>
|
||||
<property name="toolTip">
|
||||
<string>Airplane, Sloper, Jet</string>
|
||||
<string>Spectrum Satellite</string>
|
||||
</property>
|
||||
<property name="styleSheet">
|
||||
<string notr="true">QToolButton { border: none }</string>
|
||||
@ -102,7 +102,7 @@ p, li { white-space: pre-wrap; }
|
||||
</font>
|
||||
</property>
|
||||
<property name="toolTip">
|
||||
<string>Tricopter, Quadcopter, Hexacopter, Octocopter</string>
|
||||
<string>PWM - One cable per channel</string>
|
||||
</property>
|
||||
<property name="styleSheet">
|
||||
<string notr="true">QToolButton { border: none }</string>
|
||||
@ -152,7 +152,7 @@ p, li { white-space: pre-wrap; }
|
||||
</font>
|
||||
</property>
|
||||
<property name="toolTip">
|
||||
<string>Airplane, Sloper, Jet</string>
|
||||
<string>PPM - One cable for all channels</string>
|
||||
</property>
|
||||
<property name="styleSheet">
|
||||
<string notr="true">QToolButton { border: none }</string>
|
||||
@ -199,7 +199,7 @@ p, li { white-space: pre-wrap; }
|
||||
</font>
|
||||
</property>
|
||||
<property name="toolTip">
|
||||
<string>Airplane, Sloper, Jet</string>
|
||||
<string>Futaba S-BUS</string>
|
||||
</property>
|
||||
<property name="styleSheet">
|
||||
<string notr="true">QToolButton { border: none }</string>
|
||||
|
@ -69,6 +69,10 @@ void LevellingPage::performLevelling()
|
||||
return;
|
||||
}
|
||||
|
||||
getWizard()->button(QWizard::CancelButton)->setEnabled(false);
|
||||
getWizard()->button(QWizard::BackButton)->setEnabled(false);
|
||||
ui->levelButton->setEnabled(false);
|
||||
|
||||
if(!m_levellingUtil)
|
||||
{
|
||||
// Measure every 100ms * 100times = 10s
|
||||
@ -79,9 +83,6 @@ void LevellingPage::performLevelling()
|
||||
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)));
|
||||
getWizard()->button(QWizard::CancelButton)->setEnabled(false);
|
||||
getWizard()->button(QWizard::BackButton)->setEnabled(false);
|
||||
ui->levelButton->setEnabled(false);
|
||||
|
||||
m_levellingUtil->start();
|
||||
}
|
||||
|
@ -49,6 +49,9 @@ p, li { white-space: pre-wrap; }
|
||||
<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>
|
||||
|
@ -65,6 +65,7 @@ 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()
|
||||
@ -94,6 +95,8 @@ void MultiPage::setupMultiTypesCombo()
|
||||
ui->typeCombo->addItem(tr("Hexacopter H"), 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");
|
||||
|
||||
@ -105,15 +108,18 @@ void MultiPage::setupMultiTypesCombo()
|
||||
|
||||
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()
|
||||
|
@ -26,13 +26,12 @@
|
||||
<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;">
|
||||
</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;"></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 with 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 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;"></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>
|
||||
<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;">(Depending on input configuration all types may not be available to select from the list.)</span></p></body></html></string>
|
||||
<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>
|
||||
|
@ -55,7 +55,7 @@ p, li { white-space: pre-wrap; }
|
||||
</font>
|
||||
</property>
|
||||
<property name="toolTip">
|
||||
<string>Airplane, Sloper, Jet</string>
|
||||
<string>Turbo PWM ESC 400Hz</string>
|
||||
</property>
|
||||
<property name="styleSheet">
|
||||
<string notr="true">QToolButton { border: none }</string>
|
||||
@ -65,8 +65,8 @@ p, li { white-space: pre-wrap; }
|
||||
</property>
|
||||
<property name="icon">
|
||||
<iconset resource="../wizardResources.qrc">
|
||||
<normaloff>:/setupwizard/resources/bttn-turbo-down.png</normaloff>
|
||||
<normalon>:/setupwizard/resources/bttn-turbo-up.png</normalon>:/setupwizard/resources/bttn-turbo-down.png</iconset>
|
||||
<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>
|
||||
@ -105,7 +105,7 @@ p, li { white-space: pre-wrap; }
|
||||
</font>
|
||||
</property>
|
||||
<property name="toolTip">
|
||||
<string>Tricopter, Quadcopter, Hexacopter, Octocopter</string>
|
||||
<string>Standard ESC 50Hz</string>
|
||||
</property>
|
||||
<property name="styleSheet">
|
||||
<string notr="true">QToolButton { border: none }</string>
|
||||
|
@ -24,7 +24,7 @@
|
||||
<rect>
|
||||
<x>20</x>
|
||||
<y>20</y>
|
||||
<width>550</width>
|
||||
<width>581</width>
|
||||
<height>350</height>
|
||||
</rect>
|
||||
</property>
|
||||
@ -32,15 +32,21 @@
|
||||
<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;">
|
||||
</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; font-size:8pt;"></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 of setting up your OpenPilot controller board. The following pages contains simple questions about your vehicle and its characteristics. </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;">From the information gathered the wizard will create a baseline configuration that should be good enough for you to get a quick start using your OpenPilot product.</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;">The baseline configuration can, if desired, be uploaded to the OpenPilot Controller board at the end 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;"></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 contain the full range of settings available in the GCS Config plugin. All configuration parameters can be changed at later by using the GCS Config 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;"></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 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;">REMOVE ALL PROPELLERS FROM THE VEHICHLE </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;">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-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;">Ignoring the above request will put you in a</span><span style=" font-size:10pt; font-weight:600; color:#ff0000;"> risk of 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;">Ok, lets start the configuration by clicking on the 'Next'/'Continue' button below.</span></p></body></html></string>
|
||||
</property>
|
||||
<property name="alignment">
|
||||
|
@ -51,7 +51,7 @@ p, li { white-space: pre-wrap; }
|
||||
</rect>
|
||||
</property>
|
||||
<property name="toolTip">
|
||||
<string>Tricopter, Quadcopter, Hexacopter, Octocopter</string>
|
||||
<string>Show connection diagram for configuration</string>
|
||||
</property>
|
||||
<property name="text">
|
||||
<string>Hardware
|
||||
|
File diff suppressed because one or more lines are too long
Before Width: | Height: | Size: 605 KiB After Width: | Height: | Size: 676 KiB |
@ -59,9 +59,12 @@ public:
|
||||
SetupWizard::ESC_TYPE getESCType() const { return m_escType; }
|
||||
|
||||
void setLevellingBias(accelGyroBias bias) { m_levellingBias = bias; m_levellingPerformed = true; }
|
||||
bool isLevellingPerformed() { return m_levellingPerformed; }
|
||||
bool isLevellingPerformed() const { return m_levellingPerformed; }
|
||||
accelGyroBias getLevellingBias() const { return m_levellingBias; }
|
||||
|
||||
void setActuatorNeutralSettings(QList<quint16> neutralSettings) { m_actuatorNeutralConfig = neutralSettings; }
|
||||
bool isMotorCalibrationPerformed() const { return m_motorCalibrationPerformed; }
|
||||
QList<quint16> getActuatorNeutralSettings() const { return m_actuatorNeutralConfig; }
|
||||
|
||||
QString getSummaryText();
|
||||
|
||||
@ -87,6 +90,9 @@ private:
|
||||
bool m_levellingPerformed;
|
||||
accelGyroBias m_levellingBias;
|
||||
|
||||
bool m_motorCalibrationPerformed;
|
||||
QList<quint16> m_actuatorNeutralConfig;
|
||||
|
||||
Core::ConnectionManager *m_connectionManager;
|
||||
};
|
||||
|
||||
|
@ -59,7 +59,7 @@ bool VehicleConfigurationHelper::setupVehicle()
|
||||
|
||||
applyHardwareConfiguration();
|
||||
applyVehicleConfiguration();
|
||||
applyOutputConfiguration();
|
||||
applyActuatorConfiguration();
|
||||
applyFlighModeConfiguration();
|
||||
applyLevellingConfiguration();
|
||||
applyStabilizationConfiguration();
|
||||
@ -174,7 +174,7 @@ void VehicleConfigurationHelper::applyVehicleConfiguration()
|
||||
}
|
||||
}
|
||||
|
||||
void VehicleConfigurationHelper::applyOutputConfiguration()
|
||||
void VehicleConfigurationHelper::applyActuatorConfiguration()
|
||||
{
|
||||
ActuatorSettings* actSettings = ActuatorSettings::GetInstance(m_uavoManager);
|
||||
switch(m_configSource->getVehicleType())
|
||||
@ -183,10 +183,19 @@ void VehicleConfigurationHelper::applyOutputConfiguration()
|
||||
{
|
||||
ActuatorSettings::DataFields data = actSettings->getData();
|
||||
|
||||
data.ChannelUpdateFreq[0] = LEGACY_ESC_FREQUENCE;
|
||||
data.ChannelUpdateFreq[1] = LEGACY_ESC_FREQUENCE;
|
||||
data.ChannelUpdateFreq[3] = LEGACY_ESC_FREQUENCE;
|
||||
data.ChannelUpdateFreq[4] = LEGACY_ESC_FREQUENCE;
|
||||
|
||||
for(quint16 i = 0; i < ActuatorSettings::CHANNELUPDATEFREQ_NUMELEM; i++) {
|
||||
data.ChannelUpdateFreq[i] = LEGACY_ESC_FREQUENCE;
|
||||
}
|
||||
|
||||
for(quint16 i = 0; i < ActuatorSettings::CHANNELMAX_NUMELEM; i++) {
|
||||
data.ChannelType[i] = ActuatorSettings::CHANNELTYPE_PWM;
|
||||
data.ChannelAddr[i] = i;
|
||||
data.ChannelMin[i] = ACTUATOR_MIN;
|
||||
data.ChannelNeutral[i] = ACTUATOR_MIN;
|
||||
data.ChannelMax[i] = ACTUATOR_MAX;
|
||||
}
|
||||
|
||||
data.MotorsSpinWhileArmed = ActuatorSettings::MOTORSSPINWHILEARMED_FALSE;
|
||||
|
||||
qint16 updateFrequence = LEGACY_ESC_FREQUENCE;
|
||||
|
@ -68,6 +68,9 @@ private:
|
||||
static const qint16 LEGACY_ESC_FREQUENCE = 50;
|
||||
static const qint16 RAPID_ESC_FREQUENCE = 400;
|
||||
|
||||
static const qint16 ACTUATOR_MIN = 1000;
|
||||
static const qint16 ACTUATOR_MAX = 2000;
|
||||
|
||||
static const int MIXER_TYPE_DISABLED = 0;
|
||||
static const int MIXER_TYPE_MOTOR = 1;
|
||||
static const int MIXER_TYPE_SERVO = 2;
|
||||
@ -83,7 +86,7 @@ private:
|
||||
|
||||
void applyHardwareConfiguration();
|
||||
void applyVehicleConfiguration();
|
||||
void applyOutputConfiguration();
|
||||
void applyActuatorConfiguration();
|
||||
void applyFlighModeConfiguration();
|
||||
void applyLevellingConfiguration();
|
||||
void applyStabilizationConfiguration();
|
||||
|
@ -60,11 +60,13 @@ public:
|
||||
virtual VehicleConfigurationSource::INPUT_TYPE getInputType() const = 0;
|
||||
virtual VehicleConfigurationSource::ESC_TYPE getESCType() const = 0;
|
||||
|
||||
virtual bool isLevellingPerformed() = 0;
|
||||
virtual bool isLevellingPerformed() const = 0;
|
||||
virtual accelGyroBias getLevellingBias() const = 0;
|
||||
|
||||
virtual QString getSummaryText() = 0;
|
||||
virtual bool isMotorCalibrationPerformed() const = 0;
|
||||
virtual QList<quint16> getActuatorNeutralSettings() const = 0;
|
||||
|
||||
virtual QString getSummaryText() = 0;
|
||||
};
|
||||
|
||||
#endif // VEHICLECONFIGURATIONSOURCE_H
|
||||
|
Loading…
x
Reference in New Issue
Block a user